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

List of all members.

Public Member Functions

void addAssociatedFixedTransform (const LinkModel *link_model, const Eigen::Affine3d &transform)
 Remember that link_model is attached to this link using a fixed transform.
void addChildJointModel (const JointModel *joint)
const std::vector< int > & areCollisionOriginTransformsIdentity () const
 Return flags for each transform specifying whether they are identity or not.
const LinkTransformMapgetAssociatedFixedTransforms () const
 Get the set of links that are attached to this one via fixed transforms.
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.
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.
const EigenSTL::vector_Affine3dgetCollisionOriginTransforms () 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.
int getFirstCollisionBodyTransformIndex () const
const Eigen::Affine3d & 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.
int getLinkIndex () const
 The index of this joint when traversing the kinematic tree in depth first fashion.
const std::string & getName () const
 The name of this link.
const JointModelgetParentJointModel () const
 Get the joint model whose child this link is. There will always be a parent joint.
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)
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)
const std::vector
< shapes::ShapeConstPtr > & 
getShapes () const
 Get shape associated to the collision geometry for this link.
const std::string & getVisualMeshFilename () const
 Get the filename of the mesh resource used for visual display of this link.
const Eigen::Affine3d & getVisualMeshOrigin () const
 Get the transform for the visual mesh origin.
const Eigen::Vector3d & getVisualMeshScale () const
 Get the scale of the mesh resource for this link.
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_Affine3d &origins)
void setJointOriginTransform (const Eigen::Affine3d &transform)
void setLinkIndex (int index)
void setParentJointModel (const JointModel *joint)
void setParentLinkModel (const LinkModel *link)
void setVisualMesh (const std::string &visual_mesh, const Eigen::Affine3d &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.
std::vector< const JointModel * > child_joint_models_
 List of directly descending joints (each connects to a child link)
EigenSTL::vector_Affine3d collision_origin_transform_
 The constant transform applied to the collision geometry of the link (local)
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.
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.
bool is_parent_joint_fixed_
 True if the parent joint of this link is fixed.
Eigen::Affine3d joint_origin_transform_
 The constant transform applied to the link (local)
bool joint_origin_transform_is_identity_
 True of the joint origin transform is identity.
int link_index_
 Index of the transform for this link in the full robot frame.
std::string name_
 Name of the link.
const JointModelparent_joint_model_
 JointModel that connects this link to the parent link.
const LinkModelparent_link_model_
 The parent link model (NULL for the root link)
Eigen::Vector3d shape_extents_
 The extents of shape (dimensions of axis aligned bounding box when shape is at origin).
std::vector
< shapes::ShapeConstPtr
shapes_
 The collision geometry of the link.
std::string visual_mesh_filename_
 Filename associated with the visual geometry mesh of this link. If empty, no mesh was used.
Eigen::Affine3d visual_mesh_origin_
 The additional origin transform for the mesh.
Eigen::Vector3d visual_mesh_scale_
 Scale factor associated with the visual geometry mesh of this link.

Detailed Description

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

Definition at line 67 of file link_model.h.


Constructor & Destructor Documentation

moveit::core::LinkModel::LinkModel ( const std::string &  name)

Definition at line 54 of file link_model.cpp.

Definition at line 67 of file link_model.cpp.


Member Function Documentation

void moveit::core::LinkModel::addAssociatedFixedTransform ( const LinkModel link_model,
const Eigen::Affine3d &  transform 
) [inline]

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

Definition at line 194 of file link_model.h.

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

Definition at line 128 of file link_model.h.

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

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

Definition at line 188 of file link_model.h.

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

Definition at line 139 of file link_model.cpp.

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

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.

Definition at line 157 of file link_model.h.

Definition at line 92 of file link_model.h.

const Eigen::Affine3d& 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.

Definition at line 137 of file link_model.h.

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

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

Definition at line 82 of file link_model.h.

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

The name of this link.

Definition at line 76 of file link_model.h.

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

Definition at line 103 of file link_model.h.

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

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

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

Get shape associated to the collision geometry for this link.

Definition at line 169 of file link_model.h.

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

const Eigen::Affine3d& moveit::core::LinkModel::getVisualMeshOrigin ( ) const [inline]

Get the transform for the visual mesh origin.

Definition at line 212 of file link_model.h.

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

Get the scale of the mesh resource for this link.

Definition at line 206 of file link_model.h.

Definition at line 142 of file link_model.h.

Definition at line 147 of file link_model.h.

Definition at line 97 of file link_model.h.

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

Definition at line 86 of file link_model.cpp.

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

Definition at line 72 of file link_model.cpp.

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

Definition at line 87 of file link_model.h.

Definition at line 80 of file link_model.cpp.

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

Definition at line 117 of file link_model.h.

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

Definition at line 131 of file link_model.cpp.


Member Data Documentation

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

Definition at line 249 of file link_model.h.

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

Definition at line 230 of file link_model.h.

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

Definition at line 242 of file link_model.h.

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

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

Definition at line 268 of file link_model.h.

True if the parent joint of this link is fixed.

Definition at line 233 of file link_model.h.

The constant transform applied to the link (local)

Definition at line 239 of file link_model.h.

True of the joint origin transform is identity.

Definition at line 236 of file link_model.h.

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

Definition at line 271 of file link_model.h.

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

Name of the link.

Definition at line 221 of file link_model.h.

JointModel that connects this link to the parent link.

Definition at line 224 of file link_model.h.

The parent link model (NULL for the root link)

Definition at line 227 of file link_model.h.

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

The collision geometry of the link.

Definition at line 252 of file link_model.h.

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

Definition at line 258 of file link_model.h.

The additional origin transform for the mesh.

Definition at line 261 of file link_model.h.

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

Definition at line 264 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 Wed Jun 19 2019 19:23:50