Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
kdl_state_solver.h
Go to the documentation of this file.
1
26#ifndef TESSERACT_STATE_SOLVER_KDL_STATE_SOLVER_H
27#define TESSERACT_STATE_SOLVER_KDL_STATE_SOLVER_H
28
31#include <kdl/tree.hpp>
32#include <kdl/jntarray.hpp>
33#include <kdl/treejnttojacsolver.hpp>
34#include <mutex>
36
39
41{
43{
44public:
45 using Ptr = std::shared_ptr<KDLStateSolver>;
46 using ConstPtr = std::shared_ptr<const KDLStateSolver>;
47 using UPtr = std::unique_ptr<KDLStateSolver>;
48 using ConstUPtr = std::unique_ptr<const KDLStateSolver>;
49
52 ~KDLStateSolver() override = default;
53 KDLStateSolver(const KDLStateSolver& other);
57
58 StateSolver::UPtr clone() const override;
59
60 void setState(const Eigen::Ref<const Eigen::VectorXd>& joint_values) override final;
61 void setState(const std::unordered_map<std::string, double>& joint_values) override final;
62 void setState(const std::vector<std::string>& joint_names,
63 const Eigen::Ref<const Eigen::VectorXd>& joint_values) override final;
64
65 SceneState getState(const Eigen::Ref<const Eigen::VectorXd>& joint_values) const override final;
66 SceneState getState(const std::unordered_map<std::string, double>& joint_values) const override final;
67 SceneState getState(const std::vector<std::string>& joint_names,
68 const Eigen::Ref<const Eigen::VectorXd>& joint_values) const override final;
69
70 SceneState getState() const override final;
71
72 SceneState getRandomState() const override final;
73
74 Eigen::MatrixXd getJacobian(const Eigen::Ref<const Eigen::VectorXd>& joint_values,
75 const std::string& link_name) const override final;
76
77 Eigen::MatrixXd getJacobian(const std::unordered_map<std::string, double>& joint_values,
78 const std::string& link_name) const override final;
79 Eigen::MatrixXd getJacobian(const std::vector<std::string>& joint_names,
80 const Eigen::Ref<const Eigen::VectorXd>& joint_values,
81 const std::string& link_name) const override final;
82
83 std::vector<std::string> getJointNames() const override final;
84
85 std::vector<std::string> getActiveJointNames() const override final;
86
87 std::string getBaseLinkName() const override final;
88
89 std::vector<std::string> getLinkNames() const override final;
90
91 std::vector<std::string> getActiveLinkNames() const override final;
92
93 std::vector<std::string> getStaticLinkNames() const override final;
94
95 bool isActiveLinkName(const std::string& link_name) const override final;
96
97 bool hasLinkName(const std::string& link_name) const override final;
98
99 tesseract_common::VectorIsometry3d getLinkTransforms() const override final;
100
101 Eigen::Isometry3d getLinkTransform(const std::string& link_name) const override final;
102
103 Eigen::Isometry3d getRelativeLinkTransform(const std::string& from_link_name,
104 const std::string& to_link_name) const override final;
105
106 tesseract_common::KinematicLimits getLimits() const override final;
107
108private:
111 std::unique_ptr<KDL::TreeJntToJacSolver> jac_solver_;
112 std::unordered_map<std::string, unsigned int> joint_to_qnr_;
113 std::vector<int> joint_qnr_;
114 KDL::JntArray kdl_jnt_array_;
115 tesseract_common::KinematicLimits limits_;
116 mutable std::mutex mutex_;
119 const KDL::JntArray& q_in,
120 const KDL::SegmentMap::const_iterator& it,
121 const Eigen::Isometry3d& parent_frame) const;
122
124 const KDL::JntArray& q_in,
125 const KDL::SegmentMap::const_iterator& it,
126 const Eigen::Isometry3d& parent_frame) const;
127
128 bool setJointValuesHelper(KDL::JntArray& q, const std::string& joint_name, const double& joint_value) const;
129
130 bool calcJacobianHelper(KDL::Jacobian& jacobian, const KDL::JntArray& kdl_joints, const std::string& link_name) const;
131
133 KDL::JntArray getKDLJntArray(const std::vector<std::string>& joint_names,
134 const Eigen::Ref<const Eigen::VectorXd>& joint_values) const;
135 KDL::JntArray getKDLJntArray(const std::unordered_map<std::string, double>& joint_values) const;
136
138};
139
140} // namespace tesseract_scene_graph
141#endif // TESSERACT_STATE_SOLVER_KDL_STATE_SOLVER_H
#define vector(a, b, c)
Definition: FloatMath.inl:3227
Definition: kdl_state_solver.h:43
tesseract_common::VectorIsometry3d getLinkTransforms() const override final
Get all of the links transforms.
Definition: kdl_state_solver.cpp:227
tesseract_common::KinematicLimits limits_
Definition: kdl_state_solver.h:115
tesseract_common::KinematicLimits getLimits() const override final
Getter for kinematic limits.
Definition: kdl_state_solver.cpp:248
bool hasLinkName(const std::string &link_name) const override final
Check if link name exists.
Definition: kdl_state_solver.cpp:222
KDL::JntArray kdl_jnt_array_
Definition: kdl_state_solver.h:114
std::string getBaseLinkName() const override final
Get the base link name.
Definition: kdl_state_solver.cpp:208
StateSolver::UPtr clone() const override
This should clone the object so it may be used in a multi threaded application where each thread woul...
Definition: kdl_state_solver.cpp:43
void calculateTransforms(SceneState &state, const KDL::JntArray &q_in, const KDL::SegmentMap::const_iterator &it, const Eigen::Isometry3d &parent_frame) const
Definition: kdl_state_solver.cpp:331
Eigen::MatrixXd getJacobian(const Eigen::Ref< const Eigen::VectorXd > &joint_values, const std::string &link_name) const override final
Get the jacobian of the solver given the joint values.
Definition: kdl_state_solver.cpp:169
KDL::JntArray getKDLJntArray(const std::vector< std::string > &joint_names, const Eigen::Ref< const Eigen::VectorXd > &joint_values) const
Get an updated kdl joint array.
Definition: kdl_state_solver.cpp:354
void setState(const Eigen::Ref< const Eigen::VectorXd > &joint_values) override final
Set the current state of the solver.
Definition: kdl_state_solver.cpp:73
bool processKDLData(const tesseract_scene_graph::SceneGraph &scene_graph)
Definition: kdl_state_solver.cpp:250
std::shared_ptr< const KDLStateSolver > ConstPtr
Definition: kdl_state_solver.h:46
Eigen::Isometry3d getRelativeLinkTransform(const std::string &from_link_name, const std::string &to_link_name) const override final
Get transform between two links using the current state.
Definition: kdl_state_solver.cpp:242
std::shared_ptr< KDLStateSolver > Ptr
Definition: kdl_state_solver.h:45
std::vector< std::string > getStaticLinkNames() const override final
Get a vector of static link names in the environment.
Definition: kdl_state_solver.cpp:214
KDLStateSolver(KDLStateSolver &&)=delete
std::vector< int > joint_qnr_
Definition: kdl_state_solver.h:113
std::vector< std::string > getActiveLinkNames() const override final
Get the vector of active link names.
Definition: kdl_state_solver.cpp:212
bool isActiveLinkName(const std::string &link_name) const override final
Check if link is an active link.
Definition: kdl_state_solver.cpp:216
Eigen::Isometry3d getLinkTransform(const std::string &link_name) const override final
Get the transform corresponding to the link.
Definition: kdl_state_solver.cpp:237
KDLStateSolver & operator=(KDLStateSolver &&)=delete
bool calcJacobianHelper(KDL::Jacobian &jacobian, const KDL::JntArray &kdl_joints, const std::string &link_name) const
Definition: kdl_state_solver.cpp:340
SceneState getState() const override final
Get the current state of the scene.
Definition: kdl_state_solver.cpp:161
std::vector< std::string > getActiveJointNames() const override final
Get the vector of joint names which align with the limits.
Definition: kdl_state_solver.cpp:206
std::vector< std::string > getJointNames() const override final
Get the vector of joint names.
Definition: kdl_state_solver.cpp:204
std::mutex mutex_
KDL is not thread safe due to mutable variables in Joint Class.
Definition: kdl_state_solver.h:116
void calculateTransformsHelper(SceneState &state, const KDL::JntArray &q_in, const KDL::SegmentMap::const_iterator &it, const Eigen::Isometry3d &parent_frame) const
Definition: kdl_state_solver.cpp:304
SceneState current_state_
Definition: kdl_state_solver.h:109
bool setJointValuesHelper(KDL::JntArray &q, const std::string &joint_name, const double &joint_value) const
Definition: kdl_state_solver.cpp:289
std::unique_ptr< KDLStateSolver > UPtr
Definition: kdl_state_solver.h:47
std::unordered_map< std::string, unsigned int > joint_to_qnr_
Definition: kdl_state_solver.h:112
std::unique_ptr< const KDLStateSolver > ConstUPtr
Definition: kdl_state_solver.h:48
SceneState getRandomState() const override final
Get the random state of the environment.
Definition: kdl_state_solver.cpp:163
KDLTreeData data_
Definition: kdl_state_solver.h:110
std::unique_ptr< KDL::TreeJntToJacSolver > jac_solver_
Definition: kdl_state_solver.h:111
std::vector< std::string > getLinkNames() const override final
Get the vector of link names.
Definition: kdl_state_solver.cpp:210
KDLStateSolver & operator=(const KDLStateSolver &other)
Definition: kdl_state_solver.cpp:61
Definition: graph.h:125
Definition: state_solver.h:46
std::unique_ptr< StateSolver > UPtr
Definition: state_solver.h:50
auto it
Definition: collision_core_unit.cpp:208
CollisionMarginData data(default_margin)
Definition: collision_margin_data_unit.cpp:34
auto scene_graph
Definition: ikfast_kinematics_7dof_unit.cpp:51
q[0]
Definition: kinematics_core_unit.cpp:15
Eigen::MatrixXd jacobian
Definition: kinematics_core_unit.cpp:153
Common Tesseract Macros.
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
Definition: macros.h:71
Definition: create_convex_hull.cpp:36
Definition: allowed_collision_matrix.h:16
Definition: graph.h:82
Tesseract Scene Graph State Solver Interface.
The KDLTreeData populated when parsing scene graph.
Definition: kdl_parser.h:120
This holds a state of the scene.
Definition: scene_state.h:54
joint_state joint_names
Definition: tesseract_common_serialization_unit.cpp:75
joint_1 mimic joint_name
Definition: tesseract_scene_graph_joint_unit.cpp:163