moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | List of all members
moveit::core::LinkModel Class Reference

A link from the robot. Contains the constant transform applied to the link and its geometry. More...

#include <link_model.h>

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW LinkModel (const std::string &name, size_t link_index)
 Construct a link model named name. More...
 
 ~LinkModel ()
 
const std::string & getName () const
 The name of this link. More...
 
size_t getLinkIndex () const
 The index of this joint when traversing the kinematic tree in depth first fashion. More...
 
int getFirstCollisionBodyTransformIndex () const
 
void setFirstCollisionBodyTransformIndex (int index)
 
const JointModelgetParentJointModel () const
 Get the joint model whose child this link is. There will always be a parent joint. More...
 
void setParentJointModel (const JointModel *joint)
 
const LinkModelgetParentLinkModel () const
 Get the link model whose child this link is (through some joint). There may not always be a parent link (nullptr is returned for the root link) More...
 
void setParentLinkModel (const LinkModel *link)
 
const std::vector< const JointModel * > & getChildJointModels () const
 A link may have 0 or more child joints. From those joints there will certainly be other descendant links. More...
 
void addChildJointModel (const JointModel *joint)
 
const Eigen::Isometry3d & getJointOriginTransform () const
 When transforms are computed for this link, they are usually applied to the link's origin. The joint origin transform acts as an offset – it is pre-applied before any other transform. The transform is guaranteed to be a valid isometry. More...
 
bool jointOriginTransformIsIdentity () const
 
bool parentJointIsFixed () const
 
void setJointOriginTransform (const Eigen::Isometry3d &transform)
 
const EigenSTL::vector_Isometry3d & getCollisionOriginTransforms () const
 In addition to the link transform, the geometry of a link that is used for collision checking may have a different offset itself, with respect to the origin. The transform is guaranteed to be a valid isometry. More...
 
const std::vector< int > & areCollisionOriginTransformsIdentity () const
 Return flags for each transform specifying whether they are identity or not. More...
 
const std::vector< shapes::ShapeConstPtr > & getShapes () const
 Get shape associated to the collision geometry for this link. More...
 
void setGeometry (const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Isometry3d &origins)
 
const Eigen::Vector3d & getShapeExtentsAtOrigin () const
 Get the extents of the link's geometry (dimensions of axis-aligned bounding box around all shapes that make up the link, when the link is positioned at origin – only collision origin transforms are considered) More...
 
const Eigen::Vector3d & getCenteredBoundingBoxOffset () const
 Get the offset of the center of the bounding box of this link when the link is positioned at origin. More...
 
const LinkTransformMapgetAssociatedFixedTransforms () const
 Get the set of links that are attached to this one via fixed transforms. The returned transforms are guaranteed to be valid isometries. More...
 
void addAssociatedFixedTransform (const LinkModel *link_model, const Eigen::Isometry3d &transform)
 Remember that link_model is attached to this link using a fixed transform. More...
 
const std::string & getVisualMeshFilename () const
 Get the filename of the mesh resource used for visual display of this link. More...
 
const Eigen::Vector3d & getVisualMeshScale () const
 Get the scale of the mesh resource for this link. More...
 
const Eigen::Isometry3d & getVisualMeshOrigin () const
 Get the transform for the visual mesh origin. More...
 
void setVisualMesh (const std::string &visual_mesh, const Eigen::Isometry3d &origin, const Eigen::Vector3d &scale)
 

Detailed Description

A link from the robot. Contains the constant transform applied to the link and its geometry.

Definition at line 71 of file link_model.h.

Constructor & Destructor Documentation

◆ LinkModel()

moveit::core::LinkModel::LinkModel ( const std::string &  name,
size_t  link_index 
)

Construct a link model named name.

Parameters
[in]nameThe name of the link
[in]link_indexThe link index in the RobotModel

Definition at line 47 of file link_model.cpp.

◆ ~LinkModel()

moveit::core::LinkModel::~LinkModel ( )
default

Member Function Documentation

◆ addAssociatedFixedTransform()

void moveit::core::LinkModel::addAssociatedFixedTransform ( const LinkModel link_model,
const Eigen::Isometry3d &  transform 
)
inline

Remember that link_model is attached to this link using a fixed transform.

Definition at line 205 of file link_model.h.

◆ addChildJointModel()

void moveit::core::LinkModel::addChildJointModel ( const JointModel joint)
inline

Definition at line 133 of file link_model.h.

◆ areCollisionOriginTransformsIdentity()

const std::vector<int>& moveit::core::LinkModel::areCollisionOriginTransformsIdentity ( ) const
inline

Return flags for each transform specifying whether they are identity or not.

Definition at line 170 of file link_model.h.

◆ getAssociatedFixedTransforms()

const LinkTransformMap& moveit::core::LinkModel::getAssociatedFixedTransforms ( ) const
inline

Get the set of links that are attached to this one via fixed transforms. The returned transforms are guaranteed to be valid isometries.

Definition at line 199 of file link_model.h.

Here is the caller graph for this function:

◆ getCenteredBoundingBoxOffset()

const Eigen::Vector3d& moveit::core::LinkModel::getCenteredBoundingBoxOffset ( ) const
inline

Get the offset of the center of the bounding box of this link when the link is positioned at origin.

Definition at line 192 of file link_model.h.

Here is the caller graph for this function:

◆ getChildJointModels()

const std::vector<const JointModel*>& moveit::core::LinkModel::getChildJointModels ( ) const
inline

A link may have 0 or more child joints. From those joints there will certainly be other descendant links.

Definition at line 128 of file link_model.h.

Here is the caller graph for this function:

◆ getCollisionOriginTransforms()

const EigenSTL::vector_Isometry3d& moveit::core::LinkModel::getCollisionOriginTransforms ( ) const
inline

In addition to the link transform, the geometry of a link that is used for collision checking may have a different offset itself, with respect to the origin. The transform is guaranteed to be a valid isometry.

Definition at line 164 of file link_model.h.

◆ getFirstCollisionBodyTransformIndex()

int moveit::core::LinkModel::getFirstCollisionBodyTransformIndex ( ) const
inline

Definition at line 97 of file link_model.h.

Here is the caller graph for this function:

◆ getJointOriginTransform()

const Eigen::Isometry3d& moveit::core::LinkModel::getJointOriginTransform ( ) const
inline

When transforms are computed for this link, they are usually applied to the link's origin. The joint origin transform acts as an offset – it is pre-applied before any other transform. The transform is guaranteed to be a valid isometry.

Definition at line 143 of file link_model.h.

Here is the caller graph for this function:

◆ getLinkIndex()

size_t moveit::core::LinkModel::getLinkIndex ( ) const
inline

The index of this joint when traversing the kinematic tree in depth first fashion.

Definition at line 92 of file link_model.h.

Here is the caller graph for this function:

◆ getName()

const std::string& moveit::core::LinkModel::getName ( ) const
inline

The name of this link.

Definition at line 86 of file link_model.h.

Here is the caller graph for this function:

◆ getParentJointModel()

const JointModel* moveit::core::LinkModel::getParentJointModel ( ) const
inline

Get the joint model whose child this link is. There will always be a parent joint.

Definition at line 108 of file link_model.h.

Here is the caller graph for this function:

◆ getParentLinkModel()

const LinkModel* moveit::core::LinkModel::getParentLinkModel ( ) const
inline

Get the link model whose child this link is (through some joint). There may not always be a parent link (nullptr is returned for the root link)

Definition at line 117 of file link_model.h.

Here is the caller graph for this function:

◆ getShapeExtentsAtOrigin()

const Eigen::Vector3d& moveit::core::LinkModel::getShapeExtentsAtOrigin ( ) const
inline

Get the extents of the link's geometry (dimensions of axis-aligned bounding box around all shapes that make up the link, when the link is positioned at origin – only collision origin transforms are considered)

Definition at line 186 of file link_model.h.

Here is the caller graph for this function:

◆ getShapes()

const std::vector<shapes::ShapeConstPtr>& moveit::core::LinkModel::getShapes ( ) const
inline

Get shape associated to the collision geometry for this link.

Definition at line 176 of file link_model.h.

Here is the caller graph for this function:

◆ getVisualMeshFilename()

const std::string& moveit::core::LinkModel::getVisualMeshFilename ( ) const
inline

Get the filename of the mesh resource used for visual display of this link.

Definition at line 212 of file link_model.h.

Here is the caller graph for this function:

◆ getVisualMeshOrigin()

const Eigen::Isometry3d& moveit::core::LinkModel::getVisualMeshOrigin ( ) const
inline

Get the transform for the visual mesh origin.

Definition at line 224 of file link_model.h.

Here is the caller graph for this function:

◆ getVisualMeshScale()

const Eigen::Vector3d& moveit::core::LinkModel::getVisualMeshScale ( ) const
inline

Get the scale of the mesh resource for this link.

Definition at line 218 of file link_model.h.

Here is the caller graph for this function:

◆ jointOriginTransformIsIdentity()

bool moveit::core::LinkModel::jointOriginTransformIsIdentity ( ) const
inline

Definition at line 148 of file link_model.h.

◆ parentJointIsFixed()

bool moveit::core::LinkModel::parentJointIsFixed ( ) const
inline

Definition at line 153 of file link_model.h.

◆ setFirstCollisionBodyTransformIndex()

void moveit::core::LinkModel::setFirstCollisionBodyTransformIndex ( int  index)
inline

Definition at line 102 of file link_model.h.

◆ setGeometry()

void moveit::core::LinkModel::setGeometry ( const std::vector< shapes::ShapeConstPtr > &  shapes,
const EigenSTL::vector_Isometry3d &  origins 
)

Definition at line 76 of file link_model.cpp.

Here is the call graph for this function:

◆ setJointOriginTransform()

void moveit::core::LinkModel::setJointOriginTransform ( const Eigen::Isometry3d &  transform)

Definition at line 61 of file link_model.cpp.

◆ setParentJointModel()

void moveit::core::LinkModel::setParentJointModel ( const JointModel joint)

Definition at line 70 of file link_model.cpp.

Here is the call graph for this function:

◆ setParentLinkModel()

void moveit::core::LinkModel::setParentLinkModel ( const LinkModel link)
inline

Definition at line 122 of file link_model.h.

◆ setVisualMesh()

void moveit::core::LinkModel::setVisualMesh ( const std::string &  visual_mesh,
const Eigen::Isometry3d &  origin,
const Eigen::Vector3d &  scale 
)

Definition at line 122 of file link_model.cpp.


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