kdl_inv_kin_chain_nr.h
Go to the documentation of this file.
1 
26 #ifndef TESSERACT_KINEMATICS_KDL_INV_KIN_CHAIN_NR_H
27 #define TESSERACT_KINEMATICS_KDL_INV_KIN_CHAIN_NR_H
30 #include <kdl/chainiksolverpos_nr.hpp>
31 #include <kdl/chainiksolvervel_pinv.hpp>
32 #include <kdl/chainfksolverpos_recursive.hpp>
33 #include <mutex>
35 
38 
39 namespace tesseract_kinematics
40 {
41 static const std::string KDL_INV_KIN_CHAIN_NR_SOLVER_NAME = "KDLInvKinChainNR";
42 
47 {
48 public:
49  // LCOV_EXCL_START
50  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
51  // LCOV_EXCL_STOP
52 
53  using Ptr = std::shared_ptr<KDLInvKinChainNR>;
54  using ConstPtr = std::shared_ptr<const KDLInvKinChainNR>;
55  using UPtr = std::unique_ptr<KDLInvKinChainNR>;
56  using ConstUPtr = std::unique_ptr<const KDLInvKinChainNR>;
57 
67  struct Config
68  {
69  double vel_eps{ 0.00001 };
70  int vel_iterations{ 150 };
71  double pos_eps{ 1e-6 };
72  int pos_iterations{ 100 };
73  };
74 
75  ~KDLInvKinChainNR() override = default;
76  KDLInvKinChainNR(const KDLInvKinChainNR& other);
80 
90  const std::string& base_link,
91  const std::string& tip_link,
92  Config kdl_config,
93  std::string solver_name = KDL_INV_KIN_CHAIN_NR_SOLVER_NAME);
94 
103  const std::vector<std::pair<std::string, std::string> >& chains,
104  Config kdl_config,
105  std::string solver_name = KDL_INV_KIN_CHAIN_NR_SOLVER_NAME);
106 
108  const Eigen::Ref<const Eigen::VectorXd>& seed) const override final;
109 
110  std::vector<std::string> getJointNames() const override final;
111  Eigen::Index numJoints() const override final;
112  std::string getBaseLinkName() const override final;
113  std::string getWorkingFrame() const override final;
114  std::vector<std::string> getTipLinkNames() const override final;
115  std::string getSolverName() const override final;
116  InverseKinematics::UPtr clone() const override final;
117 
118 private:
121  std::unique_ptr<KDL::ChainFkSolverPos_recursive> fk_solver_;
122  std::unique_ptr<KDL::ChainIkSolverVel_pinv> ik_vel_solver_;
123  std::unique_ptr<KDL::ChainIkSolverPos_NR> ik_solver_;
125  mutable std::mutex mutex_;
128  IKSolutions calcInvKinHelper(const Eigen::Isometry3d& pose,
129  const Eigen::Ref<const Eigen::VectorXd>& seed,
130  int segment_num = -1) const;
131 };
132 
133 } // namespace tesseract_kinematics
134 #endif // TESSERACT_KINEMATICS_KDL_INV_KIN_CHAIN_NR_H
tesseract_kinematics::KDLInvKinChainNR::kdl_data_
KDLChainData kdl_data_
KDL data parsed from Scene Graph.
Definition: kdl_inv_kin_chain_nr.h:119
tesseract_kinematics::KDLChainData
The KDLChainData struct.
Definition: kdl_utils.h:91
tesseract_kinematics::KDLInvKinChainNR::fk_solver_
std::unique_ptr< KDL::ChainFkSolverPos_recursive > fk_solver_
KDL Forward Kinematic Solver.
Definition: kdl_inv_kin_chain_nr.h:121
tesseract_kinematics::KDLInvKinChainNR::ik_solver_
std::unique_ptr< KDL::ChainIkSolverPos_NR > ik_solver_
KDL Inverse kinematic solver.
Definition: kdl_inv_kin_chain_nr.h:123
tesseract_kinematics::KDLInvKinChainNR::Config::pos_iterations
int pos_iterations
Definition: kdl_inv_kin_chain_nr.h:72
tesseract_kinematics::KDLInvKinChainNR::UPtr
std::unique_ptr< KDLInvKinChainNR > UPtr
Definition: kdl_inv_kin_chain_nr.h:55
tesseract_common::TransformMap
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
tesseract_kinematics::KDLInvKinChainNR::calcInvKinHelper
IKSolutions calcInvKinHelper(const Eigen::Isometry3d &pose, const Eigen::Ref< const Eigen::VectorXd > &seed, int segment_num=-1) const
calcFwdKin helper function
Definition: kdl_inv_kin_chain_nr.cpp:88
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_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
tesseract_kinematics::KDLInvKinChainNR::clone
InverseKinematics::UPtr clone() const override final
Clone the forward kinematics object.
Definition: kdl_inv_kin_chain_nr.cpp:70
tesseract_scene_graph::SceneGraph
tesseract_kinematics::KDLInvKinChainNR::ik_vel_solver_
std::unique_ptr< KDL::ChainIkSolverVel_pinv > ik_vel_solver_
KDL Inverse kinematic velocity solver.
Definition: kdl_inv_kin_chain_nr.h:122
tesseract_kinematics::KDLInvKinChainNR::getTipLinkNames
std::vector< std::string > getTipLinkNames() const override final
Get the names of the tip links of the kinematics group.
Definition: kdl_inv_kin_chain_nr.cpp:159
tesseract_kinematics::KDLInvKinChainNR::Config::vel_eps
double vel_eps
Definition: kdl_inv_kin_chain_nr.h:69
tesseract_kinematics::InverseKinematics::UPtr
std::unique_ptr< InverseKinematics > UPtr
Definition: inverse_kinematics.h:52
tesseract_kinematics::KDLInvKinChainNR::calcInvKin
IKSolutions calcInvKin(const tesseract_common::TransformMap &tip_link_poses, const Eigen::Ref< const Eigen::VectorXd > &seed) const override final
Calculates joint solutions given a pose for each tip link.
Definition: kdl_inv_kin_chain_nr.cpp:144
tesseract_kinematics::KDLInvKinChainNR::KDLInvKinChainNR
KDLInvKinChainNR(const KDLInvKinChainNR &other)
Definition: kdl_inv_kin_chain_nr.cpp:72
tesseract_kinematics::KDLInvKinChainNR::~KDLInvKinChainNR
~KDLInvKinChainNR() override=default
tesseract_kinematics::KDLInvKinChainNR::kdl_config_
Config kdl_config_
KDL configuration data parsed from YAML.
Definition: kdl_inv_kin_chain_nr.h:120
tesseract_kinematics::KDLInvKinChainNR::operator=
KDLInvKinChainNR & operator=(const KDLInvKinChainNR &other)
Definition: kdl_inv_kin_chain_nr.cpp:74
tesseract_kinematics::KDLInvKinChainNR::Config::vel_iterations
int vel_iterations
Definition: kdl_inv_kin_chain_nr.h:70
tesseract_kinematics::KDLInvKinChainNR::Config
The Config struct.
Definition: kdl_inv_kin_chain_nr.h:67
tesseract_kinematics::KDLInvKinChainNR::getWorkingFrame
std::string getWorkingFrame() const override final
Get the inverse kinematics working frame.
Definition: kdl_inv_kin_chain_nr.cpp:157
tesseract_kinematics::KDLInvKinChainNR::getSolverName
std::string getSolverName() const override final
Get the name of the solver. Recommend using the name of the class.
Definition: kdl_inv_kin_chain_nr.cpp:161
tesseract_kinematics::KDLInvKinChainNR::Config::pos_eps
double pos_eps
Definition: kdl_inv_kin_chain_nr.h:71
tesseract_kinematics::KDLInvKinChainNR::solver_name_
std::string solver_name_
Name of this solver.
Definition: kdl_inv_kin_chain_nr.h:124
tesseract_kinematics::InverseKinematics
Inverse kinematics functions.
Definition: inverse_kinematics.h:43
TESSERACT_COMMON_IGNORE_WARNINGS_POP
#define TESSERACT_COMMON_IGNORE_WARNINGS_POP
tesseract_kinematics::KDL_INV_KIN_CHAIN_NR_SOLVER_NAME
static const std::string KDL_INV_KIN_CHAIN_NR_SOLVER_NAME
Definition: kdl_inv_kin_chain_nr.h:41
tesseract_kinematics::KDLInvKinChainNR::getBaseLinkName
std::string getBaseLinkName() const override final
Get the robot base link name.
Definition: kdl_inv_kin_chain_nr.cpp:155
tesseract_kinematics::InverseKinematics::Ptr
std::shared_ptr< InverseKinematics > Ptr
Definition: inverse_kinematics.h:50
tesseract_kinematics
Definition: forward_kinematics.h:40
kdl_utils.h
Tesseract KDL utility functions.
tesseract_kinematics::KDLInvKinChainNR
KDL Inverse kinematic chain implementation.
Definition: kdl_inv_kin_chain_nr.h:46
tesseract_kinematics::IKSolutions
std::vector< Eigen::VectorXd > IKSolutions
The inverse kinematics solutions container.
Definition: types.h:38
macros.h
tesseract_kinematics::KDLInvKinChainNR::mutex_
std::mutex mutex_
KDL is not thread safe due to mutable variables in Joint Class.
Definition: kdl_inv_kin_chain_nr.h:125
tesseract_kinematics::KDLInvKinChainNR::getJointNames
std::vector< std::string > getJointNames() const override final
Get list of joint names for kinematic object.
Definition: kdl_inv_kin_chain_nr.cpp:151
tesseract_kinematics::KDLInvKinChainNR::numJoints
Eigen::Index numJoints() const override final
Number of joints in robot.
Definition: kdl_inv_kin_chain_nr.cpp:153


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