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

#include <kinematic_group.h>

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

Public Types

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

Public Member Functions

IKSolutions calcInvKin (const KinGroupIKInput &tip_link_pose, const Eigen::Ref< const Eigen::VectorXd > &seed) const
 Calculates joint solutions given a pose. More...
 
IKSolutions calcInvKin (const KinGroupIKInputs &tip_link_poses, const Eigen::Ref< const Eigen::VectorXd > &seed) const
 Calculates joint solutions given a pose. More...
 
std::vector< std::string > getAllPossibleTipLinkNames () const
 Get the tip link name. More...
 
std::vector< std::string > getAllValidWorkingFrames () const
 Returns all possible working frames in which goal poses can be defined. More...
 
const InverseKinematicsgetInverseKinematics () const
 Get the inverse kinematics sovler. More...
 
 KinematicGroup (const KinematicGroup &other)
 
 KinematicGroup (KinematicGroup &&)=default
 
 KinematicGroup (std::string name, std::vector< std::string > joint_names, std::unique_ptr< InverseKinematics > inv_kin, const tesseract_scene_graph::SceneGraph &scene_graph, const tesseract_scene_graph::SceneState &scene_state)
 Create a kinematics group with inverse kinematics. More...
 
KinematicGroupoperator= (const KinematicGroup &other)
 
KinematicGroupoperator= (KinematicGroup &&)=default
 
 ~KinematicGroup () override
 
- Public Member Functions inherited from tesseract_kinematics::JointGroup
tesseract_common::TransformMap calcFwdKin (const Eigen::Ref< const Eigen::VectorXd > &joint_angles) const
 Calculates tool pose of robot chain. More...
 
Eigen::MatrixXd calcJacobian (const Eigen::Ref< const Eigen::VectorXd > &joint_angles, const std::string &base_link_name, const std::string &link_name) const
 Calculated jacobian of robot given joint angles. More...
 
Eigen::MatrixXd calcJacobian (const Eigen::Ref< const Eigen::VectorXd > &joint_angles, const std::string &base_link_name, const std::string &link_name, const Eigen::Vector3d &link_point) const
 Calculated jacobian of robot given joint angles. More...
 
Eigen::MatrixXd calcJacobian (const Eigen::Ref< const Eigen::VectorXd > &joint_angles, const std::string &link_name) const
 Calculated jacobian of robot given joint angles. More...
 
Eigen::MatrixXd calcJacobian (const Eigen::Ref< const Eigen::VectorXd > &joint_angles, const std::string &link_name, const Eigen::Vector3d &link_point) const
 Calculated jacobian of robot given joint angles. More...
 
bool checkJoints (const Eigen::Ref< const Eigen::VectorXd > &vec) const
 Check for consistency in # and limits of joints. More...
 
std::vector< std::string > getActiveLinkNames () const
 Get list of active link names (with and without geometry) for kinematic object. More...
 
std::string getBaseLinkName () const
 Get the robot base link name. More...
 
std::vector< std::string > getJointNames () const
 Get list of joint names for kinematic object. More...
 
tesseract_common::KinematicLimits getLimits () const
 Get the kinematic limits (joint, velocity, acceleration, etc.) More...
 
std::vector< std::string > getLinkNames () const
 Get list of all link names (with and without geometry) for kinematic object. More...
 
std::string getName () const
 Name of the manipulator. More...
 
std::vector< Eigen::Index > getRedundancyCapableJointIndices () const
 Get vector indicating which joints are capable of producing redundant solutions. More...
 
std::vector< std::string > getStaticLinkNames () const
 Get list of static link names (with and without geometry) for kinematic object. More...
 
bool hasLinkName (const std::string &link_name) const
 Check if link name exists. More...
 
bool isActiveLinkName (const std::string &link_name) const
 Check if link is an active link. More...
 
 JointGroup (const JointGroup &other)
 
 JointGroup (JointGroup &&)=default
 
 JointGroup (std::string name, std::vector< std::string > joint_names, const tesseract_scene_graph::SceneGraph &scene_graph, const tesseract_scene_graph::SceneState &scene_state)
 Create a kinematics group without inverse kinematics for the provided joint names. More...
 
Eigen::Index numJoints () const
 Number of joints in robot. More...
 
JointGroupoperator= (const JointGroup &other)
 
JointGroupoperator= (JointGroup &&)=default
 
void setLimits (const tesseract_common::KinematicLimits &limits)
 Setter for kinematic limits (joint, velocity, acceleration, etc.) More...
 
virtual ~JointGroup ()
 

Private Attributes

std::unique_ptr< InverseKinematicsinv_kin_
 
std::vector< Eigen::Index > inv_kin_joint_map_
 
std::unordered_map< std::string, std::string > inv_tip_links_map_
 
Eigen::Isometry3d inv_to_fwd_base_ { Eigen::Isometry3d::Identity() }
 
std::vector< std::string > joint_names_
 
bool reorder_required_ { false }
 
std::vector< std::string > working_frames_
 

Additional Inherited Members

- Protected Attributes inherited from tesseract_kinematics::JointGroup
std::vector< Eigen::Index > jacobian_map_
 
std::vector< std::string > joint_names_
 
tesseract_common::KinematicLimits limits_
 
std::vector< std::string > link_names_
 
std::string name_
 
std::vector< Eigen::Index > redundancy_indices_
 
tesseract_scene_graph::SceneState state_
 
std::unique_ptr< tesseract_scene_graph::StateSolverstate_solver_
 
std::vector< std::string > static_link_names_
 
tesseract_common::TransformMap static_link_transforms_
 

Detailed Description

Definition at line 75 of file kinematic_group.h.

Member Typedef Documentation

◆ ConstPtr

Definition at line 83 of file kinematic_group.h.

◆ ConstUPtr

Definition at line 85 of file kinematic_group.h.

◆ Ptr

Definition at line 82 of file kinematic_group.h.

◆ UPtr

Definition at line 84 of file kinematic_group.h.

Constructor & Destructor Documentation

◆ ~KinematicGroup()

tesseract_kinematics::KinematicGroup::~KinematicGroup ( )
overridedefault

◆ KinematicGroup() [1/3]

tesseract_kinematics::KinematicGroup::KinematicGroup ( const KinematicGroup other)

Definition at line 193 of file kinematic_group.cpp.

◆ KinematicGroup() [2/3]

tesseract_kinematics::KinematicGroup::KinematicGroup ( KinematicGroup &&  )
default

◆ KinematicGroup() [3/3]

tesseract_kinematics::KinematicGroup::KinematicGroup ( std::string  name,
std::vector< std::string >  joint_names,
std::unique_ptr< InverseKinematics inv_kin,
const tesseract_scene_graph::SceneGraph scene_graph,
const tesseract_scene_graph::SceneState scene_state 
)

Create a kinematics group with inverse kinematics.

Parameters
nameThe name of the kinematic group
inv_kinThe inverse kinematics object to create kinematic group from
scene_graphThe scene graph
scene_stateThe scene state

Definition at line 106 of file kinematic_group.cpp.

Member Function Documentation

◆ calcInvKin() [1/2]

IKSolutions tesseract_kinematics::KinematicGroup::calcInvKin ( const KinGroupIKInput tip_link_pose,
const Eigen::Ref< const Eigen::VectorXd > &  seed 
) const

Calculates joint solutions given a pose.

If redundant solutions are needed see utility function getRedundantSolutions.

Parameters
tip_link_poseThe input information to solve inverse kinematics for. This is a convenience function for when only one tip link exists
seedVector of seed joint angles (size must match number of joints in robot chain)
Returns
A vector of solutions, If empty it failed to find a solution (including uninitialized)

Definition at line 301 of file kinematic_group.cpp.

◆ calcInvKin() [2/2]

IKSolutions tesseract_kinematics::KinematicGroup::calcInvKin ( const KinGroupIKInputs tip_link_poses,
const Eigen::Ref< const Eigen::VectorXd > &  seed 
) const

Calculates joint solutions given a pose.

If redundant solutions are needed see utility function getRedundantSolutions.

Parameters
tip_link_posesThe input information to solve inverse kinematics for. There must be an input for each link provided in getTipLinkNames
seedVector of seed joint angles (size must match number of joints in robot chain)
Returns
A vector of solutions, If empty it failed to find a solution (including uninitialized)

Definition at line 210 of file kinematic_group.cpp.

◆ getAllPossibleTipLinkNames()

std::vector< std::string > tesseract_kinematics::KinematicGroup::getAllPossibleTipLinkNames ( ) const

Get the tip link name.

The inverse kinematics solver requires that all poses be solved for a set of tip link frames that terminate a kinematic chain or tree. In the case of some closed-form IK solvers, this tip link must the tool flange of the robot rather than another preferred link. If the desired tip link is a statically connected child of the required IK solver tip link, then the target IK pose can be transformed into a target pose for the IK solver tip link. This function identifies all possible tip links that can be used for IK (i.e. static child links of the IK solver tip link(s)) and internally performs the appropriate transformations when solving IK

Definition at line 309 of file kinematic_group.cpp.

◆ getAllValidWorkingFrames()

std::vector< std::string > tesseract_kinematics::KinematicGroup::getAllValidWorkingFrames ( ) const

Returns all possible working frames in which goal poses can be defined.

The inverse kinematics solver requires that all poses be defined relative to a single working frame. However if this working frame is static, a pose can be defined in another static frame in the environment and transformed into the IK solver working frame. Similarly if the working frame is an active link (e.g. attached to a part positioner), a target pose can also be defined relative to any child link of the working frame and transformed into the IK solver working frame. This function identifies all of these other possible working frames and performs the appropriate transformations internally when solving IK.

Definition at line 307 of file kinematic_group.cpp.

◆ getInverseKinematics()

const InverseKinematics & tesseract_kinematics::KinematicGroup::getInverseKinematics ( ) const

Get the inverse kinematics sovler.

Returns
The inverse kinematics solver

Definition at line 319 of file kinematic_group.cpp.

◆ operator=() [1/2]

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

Definition at line 197 of file kinematic_group.cpp.

◆ operator=() [2/2]

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

Member Data Documentation

◆ inv_kin_

std::unique_ptr<InverseKinematics> tesseract_kinematics::KinematicGroup::inv_kin_
private

Definition at line 156 of file kinematic_group.h.

◆ inv_kin_joint_map_

std::vector<Eigen::Index> tesseract_kinematics::KinematicGroup::inv_kin_joint_map_
private

Definition at line 155 of file kinematic_group.h.

◆ inv_tip_links_map_

std::unordered_map<std::string, std::string> tesseract_kinematics::KinematicGroup::inv_tip_links_map_
private

Definition at line 159 of file kinematic_group.h.

◆ inv_to_fwd_base_

Eigen::Isometry3d tesseract_kinematics::KinematicGroup::inv_to_fwd_base_ { Eigen::Isometry3d::Identity() }
private

Definition at line 157 of file kinematic_group.h.

◆ joint_names_

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

Definition at line 153 of file kinematic_group.h.

◆ reorder_required_

bool tesseract_kinematics::KinematicGroup::reorder_required_ { false }
private

Definition at line 154 of file kinematic_group.h.

◆ working_frames_

std::vector<std::string> tesseract_kinematics::KinematicGroup::working_frames_
private

Definition at line 158 of file kinematic_group.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