![]() |
Tesseract
Motion Planning Environment
|
A Joint Group is defined by a list of joint_names. More...
#include <joint_group.h>


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) | |
| JointGroup & | operator= (const JointGroup &other) |
| JointGroup (JointGroup &&)=default | |
| JointGroup & | operator= (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_ |
A Joint Group is defined by a list of joint_names.
Provides the ability to calculate forward kinematics and jacobian.
| using tesseract_kinematics::JointGroup::ConstPtr = std::shared_ptr<const JointGroup> |
| using tesseract_kinematics::JointGroup::ConstUPtr = std::unique_ptr<const JointGroup> |
| using tesseract_kinematics::JointGroup::Ptr = std::shared_ptr<JointGroup> |
| using tesseract_kinematics::JointGroup::UPtr = std::unique_ptr<JointGroup> |
|
virtualdefault |
| tesseract_kinematics::JointGroup::JointGroup | ( | const JointGroup & | other | ) |
|
default |
| 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.
| name | The name of the kinematic group |
| joint_names | The joints names to create kinematic group from |
| scene_graph | The scene graph |
| scene_state | The scene state |
| 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)
| pose | Transform of end-of-tip relative to root |
| joint_angles | Vector of joint angles (size must match number of joints in robot chain) |
| 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.
| joint_angles | Input vector of joint angles |
| base_link_name | The frame that the jacobian is calculated in |
| 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.
| joint_angles | Input vector of joint angles |
| base_link_name | The frame that the jacobian is calculated in |
| link_name | The frame that the jacobian is calculated for |
| link_point | A point on the link that the jacobian is calculated for |
| 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.
| joint_angles | Input vector of joint angles |
| link_name | The frame that the jacobian is calculated for |
| 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.
| joint_angles | Input vector of joint angles |
| link_name | The frame that the jacobian is calculated for |
| link_point | A point on the link that the jacobian is calculated for |
| bool tesseract_kinematics::JointGroup::checkJoints | ( | const Eigen::Ref< const Eigen::VectorXd > & | vec | ) | const |
Check for consistency in # and limits of joints.
| vec | Vector of joint values |
| 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
| std::string tesseract_kinematics::JointGroup::getBaseLinkName | ( | ) | const |
Get the robot base link name.
| std::vector< std::string > tesseract_kinematics::JointGroup::getJointNames | ( | ) | const |
Get list of joint names for kinematic object.
| tesseract_common::KinematicLimits tesseract_kinematics::JointGroup::getLimits | ( | ) | const |
Get the kinematic limits (joint, velocity, acceleration, etc.)
| std::vector< std::string > tesseract_kinematics::JointGroup::getLinkNames | ( | ) | const |
Get list of all link names (with and without geometry) for kinematic object.
| std::string tesseract_kinematics::JointGroup::getName | ( | ) | const |
Name of the manipulator.
| std::vector< Eigen::Index > tesseract_kinematics::JointGroup::getRedundancyCapableJointIndices | ( | ) | const |
Get vector indicating which joints are capable of producing redundant solutions.
| std::vector< std::string > tesseract_kinematics::JointGroup::getStaticLinkNames | ( | ) | const |
Get list of static link names (with and without geometry) for kinematic object.
| bool tesseract_kinematics::JointGroup::hasLinkName | ( | const std::string & | link_name | ) | const |
Check if link name exists.
| link_name | The link name to check for |
| bool tesseract_kinematics::JointGroup::isActiveLinkName | ( | const std::string & | link_name | ) | const |
Check if link is an active link.
| link_name | The link name to check |
| Eigen::Index tesseract_kinematics::JointGroup::numJoints | ( | ) | const |
Number of joints in robot.
| JointGroup & tesseract_kinematics::JointGroup::operator= | ( | const JointGroup & | other | ) |
|
default |
| void tesseract_kinematics::JointGroup::setLimits | ( | const tesseract_common::KinematicLimits & | limits | ) |
Setter for kinematic limits (joint, velocity, acceleration, etc.)
| Kinematic | Limits |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |