Public Types | Public Member Functions | Protected Attributes | List of all members
tesseract_kinematics::URInvKin Class Reference

Universal Robot Inverse Kinematics Implementation. More...

#include <ur_inv_kin.h>

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

Public Types

using ConstPtr = std::shared_ptr< const URInvKin >
 
using ConstUPtr = std::unique_ptr< const URInvKin >
 
using Ptr = std::shared_ptr< URInvKin >
 
using UPtr = std::unique_ptr< URInvKin >
 
- 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

tesseract_kinematics::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...
 
Eigen::Index numJoints () const override final
 Number of joints in robot. More...
 
URInvKinoperator= (const URInvKin &other)
 
URInvKinoperator= (URInvKin &&)=default
 
 URInvKin (const URInvKin &other)
 
 URInvKin (URInvKin &&)=default
 
 URInvKin (URParameters params, std::string base_link_name, std::string tip_link_name, std::vector< std::string > joint_names, std::string solver_name=UR_INV_KIN_CHAIN_SOLVER_NAME)
 init Initialize UR Inverse Kinematics More...
 
 ~URInvKin () 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 ()
 

Protected Attributes

std::string base_link_name_
 Link name of first link in the kinematic object. More...
 
std::vector< std::string > joint_names_
 Joint names for the kinematic object. More...
 
URParameters params_
 The UR Inverse kinematics parameters. More...
 
std::string solver_name_ { UR_INV_KIN_CHAIN_SOLVER_NAME }
 Name of this solver. More...
 
std::string tip_link_name_
 Link name of last kink in the kinematic object. More...
 

Detailed Description

Universal Robot Inverse Kinematics Implementation.

Definition at line 85 of file ur_inv_kin.h.

Member Typedef Documentation

◆ ConstPtr

using tesseract_kinematics::URInvKin::ConstPtr = std::shared_ptr<const URInvKin>

Definition at line 93 of file ur_inv_kin.h.

◆ ConstUPtr

using tesseract_kinematics::URInvKin::ConstUPtr = std::unique_ptr<const URInvKin>

Definition at line 95 of file ur_inv_kin.h.

◆ Ptr

Definition at line 92 of file ur_inv_kin.h.

◆ UPtr

Definition at line 94 of file ur_inv_kin.h.

Constructor & Destructor Documentation

◆ ~URInvKin()

tesseract_kinematics::URInvKin::~URInvKin ( )
overridedefault

◆ URInvKin() [1/3]

tesseract_kinematics::URInvKin::URInvKin ( const URInvKin other)

Definition at line 242 of file ur_inv_kin.cpp.

◆ URInvKin() [2/3]

tesseract_kinematics::URInvKin::URInvKin ( URInvKin &&  )
default

◆ URInvKin() [3/3]

tesseract_kinematics::URInvKin::URInvKin ( URParameters  params,
std::string  base_link_name,
std::string  tip_link_name,
std::vector< std::string >  joint_names,
std::string  solver_name = UR_INV_KIN_CHAIN_SOLVER_NAME 
)

init Initialize UR Inverse Kinematics

Parameters
paramsUR kinematics parameters
base_link_nameThe name of the base link for the kinematic chain
tip_link_nameThe name of the tip link for the kinematic chain
joint_namesThe joint names for the kinematic chain
solver_nameThe solver name of the kinematic chain

Definition at line 225 of file ur_inv_kin.cpp.

Member Function Documentation

◆ calcInvKin()

IKSolutions tesseract_kinematics::URInvKin::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 255 of file ur_inv_kin.cpp.

◆ clone()

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

Clone the forward kinematics object.

Implements tesseract_kinematics::InverseKinematics.

Definition at line 240 of file ur_inv_kin.cpp.

◆ getBaseLinkName()

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

Get the robot base link name.

Implements tesseract_kinematics::InverseKinematics.

Definition at line 289 of file ur_inv_kin.cpp.

◆ getJointNames()

std::vector< std::string > tesseract_kinematics::URInvKin::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 288 of file ur_inv_kin.cpp.

◆ getSolverName()

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

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

Implements tesseract_kinematics::InverseKinematics.

Definition at line 292 of file ur_inv_kin.cpp.

◆ getTipLinkNames()

std::vector< std::string > tesseract_kinematics::URInvKin::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 291 of file ur_inv_kin.cpp.

◆ getWorkingFrame()

std::string tesseract_kinematics::URInvKin::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 290 of file ur_inv_kin.cpp.

◆ numJoints()

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

Number of joints in robot.

Returns
Number of joints in robot

Implements tesseract_kinematics::InverseKinematics.

Definition at line 287 of file ur_inv_kin.cpp.

◆ operator=() [1/2]

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

Definition at line 244 of file ur_inv_kin.cpp.

◆ operator=() [2/2]

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

Member Data Documentation

◆ base_link_name_

std::string tesseract_kinematics::URInvKin::base_link_name_
protected

Link name of first link in the kinematic object.

Definition at line 130 of file ur_inv_kin.h.

◆ joint_names_

std::vector<std::string> tesseract_kinematics::URInvKin::joint_names_
protected

Joint names for the kinematic object.

Definition at line 132 of file ur_inv_kin.h.

◆ params_

URParameters tesseract_kinematics::URInvKin::params_
protected

The UR Inverse kinematics parameters.

Definition at line 129 of file ur_inv_kin.h.

◆ solver_name_

std::string tesseract_kinematics::URInvKin::solver_name_ { UR_INV_KIN_CHAIN_SOLVER_NAME }
protected

Name of this solver.

Definition at line 133 of file ur_inv_kin.h.

◆ tip_link_name_

std::string tesseract_kinematics::URInvKin::tip_link_name_
protected

Link name of last kink in the kinematic object.

Definition at line 131 of file ur_inv_kin.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