Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
Public Types | Public Member Functions | List of all members
tesseract_kinematics::ForwardKinematics Class Referenceabstract

Forward kinematics functions. More...

#include <forward_kinematics.h>

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

Public Types

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

 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...
 

Detailed Description

Forward kinematics functions.

Member Typedef Documentation

◆ ConstPtr

◆ ConstUPtr

◆ Ptr

◆ UPtr

Constructor & Destructor Documentation

◆ ForwardKinematics() [1/3]

tesseract_kinematics::ForwardKinematics::ForwardKinematics ( )
default

◆ ~ForwardKinematics()

virtual tesseract_kinematics::ForwardKinematics::~ForwardKinematics ( )
virtualdefault

◆ ForwardKinematics() [2/3]

tesseract_kinematics::ForwardKinematics::ForwardKinematics ( const ForwardKinematics )
default

◆ ForwardKinematics() [3/3]

tesseract_kinematics::ForwardKinematics::ForwardKinematics ( ForwardKinematics &&  )
default

Member Function Documentation

◆ calcFwdKin()

virtual tesseract_common::TransformMap tesseract_kinematics::ForwardKinematics::calcFwdKin ( const Eigen::Ref< const Eigen::VectorXd > &  joint_angles) const
pure virtual

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

Implemented in tesseract_kinematics::KDLFwdKinChain.

◆ calcJacobian()

virtual Eigen::MatrixXd tesseract_kinematics::ForwardKinematics::calcJacobian ( const Eigen::Ref< const Eigen::VectorXd > &  joint_angles,
const std::string &  link_name 
) const
pure virtual

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

Implemented in tesseract_kinematics::KDLFwdKinChain.

◆ clone()

virtual ForwardKinematics::UPtr tesseract_kinematics::ForwardKinematics::clone ( ) const
pure virtual

Clone the forward kinematics object.

Implemented in tesseract_kinematics::KDLFwdKinChain.

◆ getBaseLinkName()

virtual std::string tesseract_kinematics::ForwardKinematics::getBaseLinkName ( ) const
pure virtual

Get the robot base link name.

Implemented in tesseract_kinematics::KDLFwdKinChain.

◆ getJointNames()

virtual std::vector< std::string > tesseract_kinematics::ForwardKinematics::getJointNames ( ) const
pure virtual

Get list of joint names for kinematic object.

Returns
A vector of joint names

Implemented in tesseract_kinematics::KDLFwdKinChain.

◆ getSolverName()

virtual std::string tesseract_kinematics::ForwardKinematics::getSolverName ( ) const
pure virtual

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

Implemented in tesseract_kinematics::KDLFwdKinChain.

◆ getTipLinkNames()

virtual std::vector< std::string > tesseract_kinematics::ForwardKinematics::getTipLinkNames ( ) const
pure virtual

Get list of tip link names for kinematic object.

Returns
A vector of link names

Implemented in tesseract_kinematics::KDLFwdKinChain.

◆ numJoints()

virtual Eigen::Index tesseract_kinematics::ForwardKinematics::numJoints ( ) const
pure virtual

Number of joints in robot.

Returns
Number of joints in robot

Implemented in tesseract_kinematics::KDLFwdKinChain.

◆ operator=() [1/2]

ForwardKinematics & tesseract_kinematics::ForwardKinematics::operator= ( const ForwardKinematics )
default

◆ operator=() [2/2]

ForwardKinematics & tesseract_kinematics::ForwardKinematics::operator= ( ForwardKinematics &&  )
default

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