Go to the documentation of this file.
26 #ifndef TESSERACT_KINEMATICS_KDL_FWD_KINEMATIC_CHAIN_H
27 #define TESSERACT_KINEMATICS_KDL_FWD_KINEMATIC_CHAIN_H
31 #include <kdl/chainfksolverpos_recursive.hpp>
32 #include <kdl/chainjnttojacsolver.hpp>
53 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
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>;
76 const std::string& base_link,
77 const std::string& tip_link,
88 const std::vector<std::pair<std::string, std::string> >& chains,
93 Eigen::MatrixXd
calcJacobian(
const Eigen::Ref<const Eigen::VectorXd>& joint_angles,
94 const std::string& joint_link_name)
const override final;
97 std::vector<std::
string>
getJointNames() const override final;
99 Eigen::Index
numJoints() const override final;
116 const Eigen::Ref<const Eigen::VectorXd>& joint_angles,
117 int segment_num = -1)
const;
122 #endif // TESSERACT_KDL_KINEMATIC_CHAIN_H
tesseract_common::TransformMap calcFwdKinHelperAll(const Eigen::Ref< const Eigen::VectorXd > &joint_angles) const
calcFwdKin helper function
Forward kinematics functions.
KDLFwdKinChain & operator=(const KDLFwdKinChain &other)
std::shared_ptr< const ForwardKinematics > ConstPtr
~KDLFwdKinChain() override=default
std::string getBaseLinkName() const override final
Get the robot base link name.
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
std::unique_ptr< KDL::ChainFkSolverPos_recursive > fk_solver_
std::string getSolverName() const override final
Get the name of the solver. Recommend using the name of the class.
std::mutex mutex_
KDL is not thread safe due to mutable variables in Joint Class.
std::string solver_name_
Name of this solver.
std::vector< std::string > getTipLinkNames() const override final
Get list of tip link names for kinematic object.
KDLFwdKinChain(const KDLFwdKinChain &other)
KDL kinematic chain implementation.
static const std::string KDL_FWD_KIN_CHAIN_SOLVER_NAME
Forward kinematics functions.
ForwardKinematics::UPtr clone() const override final
Clone the forward kinematics object.
std::vector< std::string > getJointNames() const override final
Get list of joint names for kinematic object.
#define TESSERACT_COMMON_IGNORE_WARNINGS_POP
std::unique_ptr< const ForwardKinematics > ConstUPtr
std::unique_ptr< ForwardKinematics > UPtr
Tesseract KDL utility functions.
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.
std::shared_ptr< ForwardKinematics > Ptr
bool calcJacobianHelper(KDL::Jacobian &jacobian, const Eigen::Ref< const Eigen::VectorXd > &joint_angles, int segment_num=-1) const
calcJacobian helper function
std::unique_ptr< KDL::ChainJntToJacSolver > jac_solver_
Eigen::Index numJoints() const override final
Number of joints in robot.
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.