Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
tesseract_kinematics::ROPInvKin Class Reference

Robot on Positioner Inverse kinematic implementation. More...

#include <rop_inv_kin.h>

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

Public Types

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

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...
 
ROPInvKinoperator= (const ROPInvKin &other)
 
ROPInvKinoperator= (ROPInvKin &&)=default
 
 ROPInvKin (const ROPInvKin &other)
 
 ROPInvKin (const tesseract_scene_graph::SceneGraph &scene_graph, const tesseract_scene_graph::SceneState &scene_state, InverseKinematics::UPtr manipulator, double manipulator_reach, std::unique_ptr< ForwardKinematics > positioner, const Eigen::MatrixX2d &positioner_sample_range, const Eigen::VectorXd &positioner_sample_resolution, std::string solver_name=DEFAULT_ROP_INV_KIN_SOLVER_NAME)
 Initializes Inverse Kinematics for a robot on a positioner. More...
 
 ROPInvKin (const tesseract_scene_graph::SceneGraph &scene_graph, const tesseract_scene_graph::SceneState &scene_state, InverseKinematics::UPtr manipulator, double manipulator_reach, std::unique_ptr< ForwardKinematics > positioner, const Eigen::VectorXd &positioner_sample_resolution, std::string solver_name=DEFAULT_ROP_INV_KIN_SOLVER_NAME)
 Initializes Inverse Kinematics for a robot on a positioner. More...
 
 ROPInvKin (ROPInvKin &&)=default
 
 ~ROPInvKin () 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 ()
 

Private Member Functions

IKSolutions calcInvKinHelper (const tesseract_common::TransformMap &tip_link_poses, const Eigen::Ref< const Eigen::VectorXd > &seed) const
 calcFwdKin helper function More...
 
void ikAt (IKSolutions &solutions, const tesseract_common::TransformMap &tip_link_poses, Eigen::VectorXd &positioner_pose, const Eigen::Ref< const Eigen::VectorXd > &seed) const
 
void init (const tesseract_scene_graph::SceneGraph &scene_graph, const tesseract_scene_graph::SceneState &scene_state, InverseKinematics::UPtr manipulator, double manipulator_reach, std::unique_ptr< ForwardKinematics > positioner, const Eigen::MatrixX2d &poitioner_sample_range, const Eigen::VectorXd &positioner_sample_resolution, std::string solver_name=DEFAULT_ROP_INV_KIN_SOLVER_NAME)
 
void nested_ik (IKSolutions &solutions, int loop_level, const std::vector< Eigen::VectorXd > &dof_range, const tesseract_common::TransformMap &tip_link_poses, Eigen::VectorXd &positioner_pose, const Eigen::Ref< const Eigen::VectorXd > &seed) const
 

Private Attributes

Eigen::Index dof_ { -1 }
 
std::vector< Eigen::VectorXd > dof_range_
 
std::vector< std::string > joint_names_
 
InverseKinematics::UPtr manip_inv_kin_
 
double manip_reach_ { 0 }
 
std::string manip_tip_link_
 
std::unique_ptr< ForwardKinematicspositioner_fwd_kin_
 
std::string positioner_tip_link_
 
Eigen::Isometry3d positioner_to_robot_ { Eigen::Isometry3d::Identity() }
 
std::string solver_name_ { DEFAULT_ROP_INV_KIN_SOLVER_NAME }
 Name of this solver. More...
 

Detailed Description

Robot on Positioner Inverse kinematic implementation.

Definition at line 46 of file rop_inv_kin.h.

Member Typedef Documentation

◆ ConstPtr

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

Definition at line 54 of file rop_inv_kin.h.

◆ ConstUPtr

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

Definition at line 56 of file rop_inv_kin.h.

◆ Ptr

Definition at line 53 of file rop_inv_kin.h.

◆ UPtr

Definition at line 55 of file rop_inv_kin.h.

Constructor & Destructor Documentation

◆ ~ROPInvKin()

tesseract_kinematics::ROPInvKin::~ROPInvKin ( )
overridedefault

◆ ROPInvKin() [1/4]

tesseract_kinematics::ROPInvKin::ROPInvKin ( const ROPInvKin other)

Definition at line 162 of file rop_inv_kin.cpp.

◆ ROPInvKin() [2/4]

tesseract_kinematics::ROPInvKin::ROPInvKin ( ROPInvKin &&  )
default

◆ ROPInvKin() [3/4]

tesseract_kinematics::ROPInvKin::ROPInvKin ( const tesseract_scene_graph::SceneGraph scene_graph,
const tesseract_scene_graph::SceneState scene_state,
InverseKinematics::UPtr  manipulator,
double  manipulator_reach,
std::unique_ptr< ForwardKinematics positioner,
const Eigen::VectorXd &  positioner_sample_resolution,
std::string  solver_name = DEFAULT_ROP_INV_KIN_SOLVER_NAME 
)

Initializes Inverse Kinematics for a robot on a positioner.

Parameters
scene_graphThe Tesseract Scene Graph
scene_stateThe Tesseract Scene State
manipulator
manipulator_reach
positioner
positioner_sample_resolution
solver_nameThe name given to the solver. This is exposed so you may have same solver with different sampling resolutions
Returns
True if init() completes successfully

Definition at line 38 of file rop_inv_kin.cpp.

◆ ROPInvKin() [4/4]

tesseract_kinematics::ROPInvKin::ROPInvKin ( const tesseract_scene_graph::SceneGraph scene_graph,
const tesseract_scene_graph::SceneState scene_state,
InverseKinematics::UPtr  manipulator,
double  manipulator_reach,
std::unique_ptr< ForwardKinematics positioner,
const Eigen::MatrixX2d &  positioner_sample_range,
const Eigen::VectorXd &  positioner_sample_resolution,
std::string  solver_name = DEFAULT_ROP_INV_KIN_SOLVER_NAME 
)

Initializes Inverse Kinematics for a robot on a positioner.

Parameters
scene_graphThe Tesseract Scene Graph
scene_stateThe Tesseract Scene State
manipulator
manipulator_reach
positioner
positioner_sample_range
positioner_sample_resolution
solver_nameThe name given to the solver. This is exposed so you may have same solver with different sampling resolutions
Returns
True if init() completes successfully

Definition at line 73 of file rop_inv_kin.cpp.

Member Function Documentation

◆ calcInvKin()

IKSolutions tesseract_kinematics::ROPInvKin::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 237 of file rop_inv_kin.cpp.

◆ calcInvKinHelper()

IKSolutions tesseract_kinematics::ROPInvKin::calcInvKinHelper ( const tesseract_common::TransformMap tip_link_poses,
const Eigen::Ref< const Eigen::VectorXd > &  seed 
) const
private

calcFwdKin helper function

Definition at line 178 of file rop_inv_kin.cpp.

◆ clone()

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

Clone the forward kinematics object.

Implements tesseract_kinematics::InverseKinematics.

Definition at line 160 of file rop_inv_kin.cpp.

◆ getBaseLinkName()

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

Get the robot base link name.

Implements tesseract_kinematics::InverseKinematics.

Definition at line 250 of file rop_inv_kin.cpp.

◆ getJointNames()

std::vector< std::string > tesseract_kinematics::ROPInvKin::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 246 of file rop_inv_kin.cpp.

◆ getSolverName()

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

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

Implements tesseract_kinematics::InverseKinematics.

Definition at line 256 of file rop_inv_kin.cpp.

◆ getTipLinkNames()

std::vector< std::string > tesseract_kinematics::ROPInvKin::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 254 of file rop_inv_kin.cpp.

◆ getWorkingFrame()

std::string tesseract_kinematics::ROPInvKin::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 252 of file rop_inv_kin.cpp.

◆ ikAt()

void tesseract_kinematics::ROPInvKin::ikAt ( IKSolutions solutions,
const tesseract_common::TransformMap tip_link_poses,
Eigen::VectorXd &  positioner_pose,
const Eigen::Ref< const Eigen::VectorXd > &  seed 
) const
private

Definition at line 207 of file rop_inv_kin.cpp.

◆ init()

void tesseract_kinematics::ROPInvKin::init ( const tesseract_scene_graph::SceneGraph scene_graph,
const tesseract_scene_graph::SceneState scene_state,
InverseKinematics::UPtr  manipulator,
double  manipulator_reach,
std::unique_ptr< ForwardKinematics positioner,
const Eigen::MatrixX2d &  poitioner_sample_range,
const Eigen::VectorXd &  positioner_sample_resolution,
std::string  solver_name = DEFAULT_ROP_INV_KIN_SOLVER_NAME 
)
private

Definition at line 92 of file rop_inv_kin.cpp.

◆ nested_ik()

void tesseract_kinematics::ROPInvKin::nested_ik ( IKSolutions solutions,
int  loop_level,
const std::vector< Eigen::VectorXd > &  dof_range,
const tesseract_common::TransformMap tip_link_poses,
Eigen::VectorXd &  positioner_pose,
const Eigen::Ref< const Eigen::VectorXd > &  seed 
) const
private

Definition at line 187 of file rop_inv_kin.cpp.

◆ numJoints()

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

Number of joints in robot.

Returns
Number of joints in robot

Implements tesseract_kinematics::InverseKinematics.

Definition at line 248 of file rop_inv_kin.cpp.

◆ operator=() [1/2]

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

Definition at line 164 of file rop_inv_kin.cpp.

◆ operator=() [2/2]

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

Member Data Documentation

◆ dof_

Eigen::Index tesseract_kinematics::ROPInvKin::dof_ { -1 }
private

Definition at line 124 of file rop_inv_kin.h.

◆ dof_range_

std::vector<Eigen::VectorXd> tesseract_kinematics::ROPInvKin::dof_range_
private

Definition at line 126 of file rop_inv_kin.h.

◆ joint_names_

std::vector<std::string> tesseract_kinematics::ROPInvKin::joint_names_
private

Definition at line 118 of file rop_inv_kin.h.

◆ manip_inv_kin_

InverseKinematics::UPtr tesseract_kinematics::ROPInvKin::manip_inv_kin_
private

Definition at line 119 of file rop_inv_kin.h.

◆ manip_reach_

double tesseract_kinematics::ROPInvKin::manip_reach_ { 0 }
private

Definition at line 123 of file rop_inv_kin.h.

◆ manip_tip_link_

std::string tesseract_kinematics::ROPInvKin::manip_tip_link_
private

Definition at line 121 of file rop_inv_kin.h.

◆ positioner_fwd_kin_

std::unique_ptr<ForwardKinematics> tesseract_kinematics::ROPInvKin::positioner_fwd_kin_
private

Definition at line 120 of file rop_inv_kin.h.

◆ positioner_tip_link_

std::string tesseract_kinematics::ROPInvKin::positioner_tip_link_
private

Definition at line 122 of file rop_inv_kin.h.

◆ positioner_to_robot_

Eigen::Isometry3d tesseract_kinematics::ROPInvKin::positioner_to_robot_ { Eigen::Isometry3d::Identity() }
private

Definition at line 125 of file rop_inv_kin.h.

◆ solver_name_

std::string tesseract_kinematics::ROPInvKin::solver_name_ { DEFAULT_ROP_INV_KIN_SOLVER_NAME }
private

Name of this solver.

Definition at line 127 of file rop_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