Classes | Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
tesseract_kinematics::KDLInvKinChainLMA Class Reference

KDL Inverse kinematic chain implementation. More...

#include <kdl_inv_kin_chain_lma.h>

Inheritance diagram for tesseract_kinematics::KDLInvKinChainLMA:
Inheritance graph
[legend]

Classes

struct  Config
 The Config struct. More...
 

Public Types

using ConstPtr = std::shared_ptr< const KDLInvKinChainLMA >
 
using ConstUPtr = std::unique_ptr< const KDLInvKinChainLMA >
 
using Ptr = std::shared_ptr< KDLInvKinChainLMA >
 
using UPtr = std::unique_ptr< KDLInvKinChainLMA >
 
- Public Types inherited from tesseract_kinematics::InverseKinematics
using ConstPtr = std::shared_ptr< const InverseKinematics >
 
using ConstUPtr = std::unique_ptr< const InverseKinematics >
 
using Ptr = std::shared_ptr< InverseKinematics >
 
using UPtr = std::unique_ptr< InverseKinematics >
 

Public Member Functions

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. More...
 
InverseKinematics::UPtr clone () const override final
 Clone the forward kinematics object. More...
 
std::string getBaseLinkName () const override final
 Get the robot base link name. More...
 
std::vector< std::string > getJointNames () const override final
 Get list of joint names for kinematic object. More...
 
std::string getSolverName () const override final
 Get the name of the solver. Recommend using the name of the class. More...
 
std::vector< std::string > getTipLinkNames () const override final
 Get the names of the tip links of the kinematics group. More...
 
std::string getWorkingFrame () const override final
 Get the inverse kinematics working frame. More...
 
 KDLInvKinChainLMA (const KDLInvKinChainLMA &other)
 
 KDLInvKinChainLMA (const tesseract_scene_graph::SceneGraph &scene_graph, const std::string &base_link, const std::string &tip_link, Config kdl_config, std::string solver_name=KDL_INV_KIN_CHAIN_LMA_SOLVER_NAME)
 Construct Inverse Kinematics as chain Creates a inverse kinematic chain object. More...
 
 KDLInvKinChainLMA (const tesseract_scene_graph::SceneGraph &scene_graph, const std::vector< std::pair< std::string, std::string > > &chains, Config kdl_config, std::string solver_name=KDL_INV_KIN_CHAIN_LMA_SOLVER_NAME)
 Construct Inverse Kinematics as chain Creates a inverse kinematic chain object from sequential chains. More...
 
 KDLInvKinChainLMA (KDLInvKinChainLMA &&)=delete
 
Eigen::Index numJoints () const override final
 Number of joints in robot. More...
 
KDLInvKinChainLMAoperator= (const KDLInvKinChainLMA &other)
 
KDLInvKinChainLMAoperator= (KDLInvKinChainLMA &&)=delete
 
 ~KDLInvKinChainLMA () override=default
 
- Public Member Functions inherited from tesseract_kinematics::InverseKinematics
 InverseKinematics ()=default
 
 InverseKinematics (const InverseKinematics &)=default
 
 InverseKinematics (InverseKinematics &&)=default
 
InverseKinematicsoperator= (const InverseKinematics &)=default
 
InverseKinematicsoperator= (InverseKinematics &&)=default
 
virtual ~InverseKinematics ()
 

Private Member Functions

IKSolutions calcInvKinHelper (const Eigen::Isometry3d &pose, const Eigen::Ref< const Eigen::VectorXd > &seed, int segment_num=-1) const
 calcFwdKin helper function More...
 

Private Attributes

std::unique_ptr< KDL::ChainIkSolverPos_LMA > ik_solver_
 KDL Inverse kinematic solver. More...
 
Config kdl_config_
 KDL configuration data parsed from YAML. More...
 
KDLChainData kdl_data_
 KDL data parsed from Scene Graph. More...
 
std::mutex mutex_
 KDL is not thread safe due to mutable variables in Joint Class. More...
 
std::string solver_name_ { KDL_INV_KIN_CHAIN_LMA_SOLVER_NAME }
 Name of this solver. More...
 

Detailed Description

KDL Inverse kinematic chain implementation.

Definition at line 45 of file kdl_inv_kin_chain_lma.h.

Member Typedef Documentation

◆ ConstPtr

Definition at line 53 of file kdl_inv_kin_chain_lma.h.

◆ ConstUPtr

Definition at line 55 of file kdl_inv_kin_chain_lma.h.

◆ Ptr

Definition at line 52 of file kdl_inv_kin_chain_lma.h.

◆ UPtr

Definition at line 54 of file kdl_inv_kin_chain_lma.h.

Constructor & Destructor Documentation

◆ ~KDLInvKinChainLMA()

tesseract_kinematics::KDLInvKinChainLMA::~KDLInvKinChainLMA ( )
overridedefault

◆ KDLInvKinChainLMA() [1/4]

tesseract_kinematics::KDLInvKinChainLMA::KDLInvKinChainLMA ( const KDLInvKinChainLMA other)

Definition at line 73 of file kdl_inv_kin_chain_lma.cpp.

◆ KDLInvKinChainLMA() [2/4]

tesseract_kinematics::KDLInvKinChainLMA::KDLInvKinChainLMA ( KDLInvKinChainLMA &&  )
delete

◆ KDLInvKinChainLMA() [3/4]

tesseract_kinematics::KDLInvKinChainLMA::KDLInvKinChainLMA ( const tesseract_scene_graph::SceneGraph scene_graph,
const std::string &  base_link,
const std::string &  tip_link,
Config  kdl_config,
std::string  solver_name = KDL_INV_KIN_CHAIN_LMA_SOLVER_NAME 
)

Construct Inverse Kinematics as chain Creates a inverse kinematic chain object.

Parameters
scene_graphThe Tesseract Scene Graph
base_linkThe name of the base link for the kinematic chain
tip_linkThe name of the tip link for the kinematic chain
solver_nameThe name of the kinematic chain

Definition at line 62 of file kdl_inv_kin_chain_lma.cpp.

◆ KDLInvKinChainLMA() [4/4]

tesseract_kinematics::KDLInvKinChainLMA::KDLInvKinChainLMA ( const tesseract_scene_graph::SceneGraph scene_graph,
const std::vector< std::pair< std::string, std::string > > &  chains,
Config  kdl_config,
std::string  solver_name = KDL_INV_KIN_CHAIN_LMA_SOLVER_NAME 
)

Construct Inverse Kinematics as chain Creates a inverse kinematic chain object from sequential chains.

Parameters
scene_graphThe Tesseract Scene Graph
chainsA vector of kinematics chains <base_link, tip_link> that get concatenated
solver_nameThe solver name of the kinematic chain

Member Function Documentation

◆ calcInvKin()

IKSolutions tesseract_kinematics::KDLInvKinChainLMA::calcInvKin ( const tesseract_common::TransformMap tip_link_poses,
const Eigen::Ref< const Eigen::VectorXd > &  seed 
) const
finaloverridevirtual

Calculates joint solutions given a pose for each tip link.

This interface supports IK for both kinematic chains that have a single tool tip link and kinematic chains that have multiple tip links. For example, consider a robot with external part positioner: a pose can be specified to be relative to the tip link of the robot or the tip link of the positioner is to support a pose relative to a active link. For example a robot with an external positioner where the pose is relative to the tip link of the positioner.

Note
Redundant joint solutions can be provided by the utility function getRedundantSolutions
Parameters
tip_link_posesA map of poses corresponding to each tip link provided in getTipLinkNames and relative to the working frame of the kinematics group for which to solve inverse kinematics
seedVector of seed joint angles (size must match number of joints in kinematic object)
Returns
A vector of solutions, If empty it failed to find a solution (including uninitialized)

Implements tesseract_kinematics::InverseKinematics.

Definition at line 137 of file kdl_inv_kin_chain_lma.cpp.

◆ calcInvKinHelper()

IKSolutions tesseract_kinematics::KDLInvKinChainLMA::calcInvKinHelper ( const Eigen::Isometry3d &  pose,
const Eigen::Ref< const Eigen::VectorXd > &  seed,
int  segment_num = -1 
) const
private

calcFwdKin helper function

Definition at line 90 of file kdl_inv_kin_chain_lma.cpp.

◆ clone()

InverseKinematics::UPtr tesseract_kinematics::KDLInvKinChainLMA::clone ( ) const
finaloverridevirtual

Clone the forward kinematics object.

Implements tesseract_kinematics::InverseKinematics.

Definition at line 71 of file kdl_inv_kin_chain_lma.cpp.

◆ getBaseLinkName()

std::string tesseract_kinematics::KDLInvKinChainLMA::getBaseLinkName ( ) const
finaloverridevirtual

Get the robot base link name.

Implements tesseract_kinematics::InverseKinematics.

Definition at line 148 of file kdl_inv_kin_chain_lma.cpp.

◆ getJointNames()

std::vector< std::string > tesseract_kinematics::KDLInvKinChainLMA::getJointNames ( ) const
finaloverridevirtual

Get list of joint names for kinematic object.

Returns
A vector of joint names, joint_list_

Implements tesseract_kinematics::InverseKinematics.

Definition at line 144 of file kdl_inv_kin_chain_lma.cpp.

◆ getSolverName()

std::string tesseract_kinematics::KDLInvKinChainLMA::getSolverName ( ) const
finaloverridevirtual

Get the name of the solver. Recommend using the name of the class.

Implements tesseract_kinematics::InverseKinematics.

Definition at line 154 of file kdl_inv_kin_chain_lma.cpp.

◆ getTipLinkNames()

std::vector< std::string > tesseract_kinematics::KDLInvKinChainLMA::getTipLinkNames ( ) const
finaloverridevirtual

Get the names of the tip links of the kinematics group.

In the case of a kinematic chain, this returns one tip link; in the case of a kinematic tree this returns the tip link for each branch of the tree.

Implements tesseract_kinematics::InverseKinematics.

Definition at line 152 of file kdl_inv_kin_chain_lma.cpp.

◆ getWorkingFrame()

std::string tesseract_kinematics::KDLInvKinChainLMA::getWorkingFrame ( ) const
finaloverridevirtual

Get the inverse kinematics working frame.

This is the frame of reference in which all poses given to the calcInvKin function should be defined

Implements tesseract_kinematics::InverseKinematics.

Definition at line 150 of file kdl_inv_kin_chain_lma.cpp.

◆ numJoints()

Eigen::Index tesseract_kinematics::KDLInvKinChainLMA::numJoints ( ) const
finaloverridevirtual

Number of joints in robot.

Returns
Number of joints in robot

Implements tesseract_kinematics::InverseKinematics.

Definition at line 146 of file kdl_inv_kin_chain_lma.cpp.

◆ operator=() [1/2]

KDLInvKinChainLMA & tesseract_kinematics::KDLInvKinChainLMA::operator= ( const KDLInvKinChainLMA other)

Definition at line 75 of file kdl_inv_kin_chain_lma.cpp.

◆ operator=() [2/2]

KDLInvKinChainLMA& tesseract_kinematics::KDLInvKinChainLMA::operator= ( KDLInvKinChainLMA &&  )
delete

Member Data Documentation

◆ ik_solver_

std::unique_ptr<KDL::ChainIkSolverPos_LMA> tesseract_kinematics::KDLInvKinChainLMA::ik_solver_
private

KDL Inverse kinematic solver.

Definition at line 119 of file kdl_inv_kin_chain_lma.h.

◆ kdl_config_

Config tesseract_kinematics::KDLInvKinChainLMA::kdl_config_
private

KDL configuration data parsed from YAML.

Definition at line 118 of file kdl_inv_kin_chain_lma.h.

◆ kdl_data_

KDLChainData tesseract_kinematics::KDLInvKinChainLMA::kdl_data_
private

KDL data parsed from Scene Graph.

Definition at line 117 of file kdl_inv_kin_chain_lma.h.

◆ mutex_

std::mutex tesseract_kinematics::KDLInvKinChainLMA::mutex_
mutableprivate

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

Definition at line 121 of file kdl_inv_kin_chain_lma.h.

◆ solver_name_

std::string tesseract_kinematics::KDLInvKinChainLMA::solver_name_ { KDL_INV_KIN_CHAIN_LMA_SOLVER_NAME }
private

Name of this solver.

Definition at line 120 of file kdl_inv_kin_chain_lma.h.


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


tesseract_kinematics
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:02:14