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

A Joint Group is defined by a list of joint_names. More...

#include <joint_group.h>

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

Public Types

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

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 ()
 

Protected Attributes

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

A Joint Group is defined by a list of joint_names.

Provides the ability to calculate forward kinematics and jacobian.

Note
This creates an optimized object replace all joints not listed in the provided list with a fixed joint calculated using the provided state. Also the calcFwdKin only return the link transforms in the optimized object which is all active links and root of the scene graph usually.

Definition at line 44 of file joint_group.h.

Member Typedef Documentation

◆ ConstPtr

Definition at line 52 of file joint_group.h.

◆ ConstUPtr

Definition at line 54 of file joint_group.h.

◆ Ptr

Definition at line 51 of file joint_group.h.

◆ UPtr

Definition at line 53 of file joint_group.h.

Constructor & Destructor Documentation

◆ ~JointGroup()

tesseract_kinematics::JointGroup::~JointGroup ( )
virtualdefault

◆ JointGroup() [1/3]

tesseract_kinematics::JointGroup::JointGroup ( const JointGroup other)

Definition at line 109 of file joint_group.cpp.

◆ JointGroup() [2/3]

tesseract_kinematics::JointGroup::JointGroup ( JointGroup &&  )
default

◆ JointGroup() [3/3]

tesseract_kinematics::JointGroup::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.

Parameters
nameThe name of the kinematic group
joint_namesThe joints names to create kinematic group from
scene_graphThe scene graph
scene_stateThe scene state

Definition at line 43 of file joint_group.cpp.

Member Function Documentation

◆ calcFwdKin()

tesseract_common::TransformMap tesseract_kinematics::JointGroup::calcFwdKin ( const Eigen::Ref< const Eigen::VectorXd > &  joint_angles) const

Calculates tool pose of robot chain.

Throws an exception on failures (including uninitialized)

Parameters
poseTransform of end-of-tip relative to root
joint_anglesVector of joint angles (size must match number of joints in robot chain)

Definition at line 126 of file joint_group.cpp.

◆ calcJacobian() [1/4]

Eigen::MatrixXd tesseract_kinematics::JointGroup::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.

Parameters
joint_anglesInput vector of joint angles
base_link_nameThe frame that the jacobian is calculated in
Returns
The jacobian at the provided link_name relative to the provided base_link_name

Definition at line 160 of file joint_group.cpp.

◆ calcJacobian() [2/4]

Eigen::MatrixXd tesseract_kinematics::JointGroup::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.

Parameters
joint_anglesInput vector of joint angles
base_link_nameThe frame that the jacobian is calculated in
link_nameThe frame that the jacobian is calculated for
link_pointA point on the link that the jacobian is calculated for
Returns
The jacobian at the provided link_name relative to the provided base_link_name

Definition at line 198 of file joint_group.cpp.

◆ calcJacobian() [3/4]

Eigen::MatrixXd tesseract_kinematics::JointGroup::calcJacobian ( const Eigen::Ref< const Eigen::VectorXd > &  joint_angles,
const std::string &  link_name 
) const

Calculated jacobian of robot given joint angles.

Parameters
joint_anglesInput vector of joint angles
link_nameThe frame that the jacobian is calculated for
Returns
The jacobian at the provided link_name relative to the joint group base link

Definition at line 133 of file joint_group.cpp.

◆ calcJacobian() [4/4]

Eigen::MatrixXd tesseract_kinematics::JointGroup::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.

Parameters
joint_anglesInput vector of joint angles
link_nameThe frame that the jacobian is calculated for
link_pointA point on the link that the jacobian is calculated for
Returns
The jacobian at the provided link_name relative to the joint group base link

Definition at line 145 of file joint_group.cpp.

◆ checkJoints()

bool tesseract_kinematics::JointGroup::checkJoints ( const Eigen::Ref< const Eigen::VectorXd > &  vec) const

Check for consistency in # and limits of joints.

Parameters
vecVector of joint values
Returns
True if size of vec matches # of robot joints and all joints are within limits

Definition at line 242 of file joint_group.cpp.

◆ getActiveLinkNames()

std::vector< std::string > tesseract_kinematics::JointGroup::getActiveLinkNames ( ) const

Get list of active link names (with and without geometry) for kinematic object.

Note: This only includes links that are children of the active joints

Returns
A vector of active link names

Definition at line 271 of file joint_group.cpp.

◆ getBaseLinkName()

std::string tesseract_kinematics::JointGroup::getBaseLinkName ( ) const

Get the robot base link name.

Definition at line 301 of file joint_group.cpp.

◆ getJointNames()

std::vector< std::string > tesseract_kinematics::JointGroup::getJointNames ( ) const

Get list of joint names for kinematic object.

Returns
A vector of joint names

Definition at line 267 of file joint_group.cpp.

◆ getLimits()

tesseract_common::KinematicLimits tesseract_kinematics::JointGroup::getLimits ( ) const

Get the kinematic limits (joint, velocity, acceleration, etc.)

Returns
Kinematic Limits

Definition at line 285 of file joint_group.cpp.

◆ getLinkNames()

std::vector< std::string > tesseract_kinematics::JointGroup::getLinkNames ( ) const

Get list of all link names (with and without geometry) for kinematic object.

Returns
A vector of link names

Definition at line 269 of file joint_group.cpp.

◆ getName()

std::string tesseract_kinematics::JointGroup::getName ( ) const

Name of the manipulator.

Definition at line 303 of file joint_group.cpp.

◆ getRedundancyCapableJointIndices()

std::vector< Eigen::Index > tesseract_kinematics::JointGroup::getRedundancyCapableJointIndices ( ) const

Get vector indicating which joints are capable of producing redundant solutions.

Returns
A vector of joint indices

Definition at line 297 of file joint_group.cpp.

◆ getStaticLinkNames()

std::vector< std::string > tesseract_kinematics::JointGroup::getStaticLinkNames ( ) const

Get list of static link names (with and without geometry) for kinematic object.

Returns
A vector of static link names

Definition at line 273 of file joint_group.cpp.

◆ hasLinkName()

bool tesseract_kinematics::JointGroup::hasLinkName ( const std::string &  link_name) const

Check if link name exists.

Parameters
link_nameThe link name to check for
Returns
True if it exists, otherwise false

Definition at line 280 of file joint_group.cpp.

◆ isActiveLinkName()

bool tesseract_kinematics::JointGroup::isActiveLinkName ( const std::string &  link_name) const

Check if link is an active link.

Parameters
link_nameThe link name to check
Returns
True if active, otherwise false

Definition at line 275 of file joint_group.cpp.

◆ numJoints()

Eigen::Index tesseract_kinematics::JointGroup::numJoints ( ) const

Number of joints in robot.

Returns
Number of joints in robot

Definition at line 299 of file joint_group.cpp.

◆ operator=() [1/2]

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

Definition at line 111 of file joint_group.cpp.

◆ operator=() [2/2]

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

◆ setLimits()

void tesseract_kinematics::JointGroup::setLimits ( const tesseract_common::KinematicLimits limits)

Setter for kinematic limits (joint, velocity, acceleration, etc.)

Parameters
KinematicLimits

Definition at line 287 of file joint_group.cpp.

Member Data Documentation

◆ jacobian_map_

std::vector<Eigen::Index> tesseract_kinematics::JointGroup::jacobian_map_
protected

Definition at line 214 of file joint_group.h.

◆ joint_names_

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

Definition at line 208 of file joint_group.h.

◆ limits_

tesseract_common::KinematicLimits tesseract_kinematics::JointGroup::limits_
protected

Definition at line 212 of file joint_group.h.

◆ link_names_

std::vector<std::string> tesseract_kinematics::JointGroup::link_names_
protected

Definition at line 209 of file joint_group.h.

◆ name_

std::string tesseract_kinematics::JointGroup::name_
protected

Definition at line 205 of file joint_group.h.

◆ redundancy_indices_

std::vector<Eigen::Index> tesseract_kinematics::JointGroup::redundancy_indices_
protected

Definition at line 213 of file joint_group.h.

◆ state_

tesseract_scene_graph::SceneState tesseract_kinematics::JointGroup::state_
protected

Definition at line 206 of file joint_group.h.

◆ state_solver_

std::unique_ptr<tesseract_scene_graph::StateSolver> tesseract_kinematics::JointGroup::state_solver_
protected

Definition at line 207 of file joint_group.h.

◆ static_link_names_

std::vector<std::string> tesseract_kinematics::JointGroup::static_link_names_
protected

Definition at line 210 of file joint_group.h.

◆ static_link_transforms_

tesseract_common::TransformMap tesseract_kinematics::JointGroup::static_link_transforms_
protected

Definition at line 211 of file joint_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