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

OPW Inverse Kinematics Implementation. More...

#include <opw_inv_kin.h>

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

Public Types

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

Public Member Functions

 ~OPWInvKin () override=default
 
 OPWInvKin (const OPWInvKin &other)
 
OPWInvKinoperator= (const OPWInvKin &other)
 
 OPWInvKin (OPWInvKin &&)=default
 
OPWInvKinoperator= (OPWInvKin &&)=default
 
 OPWInvKin (opw_kinematics::Parameters< double > params, std::string base_link_name, std::string tip_link_name, std::vector< std::string > joint_names, std::string solver_name=OPW_INV_KIN_CHAIN_SOLVER_NAME)
 Construct OPW Inverse Kinematics. More...
 
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...
 
Eigen::Index numJoints () const override final
 Number of joints in robot. More...
 
std::vector< std::string > getJointNames () const override final
 Get list of joint names for kinematic object. More...
 
std::string getBaseLinkName () const override final
 Get the robot base link name. More...
 
std::string getWorkingFrame () const override final
 Get the inverse kinematics working frame. More...
 
std::vector< std::string > getTipLinkNames () const override final
 Get the names of the tip links of the kinematics group. More...
 
std::string getSolverName () const override final
 Get the name of the solver. Recommend using the name of the class. More...
 
InverseKinematics::UPtr clone () const override final
 Clone the forward kinematics object. More...
 
- Public Member Functions inherited from tesseract_kinematics::InverseKinematics
 InverseKinematics ()=default
 
virtual ~InverseKinematics ()=default
 
 InverseKinematics (const InverseKinematics &)=default
 
InverseKinematicsoperator= (const InverseKinematics &)=default
 
 InverseKinematics (InverseKinematics &&)=default
 
InverseKinematicsoperator= (InverseKinematics &&)=default
 
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 std::vector< std::string > getJointNames () const =0
 Get list of joint names for kinematic object. More...
 
virtual Eigen::Index numJoints () const =0
 Number of joints in robot. More...
 
virtual std::string getBaseLinkName () const =0
 Get the robot base link name. More...
 
virtual std::string getWorkingFrame () const =0
 Get the inverse kinematics working frame. More...
 
virtual std::vector< std::string > getTipLinkNames () const =0
 Get the names of the tip links of the kinematics group. More...
 
virtual std::string getSolverName () const =0
 Get the name of the solver. Recommend using the name of the class. More...
 
virtual InverseKinematics::UPtr clone () const =0
 Clone the forward kinematics object. More...
 

Protected Attributes

opw_kinematics::Parameters< double > params_
 The opw kinematics parameters. More...
 
std::string base_link_name_
 Link name of first link in the kinematic object. More...
 
std::string tip_link_name_
 Link name of last kink in the kinematic object. More...
 
std::vector< std::string > joint_names_
 Joint names for the kinematic object. More...
 
std::string solver_name_ { OPW_INV_KIN_CHAIN_SOLVER_NAME }
 Name of this solver. More...
 

Detailed Description

OPW Inverse Kinematics Implementation.

Member Typedef Documentation

◆ ConstPtr

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

◆ ConstUPtr

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

◆ Ptr

◆ UPtr

Constructor & Destructor Documentation

◆ ~OPWInvKin()

tesseract_kinematics::OPWInvKin::~OPWInvKin ( )
overridedefault

◆ OPWInvKin() [1/3]

tesseract_kinematics::OPWInvKin::OPWInvKin ( const OPWInvKin other)

◆ OPWInvKin() [2/3]

tesseract_kinematics::OPWInvKin::OPWInvKin ( OPWInvKin &&  )
default

◆ OPWInvKin() [3/3]

tesseract_kinematics::OPWInvKin::OPWInvKin ( opw_kinematics::Parameters< double >  params,
std::string  base_link_name,
std::string  tip_link_name,
std::vector< std::string >  joint_names,
std::string  solver_name = OPW_INV_KIN_CHAIN_SOLVER_NAME 
)

Construct OPW Inverse Kinematics.

Parameters
paramsOPW 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

Member Function Documentation

◆ calcInvKin()

IKSolutions tesseract_kinematics::OPWInvKin::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.

◆ clone()

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

Clone the forward kinematics object.

Implements tesseract_kinematics::InverseKinematics.

◆ getBaseLinkName()

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

Get the robot base link name.

Implements tesseract_kinematics::InverseKinematics.

◆ getJointNames()

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

Get list of joint names for kinematic object.

Returns
A vector of joint names, joint_list_

Implements tesseract_kinematics::InverseKinematics.

◆ getSolverName()

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

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

Implements tesseract_kinematics::InverseKinematics.

◆ getTipLinkNames()

std::vector< std::string > tesseract_kinematics::OPWInvKin::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.

◆ getWorkingFrame()

std::string tesseract_kinematics::OPWInvKin::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.

◆ numJoints()

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

Number of joints in robot.

Returns
Number of joints in robot

Implements tesseract_kinematics::InverseKinematics.

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

Member Data Documentation

◆ base_link_name_

std::string tesseract_kinematics::OPWInvKin::base_link_name_
protected

Link name of first link in the kinematic object.

◆ joint_names_

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

Joint names for the kinematic object.

◆ params_

opw_kinematics::Parameters<double> tesseract_kinematics::OPWInvKin::params_
protected

The opw kinematics parameters.

◆ solver_name_

std::string tesseract_kinematics::OPWInvKin::solver_name_ { OPW_INV_KIN_CHAIN_SOLVER_NAME }
protected

Name of this solver.

◆ tip_link_name_

std::string tesseract_kinematics::OPWInvKin::tip_link_name_
protected

Link name of last kink in the kinematic object.


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