Go to the documentation of this file.
26 #ifndef TESSERACT_KINEMATICS_IKFAST_INV_KIN_H
27 #define TESSERACT_KINEMATICS_IKFAST_INV_KIN_H
81 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
84 using Ptr = std::shared_ptr<IKFastInvKin>;
85 using ConstPtr = std::shared_ptr<const IKFastInvKin>;
86 using UPtr = std::unique_ptr<IKFastInvKin>;
87 using ConstUPtr = std::unique_ptr<const IKFastInvKin>;
103 std::string tip_link_name,
104 std::vector<std::string> joint_names,
106 std::vector<std::vector<double>> free_joint_states = {});
109 const Eigen::Ref<const Eigen::VectorXd>& seed)
const override;
127 static std::vector<std::vector<double>>
142 #endif // TESSERACT_KINEMATICS_IKFAST_INV_KIN_H
IKFast Inverse Kinematics Implmentation.
InverseKinematics::UPtr clone() const override
Clone the forward kinematics object.
std::vector< std::string > joint_names_
Joint names for the kinematic object.
std::string getSolverName() const override
Get the name of the solver. Recommend using the name of the class.
std::string getWorkingFrame() const override
Get the inverse kinematics working frame.
static std::vector< std::vector< double > > generateAllFreeJointStateCombinations(const std::vector< std::vector< double >> &free_joint_samples)
Generates all possible combinations of joint states and stores it to the free_joint_states_ class mem...
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
~IKFastInvKin() override=default
std::unique_ptr< const InverseKinematics > ConstUPtr
std::shared_ptr< const InverseKinematics > ConstPtr
Inverse kinematics functions.
IKFastInvKin(const IKFastInvKin &other)
Eigen::Index numJoints() const override
Number of joints in robot.
std::string base_link_name_
Link name of first link in the kinematic object.
std::unique_ptr< InverseKinematics > UPtr
IKSolutions calcInvKin(const tesseract_common::TransformMap &tip_link_poses, const Eigen::Ref< const Eigen::VectorXd > &seed) const override
Calculates joint solutions given a pose for each tip link.
std::string tip_link_name_
Link name of last kink in the kinematic object.
std::vector< std::string > getTipLinkNames() const override
Get the names of the tip links of the kinematics group.
Inverse kinematics functions.
std::vector< std::string > getJointNames() const override
Get list of joint names for kinematic object.
std::shared_ptr< InverseKinematics > Ptr
std::string getBaseLinkName() const override
Get the robot base link name.
IKFastInvKin & operator=(const IKFastInvKin &other)
std::string solver_name_
Name of this solver.
std::vector< Eigen::VectorXd > IKSolutions
The inverse kinematics solutions container.
static const std::string IKFAST_INV_KIN_CHAIN_SOLVER_NAME
std::vector< std::vector< double > > free_joint_states_