ikfast_inv_kin.h
Go to the documentation of this file.
1 
26 #ifndef TESSERACT_KINEMATICS_IKFAST_INV_KIN_H
27 #define TESSERACT_KINEMATICS_IKFAST_INV_KIN_H
28 
31 
32 namespace tesseract_kinematics
33 {
34 static const std::string IKFAST_INV_KIN_CHAIN_SOLVER_NAME = "IKFastInvKin";
35 
78 {
79 public:
80  // LCOV_EXCL_START
81  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
82  // LCOV_EXCL_STOP
83 
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>;
88 
89  ~IKFastInvKin() override = default;
90  IKFastInvKin(const IKFastInvKin& other);
91  IKFastInvKin& operator=(const IKFastInvKin& other);
92  IKFastInvKin(IKFastInvKin&&) = default;
93  IKFastInvKin& operator=(IKFastInvKin&&) = default;
94 
102  IKFastInvKin(std::string base_link_name,
103  std::string tip_link_name,
104  std::vector<std::string> joint_names,
105  std::string solver_name = IKFAST_INV_KIN_CHAIN_SOLVER_NAME,
106  std::vector<std::vector<double>> free_joint_states = {});
107 
109  const Eigen::Ref<const Eigen::VectorXd>& seed) const override;
110 
111  Eigen::Index numJoints() const override;
112  std::vector<std::string> getJointNames() const override;
113  std::string getBaseLinkName() const override;
114  std::string getWorkingFrame() const override;
115  std::vector<std::string> getTipLinkNames() const override;
116  std::string getSolverName() const override;
117  InverseKinematics::UPtr clone() const override;
118 
127  static std::vector<std::vector<double>>
128  generateAllFreeJointStateCombinations(const std::vector<std::vector<double>>& free_joint_samples);
129 
130 protected:
131  std::string base_link_name_;
132  std::string tip_link_name_;
133  std::vector<std::string> joint_names_;
137  std::vector<std::vector<double>> free_joint_states_;
138 };
139 
140 } // namespace tesseract_kinematics
141 
142 #endif // TESSERACT_KINEMATICS_IKFAST_INV_KIN_H
tesseract_kinematics::IKFastInvKin
IKFast Inverse Kinematics Implmentation.
Definition: ikfast_inv_kin.h:77
types.h
Kinematics types.
tesseract_kinematics::IKFastInvKin::clone
InverseKinematics::UPtr clone() const override
Clone the forward kinematics object.
Definition: ikfast_inv_kin.hpp:54
tesseract_kinematics::IKFastInvKin::joint_names_
std::vector< std::string > joint_names_
Joint names for the kinematic object.
Definition: ikfast_inv_kin.h:133
tesseract_kinematics::IKFastInvKin::getSolverName
std::string getSolverName() const override
Get the name of the solver. Recommend using the name of the class.
Definition: ikfast_inv_kin.hpp:147
tesseract_kinematics::IKFastInvKin::getWorkingFrame
std::string getWorkingFrame() const override
Get the inverse kinematics working frame.
Definition: ikfast_inv_kin.hpp:145
tesseract_kinematics::IKFastInvKin::generateAllFreeJointStateCombinations
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...
Definition: ikfast_inv_kin.hpp:150
tesseract_common::TransformMap
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
tesseract_kinematics::IKFastInvKin::~IKFastInvKin
~IKFastInvKin() override=default
tesseract_kinematics::InverseKinematics::ConstUPtr
std::unique_ptr< const InverseKinematics > ConstUPtr
Definition: inverse_kinematics.h:53
tesseract_kinematics::InverseKinematics::ConstPtr
std::shared_ptr< const InverseKinematics > ConstPtr
Definition: inverse_kinematics.h:51
inverse_kinematics.h
Inverse kinematics functions.
tesseract_kinematics::IKFastInvKin::IKFastInvKin
IKFastInvKin(const IKFastInvKin &other)
Definition: ikfast_inv_kin.hpp:56
tesseract_kinematics::IKFastInvKin::numJoints
Eigen::Index numJoints() const override
Number of joints in robot.
Definition: ikfast_inv_kin.hpp:142
tesseract_kinematics::IKFastInvKin::base_link_name_
std::string base_link_name_
Link name of first link in the kinematic object.
Definition: ikfast_inv_kin.h:131
tesseract_kinematics::InverseKinematics::UPtr
std::unique_ptr< InverseKinematics > UPtr
Definition: inverse_kinematics.h:52
tesseract_kinematics::IKFastInvKin::calcInvKin
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.
Definition: ikfast_inv_kin.hpp:69
tesseract_kinematics::IKFastInvKin::tip_link_name_
std::string tip_link_name_
Link name of last kink in the kinematic object.
Definition: ikfast_inv_kin.h:132
tesseract_kinematics::IKFastInvKin::getTipLinkNames
std::vector< std::string > getTipLinkNames() const override
Get the names of the tip links of the kinematics group.
Definition: ikfast_inv_kin.hpp:146
tesseract_kinematics::InverseKinematics
Inverse kinematics functions.
Definition: inverse_kinematics.h:43
tesseract_kinematics::IKFastInvKin::getJointNames
std::vector< std::string > getJointNames() const override
Get list of joint names for kinematic object.
Definition: ikfast_inv_kin.hpp:143
tesseract_kinematics::InverseKinematics::Ptr
std::shared_ptr< InverseKinematics > Ptr
Definition: inverse_kinematics.h:50
tesseract_kinematics
Definition: forward_kinematics.h:40
tesseract_kinematics::IKFastInvKin::getBaseLinkName
std::string getBaseLinkName() const override
Get the robot base link name.
Definition: ikfast_inv_kin.hpp:144
tesseract_kinematics::IKFastInvKin::operator=
IKFastInvKin & operator=(const IKFastInvKin &other)
Definition: ikfast_inv_kin.hpp:58
tesseract_kinematics::IKFastInvKin::solver_name_
std::string solver_name_
Name of this solver.
Definition: ikfast_inv_kin.h:134
tesseract_kinematics::IKSolutions
std::vector< Eigen::VectorXd > IKSolutions
The inverse kinematics solutions container.
Definition: types.h:38
tesseract_kinematics::IKFAST_INV_KIN_CHAIN_SOLVER_NAME
static const std::string IKFAST_INV_KIN_CHAIN_SOLVER_NAME
Definition: ikfast_inv_kin.h:34
tesseract_kinematics::IKFastInvKin::free_joint_states_
std::vector< std::vector< double > > free_joint_states_
Definition: ikfast_inv_kin.h:137


tesseract_kinematics
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:02:14