Go to the documentation of this file.
26 #ifndef TESSERACT_KINEMATICS_KDL_INV_KIN_CHAIN_NR_JL_H
27 #define TESSERACT_KINEMATICS_KDL_INV_KIN_CHAIN_NR_JL_H
30 #include <kdl/chainiksolverpos_nr_jl.hpp>
31 #include <kdl/chainiksolvervel_pinv.hpp>
32 #include <kdl/chainfksolverpos_recursive.hpp>
50 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
53 using Ptr = std::shared_ptr<KDLInvKinChainNR_JL>;
54 using ConstPtr = std::shared_ptr<const KDLInvKinChainNR_JL>;
55 using UPtr = std::unique_ptr<KDLInvKinChainNR_JL>;
56 using ConstUPtr = std::unique_ptr<const KDLInvKinChainNR_JL>;
90 const std::string& base_link,
91 const std::string& tip_link,
103 const std::vector<std::pair<std::string, std::string> >& chains,
108 const Eigen::Ref<const Eigen::VectorXd>& seed)
const override final;
110 std::vector<std::string>
getJointNames() const override final;
111 Eigen::Index
numJoints() const override final;
129 const Eigen::Ref<const Eigen::VectorXd>& seed,
130 int segment_num = -1)
const;
134 #endif // TESSERACT_KINEMATICS_KDL_INV_KIN_CHAIN_NR_JL_H
static const std::string KDL_INV_KIN_CHAIN_NR_JL_SOLVER_NAME
std::unique_ptr< KDL::ChainIkSolverVel_pinv > ik_vel_solver_
KDL Inverse kinematic velocity solver.
Config kdl_config_
KDL configuration data parsed from YAML.
std::mutex mutex_
KDL is not thread safe due to mutable variables in Joint Class.
KDLInvKinChainNR_JL(const KDLInvKinChainNR_JL &other)
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
std::unique_ptr< const InverseKinematics > ConstUPtr
std::shared_ptr< const InverseKinematics > ConstPtr
Inverse kinematics functions.
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
KDLInvKinChainNR_JL & operator=(const KDLInvKinChainNR_JL &other)
std::string solver_name_
Name of this solver.
std::unique_ptr< InverseKinematics > UPtr
std::unique_ptr< KDLInvKinChainNR_JL > UPtr
std::vector< std::string > getJointNames() const override final
Get list of joint names for kinematic object.
std::unique_ptr< KDL::ChainIkSolverPos_NR_JL > ik_solver_
KDL Inverse kinematic solver.
Eigen::Index numJoints() const override final
Number of joints in robot.
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.
std::unique_ptr< KDL::ChainFkSolverPos_recursive > fk_solver_
KDL Forward Kinematic Solver.
~KDLInvKinChainNR_JL() override=default
KDLChainData kdl_data_
KDL data parsed from Scene Graph.
KDL Inverse kinematic chain implementation.
std::string getSolverName() const override final
Get the name of the solver. Recommend using the name of the class.
std::string getBaseLinkName() const override final
Get the robot base link name.
Inverse kinematics functions.
#define TESSERACT_COMMON_IGNORE_WARNINGS_POP
std::shared_ptr< InverseKinematics > Ptr
Tesseract KDL utility functions.
IKSolutions calcInvKinHelper(const Eigen::Isometry3d &pose, const Eigen::Ref< const Eigen::VectorXd > &seed, int segment_num=-1) const
calcFwdKin helper function
std::vector< Eigen::VectorXd > IKSolutions
The inverse kinematics solutions container.
std::vector< std::string > getTipLinkNames() const override final
Get the names of the tip links of the kinematics group.
InverseKinematics::UPtr clone() const override final
Clone the forward kinematics object.
std::string getWorkingFrame() const override final
Get the inverse kinematics working frame.