Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
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]
Collaboration diagram for tesseract_kinematics::JointGroup:
Collaboration graph
[legend]

Public Types

using Ptr = std::shared_ptr< JointGroup >
 
using ConstPtr = std::shared_ptr< const JointGroup >
 
using UPtr = std::unique_ptr< JointGroup >
 
using ConstUPtr = std::unique_ptr< const JointGroup >
 

Public Member Functions

virtual ~JointGroup ()=default
 
 JointGroup (const JointGroup &other)
 
JointGroupoperator= (const JointGroup &other)
 
 JointGroup (JointGroup &&)=default
 
JointGroupoperator= (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...
 
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 &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...
 
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...
 
std::vector< std::string > getJointNames () const
 Get list of joint names for kinematic object. More...
 
std::vector< std::string > getLinkNames () const
 Get list of all link names (with and without geometry) for kinematic object. More...
 
std::vector< std::string > getActiveLinkNames () const
 Get list of active link names (with and without geometry) for kinematic object. More...
 
std::vector< std::string > getStaticLinkNames () const
 Get list of static link names (with and without geometry) for kinematic object. More...
 
bool isActiveLinkName (const std::string &link_name) const
 Check if link is an active link. More...
 
bool hasLinkName (const std::string &link_name) const
 Check if link name exists. More...
 
tesseract_common::KinematicLimits getLimits () const
 Get the kinematic limits (joint, velocity, acceleration, etc.) More...
 
void setLimits (const tesseract_common::KinematicLimits &limits)
 Setter for kinematic limits (joint, velocity, acceleration, etc.) More...
 
std::vector< Eigen::Index > getRedundancyCapableJointIndices () const
 Get vector indicating which joints are capable of producing redundant solutions. More...
 
Eigen::Index numJoints () const
 Number of joints in robot. More...
 
std::string getBaseLinkName () const
 Get the robot base link name. More...
 
std::string getName () const
 Name of the manipulator. More...
 
bool checkJoints (const Eigen::Ref< const Eigen::VectorXd > &vec) const
 Check for consistency in # and limits of joints. More...
 

Protected Attributes

std::string name_
 
tesseract_scene_graph::SceneState state_
 
tesseract_scene_graph::StateSolver::UPtr state_solver_
 
std::vector< std::string > joint_names_
 
std::vector< std::string > link_names_
 
std::vector< std::string > static_link_names_
 
tesseract_common::TransformMap static_link_transforms_
 
tesseract_common::KinematicLimits limits_
 
std::vector< Eigen::Index > redundancy_indices_
 
std::vector< Eigen::Index > jacobian_map_
 

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.

Member Typedef Documentation

◆ ConstPtr

◆ ConstUPtr

◆ Ptr

◆ UPtr

Constructor & Destructor Documentation

◆ ~JointGroup()

virtual tesseract_kinematics::JointGroup::~JointGroup ( )
virtualdefault

◆ JointGroup() [1/3]

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

◆ 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

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)

◆ 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

◆ 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

◆ 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

◆ 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

◆ 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

◆ 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

◆ getBaseLinkName()

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

Get the robot base link name.

◆ getJointNames()

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

Get list of joint names for kinematic object.

Returns
A vector of joint names

◆ getLimits()

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

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

Returns
Kinematic Limits

◆ 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

◆ getName()

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

Name of the manipulator.

◆ 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

◆ 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

◆ 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

◆ 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

◆ numJoints()

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

Number of joints in robot.

Returns
Number of joints in robot

◆ operator=() [1/2]

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

◆ 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

Member Data Documentation

◆ jacobian_map_

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

◆ joint_names_

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

◆ limits_

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

◆ link_names_

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

◆ name_

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

◆ redundancy_indices_

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

◆ state_

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

◆ state_solver_

tesseract_scene_graph::StateSolver::UPtr tesseract_kinematics::JointGroup::state_solver_
protected

◆ static_link_names_

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

◆ static_link_transforms_

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

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