Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
kdl_inv_kin_chain_lma.h
Go to the documentation of this file.
1
26#ifndef TESSERACT_KINEMATICS_KDL_INV_KIN_CHAIN_LMA_H
27#define TESSERACT_KINEMATICS_KDL_INV_KIN_CHAIN_LMA_H
30#include <kdl/tree.hpp>
31#include <kdl/chain.hpp>
32#include <kdl/chainiksolverpos_lma.hpp>
33#include <unordered_map>
34#include <console_bridge/console.h>
35#include <mutex>
36
39
43
45{
46static const std::string KDL_INV_KIN_CHAIN_LMA_SOLVER_NAME = "KDLInvKinChainLMA";
47
52{
53public:
54 // LCOV_EXCL_START
55 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
56 // LCOV_EXCL_STOP
57
58 using Ptr = std::shared_ptr<KDLInvKinChainLMA>;
59 using ConstPtr = std::shared_ptr<const KDLInvKinChainLMA>;
60 using UPtr = std::unique_ptr<KDLInvKinChainLMA>;
61 using ConstUPtr = std::unique_ptr<const KDLInvKinChainLMA>;
62
63 ~KDLInvKinChainLMA() override = default;
68
78 const std::string& base_link,
79 const std::string& tip_link,
80 std::string solver_name = KDL_INV_KIN_CHAIN_LMA_SOLVER_NAME);
81
90 const std::vector<std::pair<std::string, std::string> >& chains,
91 std::string solver_name = KDL_INV_KIN_CHAIN_LMA_SOLVER_NAME);
92
94 const Eigen::Ref<const Eigen::VectorXd>& seed) const override final;
95
96 std::vector<std::string> getJointNames() const override final;
97 Eigen::Index numJoints() const override final;
98 std::string getBaseLinkName() const override final;
99 std::string getWorkingFrame() const override final;
100 std::vector<std::string> getTipLinkNames() const override final;
101 std::string getSolverName() const override final;
102 InverseKinematics::UPtr clone() const override final;
103
104private:
106 std::unique_ptr<KDL::ChainIkSolverPos_LMA> ik_solver_;
108 mutable std::mutex mutex_;
111 IKSolutions calcInvKinHelper(const Eigen::Isometry3d& pose,
112 const Eigen::Ref<const Eigen::VectorXd>& seed,
113 int segment_num = -1) const;
114};
115
116} // namespace tesseract_kinematics
117#endif // TESSERACT_KINEMATICS_KDL_INV_KIN_CHAIN_LMA_H
#define vector(a, b, c)
Definition: FloatMath.inl:3227
Inverse kinematics functions.
Definition: inverse_kinematics.h:47
KDL Inverse kinematic chain implementation.
Definition: kdl_inv_kin_chain_lma.h:52
std::vector< std::string > getTipLinkNames() const override final
Get the names of the tip links of the kinematics group.
Definition: kdl_inv_kin_chain_lma.cpp:139
KDLChainData kdl_data_
KDL data parsed from Scene Graph.
Definition: kdl_inv_kin_chain_lma.h:105
std::string getSolverName() const override final
Get the name of the solver. Recommend using the name of the class.
Definition: kdl_inv_kin_chain_lma.cpp:141
std::mutex mutex_
KDL is not thread safe due to mutable variables in Joint Class.
Definition: kdl_inv_kin_chain_lma.h:108
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_lma.cpp:78
std::shared_ptr< KDLInvKinChainLMA > Ptr
Definition: kdl_inv_kin_chain_lma.h:58
std::string getWorkingFrame() const override final
Get the inverse kinematics working frame.
Definition: kdl_inv_kin_chain_lma.cpp:137
KDLInvKinChainLMA & operator=(const KDLInvKinChainLMA &other)
Definition: kdl_inv_kin_chain_lma.cpp:69
Eigen::Index numJoints() const override final
Number of joints in robot.
Definition: kdl_inv_kin_chain_lma.cpp:133
InverseKinematics::UPtr clone() const override final
Clone the forward kinematics object.
Definition: kdl_inv_kin_chain_lma.cpp:65
std::string getBaseLinkName() const override final
Get the robot base link name.
Definition: kdl_inv_kin_chain_lma.cpp:135
std::vector< std::string > getJointNames() const override final
Get list of joint names for kinematic object.
Definition: kdl_inv_kin_chain_lma.cpp:131
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_lma.cpp:124
KDLInvKinChainLMA & operator=(KDLInvKinChainLMA &&)=delete
KDLInvKinChainLMA(KDLInvKinChainLMA &&)=delete
std::unique_ptr< KDLInvKinChainLMA > UPtr
Definition: kdl_inv_kin_chain_lma.h:60
std::unique_ptr< const KDLInvKinChainLMA > ConstUPtr
Definition: kdl_inv_kin_chain_lma.h:61
std::shared_ptr< const KDLInvKinChainLMA > ConstPtr
Definition: kdl_inv_kin_chain_lma.h:59
std::string solver_name_
Name of this solver.
Definition: kdl_inv_kin_chain_lma.h:107
std::unique_ptr< KDL::ChainIkSolverPos_LMA > ik_solver_
KDL Inverse kinematic solver.
Definition: kdl_inv_kin_chain_lma.h:106
Definition: graph.h:125
A basic scene graph using boost.
Eigen::VectorXd seed
Definition: ikfast_kinematics_7dof_unit.cpp:48
auto scene_graph
Definition: ikfast_kinematics_7dof_unit.cpp:51
Inverse kinematics functions.
Tesseract KDL utility functions.
Common Tesseract Macros.
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
Definition: macros.h:71
Definition: create_convex_hull.cpp:36
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
Definition: types.h:66
Definition: forward_kinematics.h:44
static const std::string KDL_INV_KIN_CHAIN_LMA_SOLVER_NAME
Definition: kdl_inv_kin_chain_lma.h:46
std::vector< Eigen::VectorXd > IKSolutions
The inverse kinematics solutions container.
Definition: types.h:41
The KDLChainData struct.
Definition: kdl_utils.h:95
auto pose
Definition: tesseract_environment_collision.cpp:118
Kinematics types.
Link base_link("base_link")