Public Types | Public Member Functions | List of all members
tesseract_kinematics::InverseKinematics Class Referenceabstract

Inverse kinematics functions. More...

#include <inverse_kinematics.h>

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

Public Types

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

virtual IKSolutions calcInvKin (const tesseract_common::TransformMap &tip_link_poses, const Eigen::Ref< const Eigen::VectorXd > &seed) const =0
 Calculates joint solutions given a pose for each tip link. More...
 
virtual InverseKinematics::UPtr clone () const =0
 Clone the forward kinematics object. 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::string getSolverName () const =0
 Get the name of the solver. Recommend using the name of the class. More...
 
virtual std::vector< std::string > getTipLinkNames () const =0
 Get the names of the tip links of the kinematics group. More...
 
virtual std::string getWorkingFrame () const =0
 Get the inverse kinematics working frame. More...
 
 InverseKinematics ()=default
 
 InverseKinematics (const InverseKinematics &)=default
 
 InverseKinematics (InverseKinematics &&)=default
 
virtual Eigen::Index numJoints () const =0
 Number of joints in robot. More...
 
InverseKinematicsoperator= (const InverseKinematics &)=default
 
InverseKinematicsoperator= (InverseKinematics &&)=default
 
virtual ~InverseKinematics ()
 

Detailed Description

Inverse kinematics functions.

Definition at line 43 of file inverse_kinematics.h.

Member Typedef Documentation

◆ ConstPtr

Definition at line 51 of file inverse_kinematics.h.

◆ ConstUPtr

Definition at line 53 of file inverse_kinematics.h.

◆ Ptr

Definition at line 50 of file inverse_kinematics.h.

◆ UPtr

Definition at line 52 of file inverse_kinematics.h.

Constructor & Destructor Documentation

◆ InverseKinematics() [1/3]

tesseract_kinematics::InverseKinematics::InverseKinematics ( )
default

◆ ~InverseKinematics()

tesseract_kinematics::InverseKinematics::~InverseKinematics ( )
virtualdefault

◆ InverseKinematics() [2/3]

tesseract_kinematics::InverseKinematics::InverseKinematics ( const InverseKinematics )
default

◆ InverseKinematics() [3/3]

tesseract_kinematics::InverseKinematics::InverseKinematics ( InverseKinematics &&  )
default

Member Function Documentation

◆ calcInvKin()

virtual IKSolutions tesseract_kinematics::InverseKinematics::calcInvKin ( const tesseract_common::TransformMap tip_link_poses,
const Eigen::Ref< const Eigen::VectorXd > &  seed 
) const
pure virtual

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)

Implemented in tesseract_kinematics::URInvKin, tesseract_kinematics::KDLInvKinChainNR, tesseract_kinematics::KDLInvKinChainNR_JL, tesseract_kinematics::ROPInvKin, tesseract_kinematics::REPInvKin, tesseract_kinematics::KDLInvKinChainLMA, tesseract_kinematics::OPWInvKin, and tesseract_kinematics::IKFastInvKin.

◆ clone()

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

◆ getBaseLinkName()

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

◆ getJointNames()

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

◆ getSolverName()

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

◆ getTipLinkNames()

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

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.

Implemented in tesseract_kinematics::URInvKin, tesseract_kinematics::KDLInvKinChainNR, tesseract_kinematics::KDLInvKinChainNR_JL, tesseract_kinematics::ROPInvKin, tesseract_kinematics::REPInvKin, tesseract_kinematics::KDLInvKinChainLMA, tesseract_kinematics::OPWInvKin, and tesseract_kinematics::IKFastInvKin.

◆ getWorkingFrame()

virtual std::string tesseract_kinematics::InverseKinematics::getWorkingFrame ( ) const
pure virtual

◆ numJoints()

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

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

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