#include <kdl_state_solver.h>
Public Types | |
using | ConstPtr = std::shared_ptr< const KDLStateSolver > |
using | ConstUPtr = std::unique_ptr< const KDLStateSolver > |
using | Ptr = std::shared_ptr< KDLStateSolver > |
using | UPtr = std::unique_ptr< KDLStateSolver > |
![]() | |
using | ConstPtr = std::shared_ptr< const StateSolver > |
using | ConstUPtr = std::unique_ptr< const StateSolver > |
using | Ptr = std::shared_ptr< StateSolver > |
using | UPtr = std::unique_ptr< StateSolver > |
Public Member Functions | |
StateSolver::UPtr | clone () const override |
This should clone the object so it may be used in a multi threaded application where each thread would clone the solver. More... | |
std::vector< std::string > | getActiveJointNames () const override final |
Get the vector of joint names which align with the limits. More... | |
std::vector< std::string > | getActiveLinkNames () const override final |
Get the vector of active link names. More... | |
std::string | getBaseLinkName () const override final |
Get the base link name. More... | |
std::vector< std::string > | getFloatingJointNames () const override final |
Get the vector of floating joint names. More... | |
Eigen::MatrixXd | getJacobian (const Eigen::Ref< const Eigen::VectorXd > &joint_values, const std::string &link_name, const tesseract_common::TransformMap &floating_joint_values={}) const override final |
Get the jacobian of the solver given the joint values. More... | |
Eigen::MatrixXd | getJacobian (const std::unordered_map< std::string, double > &joint_values, const std::string &link_name, const tesseract_common::TransformMap &floating_joint_values={}) const override final |
Get the jacobian of the scene for a given set or subset of joint values. More... | |
Eigen::MatrixXd | getJacobian (const std::vector< std::string > &joint_names, const Eigen::Ref< const Eigen::VectorXd > &joint_values, const std::string &link_name, const tesseract_common::TransformMap &floating_joint_values={}) const override final |
std::vector< std::string > | getJointNames () const override final |
Get the vector of joint names. More... | |
tesseract_common::KinematicLimits | getLimits () const override final |
Getter for kinematic limits. More... | |
std::vector< std::string > | getLinkNames () const override final |
Get the vector of link names. More... | |
Eigen::Isometry3d | getLinkTransform (const std::string &link_name) const override final |
Get the transform corresponding to the link. More... | |
tesseract_common::VectorIsometry3d | getLinkTransforms () const override final |
Get all of the links transforms. More... | |
SceneState | getRandomState () const override final |
Get the random state of the environment. More... | |
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. More... | |
SceneState | getState () const override final |
Get the current state of the scene. More... | |
SceneState | getState (const Eigen::Ref< const Eigen::VectorXd > &joint_values, const tesseract_common::TransformMap &floating_joint_values={}) const override final |
Get the state of the solver given the joint values. More... | |
SceneState | getState (const std::unordered_map< std::string, double > &joint_values, const tesseract_common::TransformMap &floating_joint_values={}) const override final |
Get the state of the scene for a given set or subset of joint values. More... | |
SceneState | getState (const std::vector< std::string > &joint_names, const Eigen::Ref< const Eigen::VectorXd > &joint_values, const tesseract_common::TransformMap &floating_joint_values={}) const override final |
SceneState | getState (const tesseract_common::TransformMap &floating_joint_values) const override final |
Get the state given floating joint values. More... | |
std::vector< std::string > | getStaticLinkNames () const override final |
Get a vector of static link names in the environment. More... | |
bool | hasLinkName (const std::string &link_name) const override final |
Check if link name exists. More... | |
bool | isActiveLinkName (const std::string &link_name) const override final |
Check if link is an active link. More... | |
KDLStateSolver (const KDLStateSolver &other) | |
KDLStateSolver (const tesseract_scene_graph::SceneGraph &scene_graph) | |
KDLStateSolver (const tesseract_scene_graph::SceneGraph &scene_graph, KDLTreeData data) | |
KDLStateSolver (KDLStateSolver &&)=delete | |
KDLStateSolver & | operator= (const KDLStateSolver &other) |
KDLStateSolver & | operator= (KDLStateSolver &&)=delete |
void | setState (const Eigen::Ref< const Eigen::VectorXd > &joint_values, const tesseract_common::TransformMap &floating_joint_values={}) override final |
Set the current state of the solver. More... | |
void | setState (const std::unordered_map< std::string, double > &joint_values, const tesseract_common::TransformMap &floating_joint_values={}) override final |
Set the current state of the solver. More... | |
void | setState (const std::vector< std::string > &joint_names, const Eigen::Ref< const Eigen::VectorXd > &joint_values, const tesseract_common::TransformMap &floating_joint_values={}) override final |
void | setState (const tesseract_common::TransformMap &floating_joint_values) override final |
Set the current state of the floating joint values. More... | |
~KDLStateSolver () override=default | |
![]() | |
StateSolver & | operator= (const StateSolver &)=default |
StateSolver & | operator= (StateSolver &&)=default |
StateSolver ()=default | |
StateSolver (const StateSolver &)=default | |
StateSolver (StateSolver &&)=default | |
virtual | ~StateSolver ()=default |
Private Member Functions | |
bool | calcJacobianHelper (KDL::Jacobian &jacobian, const KDL::JntArray &kdl_joints, const std::string &link_name) const |
void | calculateTransforms (SceneState &state, const KDL::JntArray &q_in, const KDL::SegmentMap::const_iterator &it, const Eigen::Isometry3d &parent_frame) const |
void | calculateTransformsHelper (SceneState &state, const KDL::JntArray &q_in, const KDL::SegmentMap::const_iterator &it, const Eigen::Isometry3d &parent_frame) const |
KDL::JntArray | getKDLJntArray (const std::unordered_map< std::string, double > &joint_values) const |
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. More... | |
bool | processKDLData (const tesseract_scene_graph::SceneGraph &scene_graph) |
bool | setJointValuesHelper (KDL::JntArray &q, const std::string &joint_name, const double &joint_value) const |
Private Attributes | |
SceneState | current_state_ |
KDLTreeData | data_ |
std::unique_ptr< KDL::TreeJntToJacSolver > | jac_solver_ |
std::vector< int > | joint_qnr_ |
std::unordered_map< std::string, unsigned int > | joint_to_qnr_ |
KDL::JntArray | kdl_jnt_array_ |
tesseract_common::KinematicLimits | limits_ |
std::mutex | mutex_ |
KDL is not thread safe due to mutable variables in Joint Class. More... | |
Definition at line 44 of file kdl_state_solver.h.
using tesseract_scene_graph::KDLStateSolver::ConstPtr = std::shared_ptr<const KDLStateSolver> |
Definition at line 48 of file kdl_state_solver.h.
using tesseract_scene_graph::KDLStateSolver::ConstUPtr = std::unique_ptr<const KDLStateSolver> |
Definition at line 50 of file kdl_state_solver.h.
using tesseract_scene_graph::KDLStateSolver::Ptr = std::shared_ptr<KDLStateSolver> |
Definition at line 47 of file kdl_state_solver.h.
using tesseract_scene_graph::KDLStateSolver::UPtr = std::unique_ptr<KDLStateSolver> |
Definition at line 49 of file kdl_state_solver.h.
tesseract_scene_graph::KDLStateSolver::KDLStateSolver | ( | const tesseract_scene_graph::SceneGraph & | scene_graph | ) |
Definition at line 48 of file kdl_state_solver.cpp.
tesseract_scene_graph::KDLStateSolver::KDLStateSolver | ( | const tesseract_scene_graph::SceneGraph & | scene_graph, |
KDLTreeData | data | ||
) |
Definition at line 57 of file kdl_state_solver.cpp.
|
overridedefault |
tesseract_scene_graph::KDLStateSolver::KDLStateSolver | ( | const KDLStateSolver & | other | ) |
Definition at line 63 of file kdl_state_solver.cpp.
|
delete |
|
private |
Definition at line 370 of file kdl_state_solver.cpp.
|
private |
Definition at line 361 of file kdl_state_solver.cpp.
|
private |
Definition at line 334 of file kdl_state_solver.cpp.
|
overridevirtual |
This should clone the object so it may be used in a multi threaded application where each thread would clone the solver.
Implements tesseract_scene_graph::StateSolver.
Definition at line 46 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Get the vector of joint names which align with the limits.
Implements tesseract_scene_graph::StateSolver.
Definition at line 230 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Get the vector of active link names.
Implements tesseract_scene_graph::StateSolver.
Definition at line 236 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Get the base link name.
Implements tesseract_scene_graph::StateSolver.
Definition at line 232 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Get the vector of floating joint names.
Implements tesseract_scene_graph::StateSolver.
Definition at line 228 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Get the jacobian of the solver given the joint values.
This must be the same size and order as what is returned by getJointNames
joint_values | The joint values |
link_name | The link name to calculate the jacobian |
Implements tesseract_scene_graph::StateSolver.
Definition at line 188 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Get the jacobian of the scene for a given set or subset of joint values.
This does not change the internal state of the solver.
joints | A map of joint names to joint values to change. |
link_name | The link name to calculate the jacobian |
Implements tesseract_scene_graph::StateSolver.
Definition at line 201 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Implements tesseract_scene_graph::StateSolver.
Definition at line 213 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Get the vector of joint names.
Implements tesseract_scene_graph::StateSolver.
Definition at line 226 of file kdl_state_solver.cpp.
|
private |
Definition at line 396 of file kdl_state_solver.cpp.
|
private |
Get an updated kdl joint array.
Definition at line 384 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Getter for kinematic limits.
Implements tesseract_scene_graph::StateSolver.
Definition at line 272 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Get the vector of link names.
Implements tesseract_scene_graph::StateSolver.
Definition at line 234 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Get the transform corresponding to the link.
Implements tesseract_scene_graph::StateSolver.
Definition at line 261 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Get all of the links transforms.
Order should be the same as getLinkNames()
Implements tesseract_scene_graph::StateSolver.
Definition at line 251 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Get the random state of the environment.
Implements tesseract_scene_graph::StateSolver.
Definition at line 182 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Get transform between two links using the current state.
from_link_name | The link name the transform should be relative to |
to_link_name | The link name to get transform |
Implements tesseract_scene_graph::StateSolver.
Definition at line 266 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Get the current state of the scene.
Implements tesseract_scene_graph::StateSolver.
Definition at line 180 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Get the state of the solver given the joint values.
This must be the same size and order as what is returned by getJointNames
joint_values | The joint values |
floating_joint_values | The floating joint origin transform |
Implements tesseract_scene_graph::StateSolver.
Definition at line 120 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Get the state of the scene for a given set or subset of joint values.
This does not change the internal state of the solver.
joints | A map of joint names to joint values to change. |
floating_joint_values | The floating joint origin transform |
Implements tesseract_scene_graph::StateSolver.
Definition at line 138 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Implements tesseract_scene_graph::StateSolver.
Definition at line 156 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Get the state given floating joint values.
floating_joint_values | The floating joint values to leverage |
Implements tesseract_scene_graph::StateSolver.
Definition at line 175 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Get a vector of static link names in the environment.
Implements tesseract_scene_graph::StateSolver.
Definition at line 238 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Check if link name exists.
link_name | The link name to check for |
Implements tesseract_scene_graph::StateSolver.
Definition at line 246 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Check if link is an active link.
link_name | The link name to check |
Implements tesseract_scene_graph::StateSolver.
Definition at line 240 of file kdl_state_solver.cpp.
KDLStateSolver & tesseract_scene_graph::KDLStateSolver::operator= | ( | const KDLStateSolver & | other | ) |
Definition at line 64 of file kdl_state_solver.cpp.
|
delete |
|
private |
Definition at line 274 of file kdl_state_solver.cpp.
|
private |
Definition at line 319 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Set the current state of the solver.
This must be the same size and order as what is returned by getJointNames
joint_values | The joint values |
Implements tesseract_scene_graph::StateSolver.
Definition at line 76 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Set the current state of the solver.
After updating the current state these function must call currentStateChanged() which will update the contact managers transforms
Implements tesseract_scene_graph::StateSolver.
Definition at line 89 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Implements tesseract_scene_graph::StateSolver.
Definition at line 101 of file kdl_state_solver.cpp.
|
finaloverridevirtual |
Set the current state of the floating joint values.
floating_joint_values | The floating joint values to set |
Implements tesseract_scene_graph::StateSolver.
Definition at line 115 of file kdl_state_solver.cpp.
|
private |
Current state of the environment
Definition at line 124 of file kdl_state_solver.h.
|
private |
KDL tree data
Definition at line 125 of file kdl_state_solver.h.
|
private |
KDL Jacobian Solver
Definition at line 126 of file kdl_state_solver.h.
|
private |
The kdl segment number corresponding to joint in joint names
Definition at line 128 of file kdl_state_solver.h.
|
private |
Map between joint name and kdl q index
Definition at line 127 of file kdl_state_solver.h.
|
private |
The kdl joint array
Definition at line 129 of file kdl_state_solver.h.
|
private |
The kinematic limits
Definition at line 130 of file kdl_state_solver.h.
|
mutableprivate |
KDL is not thread safe due to mutable variables in Joint Class.
Definition at line 131 of file kdl_state_solver.h.