Go to the documentation of this file.
26 #ifndef TESSERACT_KINEMATICS_INVERSE_KINEMATICS_H
27 #define TESSERACT_KINEMATICS_INVERSE_KINEMATICS_H
47 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
50 using Ptr = std::shared_ptr<InverseKinematics>;
51 using ConstPtr = std::shared_ptr<const InverseKinematics>;
52 using UPtr = std::unique_ptr<InverseKinematics>;
53 using ConstUPtr = std::unique_ptr<const InverseKinematics>;
76 const Eigen::Ref<const Eigen::VectorXd>& seed)
const = 0;
88 virtual Eigen::Index
numJoints()
const = 0;
114 #endif // TESSERACT_KINEMATICS_INVERSE_KINEMATICS_H
virtual IKSolutions calcInvKin(const tesseract_common::TransformMap &tip_link_poses, const Eigen::Ref< const Eigen::VectorXd > &seed) const =0
Calculates joint solutions given a pose for each tip link.
InverseKinematics()=default
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
std::unique_ptr< const InverseKinematics > ConstUPtr
std::shared_ptr< const InverseKinematics > ConstPtr
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
virtual InverseKinematics::UPtr clone() const =0
Clone the forward kinematics object.
virtual std::vector< std::string > getJointNames() const =0
Get list of joint names for kinematic object.
std::unique_ptr< InverseKinematics > UPtr
InverseKinematics & operator=(const InverseKinematics &)=default
virtual std::string getWorkingFrame() const =0
Get the inverse kinematics working frame.
virtual std::string getBaseLinkName() const =0
Get the robot base link name.
virtual std::string getSolverName() const =0
Get the name of the solver. Recommend using the name of the class.
virtual ~InverseKinematics()
Inverse kinematics functions.
#define TESSERACT_COMMON_IGNORE_WARNINGS_POP
std::shared_ptr< InverseKinematics > Ptr
virtual std::vector< std::string > getTipLinkNames() const =0
Get the names of the tip links of the kinematics group.
std::vector< Eigen::VectorXd > IKSolutions
The inverse kinematics solutions container.
virtual Eigen::Index numJoints() const =0
Number of joints in robot.