kdl_fwd_kin_chain.h
Go to the documentation of this file.
1 
26 #ifndef TESSERACT_KINEMATICS_KDL_FWD_KINEMATIC_CHAIN_H
27 #define TESSERACT_KINEMATICS_KDL_FWD_KINEMATIC_CHAIN_H
28 
31 #include <kdl/chainfksolverpos_recursive.hpp>
32 #include <kdl/chainjnttojacsolver.hpp>
33 #include <mutex>
35 
38 
39 namespace tesseract_kinematics
40 {
41 static const std::string KDL_FWD_KIN_CHAIN_SOLVER_NAME = "KDLFwdKinChain";
42 
50 {
51 public:
52  // LCOV_EXCL_START
53  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
54  // LCOV_EXCL_STOP
55 
56  using Ptr = std::shared_ptr<KDLFwdKinChain>;
57  using ConstPtr = std::shared_ptr<const KDLFwdKinChain>;
58  using UPtr = std::unique_ptr<KDLFwdKinChain>;
59  using ConstUPtr = std::unique_ptr<const KDLFwdKinChain>;
60 
61  ~KDLFwdKinChain() override = default;
62  KDLFwdKinChain(const KDLFwdKinChain& other);
64  KDLFwdKinChain(KDLFwdKinChain&&) = delete;
66 
76  const std::string& base_link,
77  const std::string& tip_link,
78  std::string solver_name = KDL_FWD_KIN_CHAIN_SOLVER_NAME);
79 
88  const std::vector<std::pair<std::string, std::string> >& chains,
89  std::string solver_name = KDL_FWD_KIN_CHAIN_SOLVER_NAME);
90 
91  tesseract_common::TransformMap calcFwdKin(const Eigen::Ref<const Eigen::VectorXd>& joint_angles) const override final;
92 
93  Eigen::MatrixXd calcJacobian(const Eigen::Ref<const Eigen::VectorXd>& joint_angles,
94  const std::string& joint_link_name) const override final;
95 
96  std::string getBaseLinkName() const override final;
97  std::vector<std::string> getJointNames() const override final;
98  std::vector<std::string> getTipLinkNames() const override final;
99  Eigen::Index numJoints() const override final;
100  std::string getSolverName() const override final;
101  ForwardKinematics::UPtr clone() const override final;
102 
103 private:
105  std::string name_;
106  std::unique_ptr<KDL::ChainFkSolverPos_recursive> fk_solver_;
107  std::unique_ptr<KDL::ChainJntToJacSolver> jac_solver_;
109  mutable std::mutex mutex_;
112  tesseract_common::TransformMap calcFwdKinHelperAll(const Eigen::Ref<const Eigen::VectorXd>& joint_angles) const;
113 
115  bool calcJacobianHelper(KDL::Jacobian& jacobian,
116  const Eigen::Ref<const Eigen::VectorXd>& joint_angles,
117  int segment_num = -1) const;
118 
119 }; // class KDLKinematicChain
120 
121 } // namespace tesseract_kinematics
122 #endif // TESSERACT_KDL_KINEMATIC_CHAIN_H
tesseract_kinematics::KDLFwdKinChain::calcFwdKinHelperAll
tesseract_common::TransformMap calcFwdKinHelperAll(const Eigen::Ref< const Eigen::VectorXd > &joint_angles) const
calcFwdKin helper function
Definition: kdl_fwd_kin_chain.cpp:78
tesseract_kinematics::ForwardKinematics
Forward kinematics functions.
Definition: forward_kinematics.h:43
tesseract_kinematics::KDLChainData
The KDLChainData struct.
Definition: kdl_utils.h:91
tesseract_kinematics::KDLFwdKinChain::operator=
KDLFwdKinChain & operator=(const KDLFwdKinChain &other)
Definition: kdl_fwd_kin_chain.cpp:67
tesseract_kinematics::KDLFwdKinChain::kdl_data_
KDLChainData kdl_data_
Definition: kdl_fwd_kin_chain.h:104
tesseract_kinematics::ForwardKinematics::ConstPtr
std::shared_ptr< const ForwardKinematics > ConstPtr
Definition: forward_kinematics.h:51
tesseract_kinematics::KDLFwdKinChain::~KDLFwdKinChain
~KDLFwdKinChain() override=default
tesseract_kinematics::KDLFwdKinChain::getBaseLinkName
std::string getBaseLinkName() const override final
Get the robot base link name.
Definition: kdl_fwd_kin_chain.cpp:154
tesseract_common::TransformMap
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
tesseract_scene_graph::SceneGraph
tesseract_kinematics::KDLFwdKinChain::fk_solver_
std::unique_ptr< KDL::ChainFkSolverPos_recursive > fk_solver_
Definition: kdl_fwd_kin_chain.h:106
tesseract_kinematics::KDLFwdKinChain::getSolverName
std::string getSolverName() const override final
Get the name of the solver. Recommend using the name of the class.
Definition: kdl_fwd_kin_chain.cpp:158
tesseract_kinematics::KDLFwdKinChain::mutex_
std::mutex mutex_
KDL is not thread safe due to mutable variables in Joint Class.
Definition: kdl_fwd_kin_chain.h:109
tesseract_kinematics::KDLFwdKinChain::solver_name_
std::string solver_name_
Name of this solver.
Definition: kdl_fwd_kin_chain.h:108
tesseract_kinematics::KDLFwdKinChain::getTipLinkNames
std::vector< std::string > getTipLinkNames() const override final
Get list of tip link names for kinematic object.
Definition: kdl_fwd_kin_chain.cpp:156
tesseract_kinematics::KDLFwdKinChain::KDLFwdKinChain
KDLFwdKinChain(const KDLFwdKinChain &other)
Definition: kdl_fwd_kin_chain.cpp:66
tesseract_kinematics::KDLFwdKinChain
KDL kinematic chain implementation.
Definition: kdl_fwd_kin_chain.h:49
tesseract_kinematics::KDL_FWD_KIN_CHAIN_SOLVER_NAME
static const std::string KDL_FWD_KIN_CHAIN_SOLVER_NAME
Definition: kdl_fwd_kin_chain.h:41
forward_kinematics.h
Forward kinematics functions.
tesseract_kinematics::KDLFwdKinChain::clone
ForwardKinematics::UPtr clone() const override final
Clone the forward kinematics object.
Definition: kdl_fwd_kin_chain.cpp:64
tesseract_kinematics::KDLFwdKinChain::getJointNames
std::vector< std::string > getJointNames() const override final
Get list of joint names for kinematic object.
Definition: kdl_fwd_kin_chain.cpp:150
TESSERACT_COMMON_IGNORE_WARNINGS_POP
#define TESSERACT_COMMON_IGNORE_WARNINGS_POP
tesseract_kinematics::ForwardKinematics::ConstUPtr
std::unique_ptr< const ForwardKinematics > ConstUPtr
Definition: forward_kinematics.h:53
tesseract_kinematics::ForwardKinematics::UPtr
std::unique_ptr< ForwardKinematics > UPtr
Definition: forward_kinematics.h:52
tesseract_kinematics
Definition: forward_kinematics.h:40
kdl_utils.h
Tesseract KDL utility functions.
tesseract_kinematics::KDLFwdKinChain::calcJacobian
Eigen::MatrixXd calcJacobian(const Eigen::Ref< const Eigen::VectorXd > &joint_angles, const std::string &joint_link_name) const override final
Calculates the Jacobian matrix for a given joint state in the reference frame of the specified link.
Definition: kdl_fwd_kin_chain.cpp:132
tesseract_kinematics::ForwardKinematics::Ptr
std::shared_ptr< ForwardKinematics > Ptr
Definition: forward_kinematics.h:50
macros.h
tesseract_kinematics::KDLFwdKinChain::calcJacobianHelper
bool calcJacobianHelper(KDL::Jacobian &jacobian, const Eigen::Ref< const Eigen::VectorXd > &joint_angles, int segment_num=-1) const
calcJacobian helper function
Definition: kdl_fwd_kin_chain.cpp:108
tesseract_kinematics::KDLFwdKinChain::name_
std::string name_
Definition: kdl_fwd_kin_chain.h:105
tesseract_kinematics::KDLFwdKinChain::jac_solver_
std::unique_ptr< KDL::ChainJntToJacSolver > jac_solver_
Definition: kdl_fwd_kin_chain.h:107
tesseract_kinematics::KDLFwdKinChain::numJoints
Eigen::Index numJoints() const override final
Number of joints in robot.
Definition: kdl_fwd_kin_chain.cpp:152
tesseract_kinematics::KDLFwdKinChain::calcFwdKin
tesseract_common::TransformMap calcFwdKin(const Eigen::Ref< const Eigen::VectorXd > &joint_angles) const override final
Calculates the transform for each tip link in the kinematic group.
Definition: kdl_fwd_kin_chain.cpp:101


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