Public Member Functions | Private Attributes | 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

void addAssociatedFixedTransform (const LinkModel *link_model, const Eigen::Isometry3d &transform)
 Remember that link_model is attached to this link using a fixed transform. More...
 
void addChildJointModel (const JointModel *joint)
 
const std::vector< int > & areCollisionOriginTransformsIdentity () const
 Return flags for each transform specifying whether they are identity or not. 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...
 
const Eigen::Vector3dgetCenteredBoundingBoxOffset () const
 Get the offset of the center of the bounding box of this link when the link is positioned at origin. More...
 
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...
 
const EigenSTL::vector_Isometry3dgetCollisionOriginTransforms () 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...
 
int getFirstCollisionBodyTransformIndex () const
 
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...
 
int getLinkIndex () const
 The index of this joint when traversing the kinematic tree in depth first fashion. More...
 
const std::string & getName () const
 The name of this link. More...
 
const JointModelgetParentJointModel () const
 Get the joint model whose child this link is. There will always be a parent joint. More...
 
const LinkModelgetParentLinkModel () const
 Get the link model whose child this link is (through some joint). There may not always be a parent link (NULL is returned for the root link) More...
 
const Eigen::Vector3dgetShapeExtentsAtOrigin () 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 std::vector< shapes::ShapeConstPtr > & getShapes () const
 Get shape associated to the collision geometry for this link. More...
 
const std::string & getVisualMeshFilename () const
 Get the filename of the mesh resource used for visual display of this link. More...
 
const Eigen::Isometry3d & getVisualMeshOrigin () const
 Get the transform for the visual mesh origin. More...
 
const Eigen::Vector3dgetVisualMeshScale () const
 Get the scale of the mesh resource for this link. More...
 
bool jointOriginTransformIsIdentity () const
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW LinkModel (const std::string &name)
 
bool parentJointIsFixed () const
 
void setFirstCollisionBodyTransformIndex (int index)
 
void setGeometry (const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Isometry3d &origins)
 
void setJointOriginTransform (const Eigen::Isometry3d &transform)
 
void setLinkIndex (int index)
 
void setParentJointModel (const JointModel *joint)
 
void setParentLinkModel (const LinkModel *link)
 
void setVisualMesh (const std::string &visual_mesh, const Eigen::Isometry3d &origin, const Eigen::Vector3d &scale)
 
 ~LinkModel ()
 

Private Attributes

LinkTransformMap associated_fixed_transforms_
 The set of links that are attached to this one via fixed transforms. More...
 
Eigen::Vector3d centered_bounding_box_offset_
 Center of the axis aligned bounding box with size shape_extents_ (zero if symmetric along all axes). More...
 
std::vector< const JointModel * > child_joint_models_
 List of directly descending joints (each connects to a child link) More...
 
EigenSTL::vector_Isometry3d collision_origin_transform_
 The constant transform applied to the collision geometry of the link (local) More...
 
std::vector< int > collision_origin_transform_is_identity_
 Flag indicating if the constant transform applied to the collision geometry of the link (local) is identity; use int instead of bool to avoid bit operations. More...
 
int first_collision_body_transform_index_
 Index of the transform for the first shape that makes up the geometry of this link in the full robot state. More...
 
bool is_parent_joint_fixed_
 True if the parent joint of this link is fixed. More...
 
Eigen::Isometry3d joint_origin_transform_
 The constant transform applied to the link (local) More...
 
bool joint_origin_transform_is_identity_
 True of the joint origin transform is identity. More...
 
int link_index_
 Index of the transform for this link in the full robot frame. More...
 
std::string name_
 Name of the link. More...
 
const JointModelparent_joint_model_
 JointModel that connects this link to the parent link. More...
 
const LinkModelparent_link_model_
 The parent link model (NULL for the root link) More...
 
Eigen::Vector3d shape_extents_
 The extents of shape (dimensions of axis aligned bounding box when shape is at origin). More...
 
std::vector< shapes::ShapeConstPtrshapes_
 The collision geometry of the link. More...
 
std::string visual_mesh_filename_
 Filename associated with the visual geometry mesh of this link. If empty, no mesh was used. More...
 
Eigen::Isometry3d visual_mesh_origin_
 The additional origin transform for the mesh. More...
 
Eigen::Vector3d visual_mesh_scale_
 Scale factor associated with the visual geometry mesh of this link. More...
 

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)

Definition at line 111 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 204 of file link_model.h.

◆ addChildJointModel()

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

Definition at line 132 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 169 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 198 of file link_model.h.

◆ 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 191 of file link_model.h.

◆ 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 127 of file link_model.h.

◆ 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 163 of file link_model.h.

◆ getFirstCollisionBodyTransformIndex()

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

Definition at line 96 of file link_model.h.

◆ 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 142 of file link_model.h.

◆ getLinkIndex()

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

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

Definition at line 86 of file link_model.h.

◆ getName()

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

The name of this link.

Definition at line 80 of file link_model.h.

◆ 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 107 of file link_model.h.

◆ 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 (NULL is returned for the root link)

Definition at line 116 of file link_model.h.

◆ 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 185 of file link_model.h.

◆ 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 175 of file link_model.h.

◆ 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 211 of file link_model.h.

◆ getVisualMeshOrigin()

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

Get the transform for the visual mesh origin.

Definition at line 223 of file link_model.h.

◆ getVisualMeshScale()

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

Get the scale of the mesh resource for this link.

Definition at line 217 of file link_model.h.

◆ jointOriginTransformIsIdentity()

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

Definition at line 147 of file link_model.h.

◆ parentJointIsFixed()

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

Definition at line 152 of file link_model.h.

◆ setFirstCollisionBodyTransformIndex()

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

Definition at line 101 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 140 of file link_model.cpp.

◆ setJointOriginTransform()

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

Definition at line 125 of file link_model.cpp.

◆ setLinkIndex()

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

Definition at line 91 of file link_model.h.

◆ setParentJointModel()

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

Definition at line 134 of file link_model.cpp.

◆ setParentLinkModel()

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

Definition at line 121 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 182 of file link_model.cpp.

Member Data Documentation

◆ associated_fixed_transforms_

LinkTransformMap moveit::core::LinkModel::associated_fixed_transforms_
private

The set of links that are attached to this one via fixed transforms.

Definition at line 260 of file link_model.h.

◆ centered_bounding_box_offset_

Eigen::Vector3d moveit::core::LinkModel::centered_bounding_box_offset_
private

Center of the axis aligned bounding box with size shape_extents_ (zero if symmetric along all axes).

Definition at line 269 of file link_model.h.

◆ child_joint_models_

std::vector<const JointModel*> moveit::core::LinkModel::child_joint_models_
private

List of directly descending joints (each connects to a child link)

Definition at line 241 of file link_model.h.

◆ collision_origin_transform_

EigenSTL::vector_Isometry3d moveit::core::LinkModel::collision_origin_transform_
private

The constant transform applied to the collision geometry of the link (local)

Definition at line 253 of file link_model.h.

◆ collision_origin_transform_is_identity_

std::vector<int> moveit::core::LinkModel::collision_origin_transform_is_identity_
private

Flag indicating if the constant transform applied to the collision geometry of the link (local) is identity; use int instead of bool to avoid bit operations.

Definition at line 257 of file link_model.h.

◆ first_collision_body_transform_index_

int moveit::core::LinkModel::first_collision_body_transform_index_
private

Index of the transform for the first shape that makes up the geometry of this link in the full robot state.

Definition at line 282 of file link_model.h.

◆ is_parent_joint_fixed_

bool moveit::core::LinkModel::is_parent_joint_fixed_
private

True if the parent joint of this link is fixed.

Definition at line 244 of file link_model.h.

◆ joint_origin_transform_

Eigen::Isometry3d moveit::core::LinkModel::joint_origin_transform_
private

The constant transform applied to the link (local)

Definition at line 250 of file link_model.h.

◆ joint_origin_transform_is_identity_

bool moveit::core::LinkModel::joint_origin_transform_is_identity_
private

True of the joint origin transform is identity.

Definition at line 247 of file link_model.h.

◆ link_index_

int moveit::core::LinkModel::link_index_
private

Index of the transform for this link in the full robot frame.

Definition at line 285 of file link_model.h.

◆ name_

std::string moveit::core::LinkModel::name_
private

Name of the link.

Definition at line 232 of file link_model.h.

◆ parent_joint_model_

const JointModel* moveit::core::LinkModel::parent_joint_model_
private

JointModel that connects this link to the parent link.

Definition at line 235 of file link_model.h.

◆ parent_link_model_

const LinkModel* moveit::core::LinkModel::parent_link_model_
private

The parent link model (NULL for the root link)

Definition at line 238 of file link_model.h.

◆ shape_extents_

Eigen::Vector3d moveit::core::LinkModel::shape_extents_
private

The extents of shape (dimensions of axis aligned bounding box when shape is at origin).

Definition at line 266 of file link_model.h.

◆ shapes_

std::vector<shapes::ShapeConstPtr> moveit::core::LinkModel::shapes_
private

The collision geometry of the link.

Definition at line 263 of file link_model.h.

◆ visual_mesh_filename_

std::string moveit::core::LinkModel::visual_mesh_filename_
private

Filename associated with the visual geometry mesh of this link. If empty, no mesh was used.

Definition at line 272 of file link_model.h.

◆ visual_mesh_origin_

Eigen::Isometry3d moveit::core::LinkModel::visual_mesh_origin_
private

The additional origin transform for the mesh.

Definition at line 275 of file link_model.h.

◆ visual_mesh_scale_

Eigen::Vector3d moveit::core::LinkModel::visual_mesh_scale_
private

Scale factor associated with the visual geometry mesh of this link.

Definition at line 278 of file link_model.h.


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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Apr 18 2024 02:23:41