Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
tesseract_kinematics::KDLFwdKinChain Class Reference

KDL kinematic chain implementation. More...

#include <kdl_fwd_kin_chain.h>

Inheritance diagram for tesseract_kinematics::KDLFwdKinChain:
Inheritance graph
[legend]
Collaboration diagram for tesseract_kinematics::KDLFwdKinChain:
Collaboration graph
[legend]

Public Types

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

Public Member Functions

 ~KDLFwdKinChain () override=default
 
 KDLFwdKinChain (const KDLFwdKinChain &other)
 
KDLFwdKinChainoperator= (const KDLFwdKinChain &other)
 
 KDLFwdKinChain (KDLFwdKinChain &&)=delete
 
KDLFwdKinChainoperator= (KDLFwdKinChain &&)=delete
 
 KDLFwdKinChain (const tesseract_scene_graph::SceneGraph &scene_graph, const std::string &base_link, const std::string &tip_link, std::string solver_name=KDL_FWD_KIN_CHAIN_SOLVER_NAME)
 Initializes Forward Kinematics as chain Creates a forward kinematic chain object. More...
 
 KDLFwdKinChain (const tesseract_scene_graph::SceneGraph &scene_graph, const std::vector< std::pair< std::string, std::string > > &chains, std::string solver_name=KDL_FWD_KIN_CHAIN_SOLVER_NAME)
 Construct Forward Kinematics as chain Creates a forward kinematic chain object from sequential chains. More...
 
tesseract_common::TransformMap calcFwdKin (const Eigen::Ref< const Eigen::VectorXd > &joint_angles) const override final
 Calculates the transform for each tip link in the kinematic group. More...
 
Eigen::MatrixXd calcJacobian (const Eigen::Ref< const Eigen::VectorXd > &joint_angles, const std::string &joint_link_name) const override final
 Calculates the Jacobian matrix for a given joint state in the reference frame of the specified link. 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::vector< std::string > getTipLinkNames () const override final
 Get list of tip link names for kinematic object. More...
 
Eigen::Index numJoints () const override final
 Number of joints in robot. More...
 
std::string getSolverName () const override final
 Get the name of the solver. Recommend using the name of the class. More...
 
ForwardKinematics::UPtr clone () const override final
 Clone the forward kinematics object. More...
 
- Public Member Functions inherited from tesseract_kinematics::ForwardKinematics
 ForwardKinematics ()=default
 
virtual ~ForwardKinematics ()=default
 
 ForwardKinematics (const ForwardKinematics &)=default
 
ForwardKinematicsoperator= (const ForwardKinematics &)=default
 
 ForwardKinematics (ForwardKinematics &&)=default
 
ForwardKinematicsoperator= (ForwardKinematics &&)=default
 
virtual tesseract_common::TransformMap calcFwdKin (const Eigen::Ref< const Eigen::VectorXd > &joint_angles) const =0
 Calculates the transform for each tip link in the kinematic group. More...
 
virtual Eigen::MatrixXd calcJacobian (const Eigen::Ref< const Eigen::VectorXd > &joint_angles, const std::string &link_name) const =0
 Calculates the Jacobian matrix for a given joint state in the reference frame of the specified link. More...
 
virtual std::string getBaseLinkName () const =0
 Get the robot base link name. More...
 
virtual std::vector< std::string > getJointNames () const =0
 Get list of joint names for kinematic object. More...
 
virtual std::vector< std::string > getTipLinkNames () const =0
 Get list of tip link names for kinematic object. More...
 
virtual Eigen::Index numJoints () const =0
 Number of joints in robot. More...
 
virtual std::string getSolverName () const =0
 Get the name of the solver. Recommend using the name of the class. More...
 
virtual ForwardKinematics::UPtr clone () const =0
 Clone the forward kinematics object. More...
 

Private Member Functions

tesseract_common::TransformMap calcFwdKinHelperAll (const Eigen::Ref< const Eigen::VectorXd > &joint_angles) const
 calcFwdKin helper function More...
 
bool calcJacobianHelper (KDL::Jacobian &jacobian, const Eigen::Ref< const Eigen::VectorXd > &joint_angles, int segment_num=-1) const
 calcJacobian helper function More...
 

Private Attributes

KDLChainData kdl_data_
 
std::string name_
 
std::unique_ptr< KDL::ChainFkSolverPos_recursive > fk_solver_
 
std::unique_ptr< KDL::ChainJntToJacSolver > jac_solver_
 
std::string solver_name_ { KDL_FWD_KIN_CHAIN_SOLVER_NAME }
 Name of this solver. More...
 
std::mutex mutex_
 KDL is not thread safe due to mutable variables in Joint Class. More...
 

Detailed Description

KDL kinematic chain implementation.

Typically, just wrappers around the equivalent KDL calls.

Member Typedef Documentation

◆ ConstPtr

◆ ConstUPtr

◆ Ptr

◆ UPtr

Constructor & Destructor Documentation

◆ ~KDLFwdKinChain()

tesseract_kinematics::KDLFwdKinChain::~KDLFwdKinChain ( )
overridedefault

◆ KDLFwdKinChain() [1/4]

tesseract_kinematics::KDLFwdKinChain::KDLFwdKinChain ( const KDLFwdKinChain other)

◆ KDLFwdKinChain() [2/4]

tesseract_kinematics::KDLFwdKinChain::KDLFwdKinChain ( KDLFwdKinChain &&  )
delete

◆ KDLFwdKinChain() [3/4]

tesseract_kinematics::KDLFwdKinChain::KDLFwdKinChain ( const tesseract_scene_graph::SceneGraph scene_graph,
const std::string &  base_link,
const std::string &  tip_link,
std::string  solver_name = KDL_FWD_KIN_CHAIN_SOLVER_NAME 
)

Initializes Forward Kinematics as chain Creates a forward 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 solver name of the kinematic chain

◆ KDLFwdKinChain() [4/4]

tesseract_kinematics::KDLFwdKinChain::KDLFwdKinChain ( const tesseract_scene_graph::SceneGraph scene_graph,
const std::vector< std::pair< std::string, std::string > > &  chains,
std::string  solver_name = KDL_FWD_KIN_CHAIN_SOLVER_NAME 
)

Construct Forward Kinematics as chain Creates a forward 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

◆ calcFwdKin()

tesseract_common::TransformMap tesseract_kinematics::KDLFwdKinChain::calcFwdKin ( const Eigen::Ref< const Eigen::VectorXd > &  joint_angles) const
finaloverridevirtual

Calculates the transform for each tip link in the kinematic group.

This should return a transform for every link listed in getTipLinkNames() Throws an exception on failures (including uninitialized)

Parameters
joint_anglesVector of joint angles (size must match number of joints in robot chain)
Returns
A map of tip link names and transforms

Implements tesseract_kinematics::ForwardKinematics.

◆ calcFwdKinHelperAll()

tesseract_common::TransformMap tesseract_kinematics::KDLFwdKinChain::calcFwdKinHelperAll ( const Eigen::Ref< const Eigen::VectorXd > &  joint_angles) const
private

calcFwdKin helper function

◆ calcJacobian()

Eigen::MatrixXd tesseract_kinematics::KDLFwdKinChain::calcJacobian ( const Eigen::Ref< const Eigen::VectorXd > &  joint_angles,
const std::string &  link_name 
) const
finaloverridevirtual

Calculates the Jacobian matrix for a given joint state in the reference frame of the specified link.

This should be able to return a jacobian given any link listed in getTipLinkNames() Throws an exception on failures (including uninitialized)

Parameters
joint_anglesInput vector of joint angles
link_nameThe link name to calculate jacobian
Returns
The jacobian at the provided link

Implements tesseract_kinematics::ForwardKinematics.

◆ calcJacobianHelper()

bool tesseract_kinematics::KDLFwdKinChain::calcJacobianHelper ( KDL::Jacobian &  jacobian,
const Eigen::Ref< const Eigen::VectorXd > &  joint_angles,
int  segment_num = -1 
) const
private

calcJacobian helper function

◆ clone()

ForwardKinematics::UPtr tesseract_kinematics::KDLFwdKinChain::clone ( ) const
finaloverridevirtual

Clone the forward kinematics object.

Implements tesseract_kinematics::ForwardKinematics.

◆ getBaseLinkName()

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

Get the robot base link name.

Implements tesseract_kinematics::ForwardKinematics.

◆ getJointNames()

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

Get list of joint names for kinematic object.

Returns
A vector of joint names

Implements tesseract_kinematics::ForwardKinematics.

◆ getSolverName()

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

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

Implements tesseract_kinematics::ForwardKinematics.

◆ getTipLinkNames()

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

Get list of tip link names for kinematic object.

Returns
A vector of link names

Implements tesseract_kinematics::ForwardKinematics.

◆ numJoints()

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

Number of joints in robot.

Returns
Number of joints in robot

Implements tesseract_kinematics::ForwardKinematics.

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

Member Data Documentation

◆ fk_solver_

std::unique_ptr<KDL::ChainFkSolverPos_recursive> tesseract_kinematics::KDLFwdKinChain::fk_solver_
private

KDL Forward Kinematic Solver

◆ jac_solver_

std::unique_ptr<KDL::ChainJntToJacSolver> tesseract_kinematics::KDLFwdKinChain::jac_solver_
private

KDL Jacobian Solver

◆ kdl_data_

KDLChainData tesseract_kinematics::KDLFwdKinChain::kdl_data_
private

KDL data parsed from Scene Graph

◆ mutex_

std::mutex tesseract_kinematics::KDLFwdKinChain::mutex_
mutableprivate

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

◆ name_

std::string tesseract_kinematics::KDLFwdKinChain::name_
private

Name of the kinematic chain

◆ solver_name_

std::string tesseract_kinematics::KDLFwdKinChain::solver_name_ { KDL_FWD_KIN_CHAIN_SOLVER_NAME }
private

Name of this solver.


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