37 #ifndef PLANAR_MANIPULATOR_H_
38 #define PLANAR_MANIPULATOR_H_
41 #include <Eigen/Dense>
47 PlanarManipulator(
unsigned int numLinks,
double linkLength,
const std::pair<double, double> &origin = {0.0, 0.0});
51 const std::pair<double, double> &origin = {0.0, 0.0});
56 unsigned int getNumLinks()
const;
59 const Eigen::Affine2d &getBaseFrame()
const;
62 void setBaseFrame(
const Eigen::Affine2d &frame);
65 const std::vector<double> &getLinkLengths()
const;
68 void setBounds(
unsigned int link,
double low,
double high);
70 void setBounds(
const std::vector<double> &low,
const std::vector<double> &high);
73 bool hasBounds(
unsigned int link)
const;
75 void getBounds(
unsigned int link,
double &low,
double &high)
const;
77 const std::vector<double> &lowerBounds()
const;
79 const std::vector<double> &upperBounds()
const;
83 void FK(
const double *joints, std::vector<Eigen::Affine2d> &frames)
const;
84 void FK(
const std::vector<double> &joints, std::vector<Eigen::Affine2d> &frames)
const;
85 void FK(
const Eigen::VectorXd &joints, std::vector<Eigen::Affine2d> &frames)
const;
86 void FK(
const double *joints, Eigen::Affine2d &eeFrame)
const;
87 void FK(
const std::vector<double> &joints, Eigen::Affine2d &eeFrame)
const;
88 void FK(
const Eigen::VectorXd &joints, Eigen::Affine2d &eeFrame)
const;
93 bool IK(std::vector<double> &solution,
const Eigen::Affine2d &eeFrame)
const;
94 bool IK(std::vector<double> &solution,
const std::vector<double> &seed,
const Eigen::Affine2d &desiredFrame)
const;
99 bool FABRIK(std::vector<double> &solution,
const Eigen::Affine2d &eeFrame,
double xyTol = 1e-5,
100 double thetaTol = 1e-3)
const;
101 bool FABRIK(std::vector<double> &solution,
const std::vector<double> &seed,
const Eigen::Affine2d &desiredFrame,
102 double xyTol = 1e-5,
double thetaTol = 1e-3)
const;
105 void Jacobian(
const std::vector<double> &joints, Eigen::MatrixXd &jac)
const;
106 void Jacobian(
const Eigen::VectorXd &joints, Eigen::MatrixXd &jac)
const;
107 void Jacobian(
const double *joints, Eigen::MatrixXd &jac)
const;
110 static void frameToPose(
const Eigen::Affine2d &frame, Eigen::VectorXd &pose);
113 bool infeasible(
const Eigen::Affine2d &frame)
const;
116 unsigned int numLinks_;
118 std::vector<double> linkLengths_;
120 std::vector<bool> hasBounds_;
121 std::vector<double> lowerBounds_;
122 std::vector<double> upperBounds_;
125 Eigen::Affine2d baseFrame_;