Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
tesseract_scene_graph::KDLStateSolver Class Reference

#include <kdl_state_solver.h>

Inheritance diagram for tesseract_scene_graph::KDLStateSolver:
Inheritance graph
[legend]

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 >
 
- Public Types inherited from tesseract_scene_graph::StateSolver
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
 
KDLStateSolveroperator= (const KDLStateSolver &other)
 
KDLStateSolveroperator= (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
 
- Public Member Functions inherited from tesseract_scene_graph::StateSolver
StateSolveroperator= (const StateSolver &)=default
 
StateSolveroperator= (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...
 

Detailed Description

Definition at line 44 of file kdl_state_solver.h.

Member Typedef Documentation

◆ ConstPtr

Definition at line 48 of file kdl_state_solver.h.

◆ ConstUPtr

Definition at line 50 of file kdl_state_solver.h.

◆ Ptr

Definition at line 47 of file kdl_state_solver.h.

◆ UPtr

Definition at line 49 of file kdl_state_solver.h.

Constructor & Destructor Documentation

◆ KDLStateSolver() [1/4]

tesseract_scene_graph::KDLStateSolver::KDLStateSolver ( const tesseract_scene_graph::SceneGraph scene_graph)

Definition at line 48 of file kdl_state_solver.cpp.

◆ KDLStateSolver() [2/4]

tesseract_scene_graph::KDLStateSolver::KDLStateSolver ( const tesseract_scene_graph::SceneGraph scene_graph,
KDLTreeData  data 
)

Definition at line 57 of file kdl_state_solver.cpp.

◆ ~KDLStateSolver()

tesseract_scene_graph::KDLStateSolver::~KDLStateSolver ( )
overridedefault

◆ KDLStateSolver() [3/4]

tesseract_scene_graph::KDLStateSolver::KDLStateSolver ( const KDLStateSolver other)

Definition at line 63 of file kdl_state_solver.cpp.

◆ KDLStateSolver() [4/4]

tesseract_scene_graph::KDLStateSolver::KDLStateSolver ( KDLStateSolver &&  )
delete

Member Function Documentation

◆ calcJacobianHelper()

bool tesseract_scene_graph::KDLStateSolver::calcJacobianHelper ( KDL::Jacobian &  jacobian,
const KDL::JntArray &  kdl_joints,
const std::string &  link_name 
) const
private

Definition at line 370 of file kdl_state_solver.cpp.

◆ calculateTransforms()

void tesseract_scene_graph::KDLStateSolver::calculateTransforms ( SceneState state,
const KDL::JntArray &  q_in,
const KDL::SegmentMap::const_iterator &  it,
const Eigen::Isometry3d &  parent_frame 
) const
private

Definition at line 361 of file kdl_state_solver.cpp.

◆ calculateTransformsHelper()

void tesseract_scene_graph::KDLStateSolver::calculateTransformsHelper ( SceneState state,
const KDL::JntArray &  q_in,
const KDL::SegmentMap::const_iterator &  it,
const Eigen::Isometry3d &  parent_frame 
) const
private

Definition at line 334 of file kdl_state_solver.cpp.

◆ clone()

StateSolver::UPtr tesseract_scene_graph::KDLStateSolver::clone ( ) const
overridevirtual

This should clone the object so it may be used in a multi threaded application where each thread would clone the solver.

Returns
A clone of the object.

Implements tesseract_scene_graph::StateSolver.

Definition at line 46 of file kdl_state_solver.cpp.

◆ getActiveJointNames()

std::vector< std::string > tesseract_scene_graph::KDLStateSolver::getActiveJointNames ( ) const
finaloverridevirtual

Get the vector of joint names which align with the limits.

Returns
A vector of joint names

Implements tesseract_scene_graph::StateSolver.

Definition at line 230 of file kdl_state_solver.cpp.

◆ getActiveLinkNames()

std::vector< std::string > tesseract_scene_graph::KDLStateSolver::getActiveLinkNames ( ) const
finaloverridevirtual

Get the vector of active link names.

Returns
A vector of active link names

Implements tesseract_scene_graph::StateSolver.

Definition at line 236 of file kdl_state_solver.cpp.

◆ getBaseLinkName()

std::string tesseract_scene_graph::KDLStateSolver::getBaseLinkName ( ) const
finaloverridevirtual

Get the base link name.

Returns
The base link name

Implements tesseract_scene_graph::StateSolver.

Definition at line 232 of file kdl_state_solver.cpp.

◆ getFloatingJointNames()

std::vector< std::string > tesseract_scene_graph::KDLStateSolver::getFloatingJointNames ( ) const
finaloverridevirtual

Get the vector of floating joint names.

Returns
A vector of joint names

Implements tesseract_scene_graph::StateSolver.

Definition at line 228 of file kdl_state_solver.cpp.

◆ getJacobian() [1/3]

Eigen::MatrixXd tesseract_scene_graph::KDLStateSolver::getJacobian ( const Eigen::Ref< const Eigen::VectorXd > &  joint_values,
const std::string &  link_name,
const tesseract_common::TransformMap floating_joint_values = {} 
) const
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

Parameters
joint_valuesThe joint values
link_nameThe link name to calculate the jacobian

Implements tesseract_scene_graph::StateSolver.

Definition at line 188 of file kdl_state_solver.cpp.

◆ getJacobian() [2/3]

Eigen::MatrixXd tesseract_scene_graph::KDLStateSolver::getJacobian ( const std::unordered_map< std::string, double > &  joint_values,
const std::string &  link_name,
const tesseract_common::TransformMap floating_joint_values = {} 
) const
finaloverridevirtual

Get the jacobian of the scene for a given set or subset of joint values.

  • This does not return the jacobian based on the provided joint names. It is order based on the order returned from getJointNames

This does not change the internal state of the solver.

Parameters
jointsA map of joint names to joint values to change.
link_nameThe link name to calculate the jacobian
Returns
A the state of the environment

Implements tesseract_scene_graph::StateSolver.

Definition at line 201 of file kdl_state_solver.cpp.

◆ getJacobian() [3/3]

Eigen::MatrixXd tesseract_scene_graph::KDLStateSolver::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
finaloverridevirtual

Implements tesseract_scene_graph::StateSolver.

Definition at line 213 of file kdl_state_solver.cpp.

◆ getJointNames()

std::vector< std::string > tesseract_scene_graph::KDLStateSolver::getJointNames ( ) const
finaloverridevirtual

Get the vector of joint names.

Returns
A vector of joint names

Implements tesseract_scene_graph::StateSolver.

Definition at line 226 of file kdl_state_solver.cpp.

◆ getKDLJntArray() [1/2]

KDL::JntArray tesseract_scene_graph::KDLStateSolver::getKDLJntArray ( const std::unordered_map< std::string, double > &  joint_values) const
private

Definition at line 396 of file kdl_state_solver.cpp.

◆ getKDLJntArray() [2/2]

KDL::JntArray tesseract_scene_graph::KDLStateSolver::getKDLJntArray ( const std::vector< std::string > &  joint_names,
const Eigen::Ref< const Eigen::VectorXd > &  joint_values 
) const
private

Get an updated kdl joint array.

Definition at line 384 of file kdl_state_solver.cpp.

◆ getLimits()

tesseract_common::KinematicLimits tesseract_scene_graph::KDLStateSolver::getLimits ( ) const
finaloverridevirtual

Getter for kinematic limits.

Returns
The kinematic limits

Implements tesseract_scene_graph::StateSolver.

Definition at line 272 of file kdl_state_solver.cpp.

◆ getLinkNames()

std::vector< std::string > tesseract_scene_graph::KDLStateSolver::getLinkNames ( ) const
finaloverridevirtual

Get the vector of link names.

Returns
A vector of link names

Implements tesseract_scene_graph::StateSolver.

Definition at line 234 of file kdl_state_solver.cpp.

◆ getLinkTransform()

Eigen::Isometry3d tesseract_scene_graph::KDLStateSolver::getLinkTransform ( const std::string &  link_name) const
finaloverridevirtual

Get the transform corresponding to the link.

Returns
Transform and is identity when no transform is available.

Implements tesseract_scene_graph::StateSolver.

Definition at line 261 of file kdl_state_solver.cpp.

◆ getLinkTransforms()

tesseract_common::VectorIsometry3d tesseract_scene_graph::KDLStateSolver::getLinkTransforms ( ) const
finaloverridevirtual

Get all of the links transforms.

Order should be the same as getLinkNames()

Returns
Get a vector of transforms for all links.

Implements tesseract_scene_graph::StateSolver.

Definition at line 251 of file kdl_state_solver.cpp.

◆ getRandomState()

SceneState tesseract_scene_graph::KDLStateSolver::getRandomState ( ) const
finaloverridevirtual

Get the random state of the environment.

Returns
Environment state

Implements tesseract_scene_graph::StateSolver.

Definition at line 182 of file kdl_state_solver.cpp.

◆ getRelativeLinkTransform()

Eigen::Isometry3d tesseract_scene_graph::KDLStateSolver::getRelativeLinkTransform ( const std::string &  from_link_name,
const std::string &  to_link_name 
) const
finaloverridevirtual

Get transform between two links using the current state.

Parameters
from_link_nameThe link name the transform should be relative to
to_link_nameThe link name to get transform
Returns
The relative transform = inv(Transform(from_link_name)) * Transform(to_link_name)

Implements tesseract_scene_graph::StateSolver.

Definition at line 266 of file kdl_state_solver.cpp.

◆ getState() [1/5]

SceneState tesseract_scene_graph::KDLStateSolver::getState ( ) const
finaloverridevirtual

Get the current state of the scene.

Returns
The current state

Implements tesseract_scene_graph::StateSolver.

Definition at line 180 of file kdl_state_solver.cpp.

◆ getState() [2/5]

SceneState tesseract_scene_graph::KDLStateSolver::getState ( const Eigen::Ref< const Eigen::VectorXd > &  joint_values,
const tesseract_common::TransformMap floating_joint_values = {} 
) const
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

Parameters
joint_valuesThe joint values
floating_joint_valuesThe floating joint origin transform

Implements tesseract_scene_graph::StateSolver.

Definition at line 120 of file kdl_state_solver.cpp.

◆ getState() [3/5]

SceneState tesseract_scene_graph::KDLStateSolver::getState ( const std::unordered_map< std::string, double > &  joint_values,
const tesseract_common::TransformMap floating_joint_values = {} 
) const
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.

Parameters
jointsA map of joint names to joint values to change.
floating_joint_valuesThe floating joint origin transform
Returns
A the state of the environment

Implements tesseract_scene_graph::StateSolver.

Definition at line 138 of file kdl_state_solver.cpp.

◆ getState() [4/5]

SceneState tesseract_scene_graph::KDLStateSolver::getState ( const std::vector< std::string > &  joint_names,
const Eigen::Ref< const Eigen::VectorXd > &  joint_values,
const tesseract_common::TransformMap floating_joint_values = {} 
) const
finaloverridevirtual

Implements tesseract_scene_graph::StateSolver.

Definition at line 156 of file kdl_state_solver.cpp.

◆ getState() [5/5]

SceneState tesseract_scene_graph::KDLStateSolver::getState ( const tesseract_common::TransformMap floating_joint_values) const
finaloverridevirtual

Get the state given floating joint values.

Parameters
floating_joint_valuesThe floating joint values to leverage
Returns
A the state of the environment

Implements tesseract_scene_graph::StateSolver.

Definition at line 175 of file kdl_state_solver.cpp.

◆ getStaticLinkNames()

std::vector< std::string > tesseract_scene_graph::KDLStateSolver::getStaticLinkNames ( ) const
finaloverridevirtual

Get a vector of static link names in the environment.

Returns
A vector of static link names

Implements tesseract_scene_graph::StateSolver.

Definition at line 238 of file kdl_state_solver.cpp.

◆ hasLinkName()

bool tesseract_scene_graph::KDLStateSolver::hasLinkName ( const std::string &  link_name) const
finaloverridevirtual

Check if link name exists.

Parameters
link_nameThe link name to check for
Returns
True if it exists, otherwise false

Implements tesseract_scene_graph::StateSolver.

Definition at line 246 of file kdl_state_solver.cpp.

◆ isActiveLinkName()

bool tesseract_scene_graph::KDLStateSolver::isActiveLinkName ( const std::string &  link_name) const
finaloverridevirtual

Check if link is an active link.

Parameters
link_nameThe link name to check
Returns
True if active, otherwise false

Implements tesseract_scene_graph::StateSolver.

Definition at line 240 of file kdl_state_solver.cpp.

◆ operator=() [1/2]

KDLStateSolver & tesseract_scene_graph::KDLStateSolver::operator= ( const KDLStateSolver other)

Definition at line 64 of file kdl_state_solver.cpp.

◆ operator=() [2/2]

KDLStateSolver& tesseract_scene_graph::KDLStateSolver::operator= ( KDLStateSolver &&  )
delete

◆ processKDLData()

bool tesseract_scene_graph::KDLStateSolver::processKDLData ( const tesseract_scene_graph::SceneGraph scene_graph)
private

Definition at line 274 of file kdl_state_solver.cpp.

◆ setJointValuesHelper()

bool tesseract_scene_graph::KDLStateSolver::setJointValuesHelper ( KDL::JntArray &  q,
const std::string &  joint_name,
const double &  joint_value 
) const
private

Definition at line 319 of file kdl_state_solver.cpp.

◆ setState() [1/4]

void tesseract_scene_graph::KDLStateSolver::setState ( const Eigen::Ref< const Eigen::VectorXd > &  joint_values,
const tesseract_common::TransformMap floating_joint_values = {} 
)
finaloverridevirtual

Set the current state of the solver.

This must be the same size and order as what is returned by getJointNames

Parameters
joint_valuesThe joint values

Implements tesseract_scene_graph::StateSolver.

Definition at line 76 of file kdl_state_solver.cpp.

◆ setState() [2/4]

void tesseract_scene_graph::KDLStateSolver::setState ( const std::unordered_map< std::string, double > &  joint_values,
const tesseract_common::TransformMap floating_joint_values = {} 
)
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.

◆ setState() [3/4]

void tesseract_scene_graph::KDLStateSolver::setState ( const std::vector< std::string > &  joint_names,
const Eigen::Ref< const Eigen::VectorXd > &  joint_values,
const tesseract_common::TransformMap floating_joint_values = {} 
)
finaloverridevirtual

Implements tesseract_scene_graph::StateSolver.

Definition at line 101 of file kdl_state_solver.cpp.

◆ setState() [4/4]

void tesseract_scene_graph::KDLStateSolver::setState ( const tesseract_common::TransformMap floating_joint_values)
finaloverridevirtual

Set the current state of the floating joint values.

Parameters
floating_joint_valuesThe floating joint values to set

Implements tesseract_scene_graph::StateSolver.

Definition at line 115 of file kdl_state_solver.cpp.

Member Data Documentation

◆ current_state_

SceneState tesseract_scene_graph::KDLStateSolver::current_state_
private

Current state of the environment

Definition at line 124 of file kdl_state_solver.h.

◆ data_

KDLTreeData tesseract_scene_graph::KDLStateSolver::data_
private

KDL tree data

Definition at line 125 of file kdl_state_solver.h.

◆ jac_solver_

std::unique_ptr<KDL::TreeJntToJacSolver> tesseract_scene_graph::KDLStateSolver::jac_solver_
private

KDL Jacobian Solver

Definition at line 126 of file kdl_state_solver.h.

◆ joint_qnr_

std::vector<int> tesseract_scene_graph::KDLStateSolver::joint_qnr_
private

The kdl segment number corresponding to joint in joint names

Definition at line 128 of file kdl_state_solver.h.

◆ joint_to_qnr_

std::unordered_map<std::string, unsigned int> tesseract_scene_graph::KDLStateSolver::joint_to_qnr_
private

Map between joint name and kdl q index

Definition at line 127 of file kdl_state_solver.h.

◆ kdl_jnt_array_

KDL::JntArray tesseract_scene_graph::KDLStateSolver::kdl_jnt_array_
private

The kdl joint array

Definition at line 129 of file kdl_state_solver.h.

◆ limits_

tesseract_common::KinematicLimits tesseract_scene_graph::KDLStateSolver::limits_
private

The kinematic limits

Definition at line 130 of file kdl_state_solver.h.

◆ mutex_

std::mutex tesseract_scene_graph::KDLStateSolver::mutex_
mutableprivate

KDL is not thread safe due to mutable variables in Joint Class.

Definition at line 131 of file kdl_state_solver.h.


The documentation for this class was generated from the following files:


tesseract_state_solver
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:02:10