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 LinkTransformMap & | getAssociatedFixedTransforms () 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::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 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_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... | |
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 JointModel * | getParentJointModel () const |
Get the joint model whose child this link is. There will always be a parent joint. More... | |
const LinkModel * | getParentLinkModel () 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::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 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::Vector3d & | getVisualMeshScale () 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 JointModel * | parent_joint_model_ |
JointModel that connects this link to the parent link. More... | |
const LinkModel * | parent_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::ShapeConstPtr > | shapes_ |
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... | |
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.
moveit::core::LinkModel::LinkModel | ( | const std::string & | name | ) |
Definition at line 111 of file link_model.cpp.
|
default |
|
inline |
Remember that link_model is attached to this link using a fixed transform.
Definition at line 204 of file link_model.h.
|
inline |
Definition at line 132 of file link_model.h.
|
inline |
Return flags for each transform specifying whether they are identity or not.
Definition at line 169 of file link_model.h.
|
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.
|
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.
|
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.
|
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.
|
inline |
Definition at line 96 of file link_model.h.
|
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.
|
inline |
The index of this joint when traversing the kinematic tree in depth first fashion.
Definition at line 86 of file link_model.h.
|
inline |
The name of this link.
Definition at line 80 of file link_model.h.
|
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.
|
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.
|
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.
|
inline |
Get shape associated to the collision geometry for this link.
Definition at line 175 of file link_model.h.
|
inline |
Get the filename of the mesh resource used for visual display of this link.
Definition at line 211 of file link_model.h.
|
inline |
Get the transform for the visual mesh origin.
Definition at line 223 of file link_model.h.
|
inline |
Get the scale of the mesh resource for this link.
Definition at line 217 of file link_model.h.
|
inline |
Definition at line 147 of file link_model.h.
|
inline |
Definition at line 152 of file link_model.h.
|
inline |
Definition at line 101 of file link_model.h.
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.
void moveit::core::LinkModel::setJointOriginTransform | ( | const Eigen::Isometry3d & | transform | ) |
Definition at line 125 of file link_model.cpp.
|
inline |
Definition at line 91 of file link_model.h.
void moveit::core::LinkModel::setParentJointModel | ( | const JointModel * | joint | ) |
Definition at line 134 of file link_model.cpp.
|
inline |
Definition at line 121 of file link_model.h.
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.
|
private |
The set of links that are attached to this one via fixed transforms.
Definition at line 260 of file link_model.h.
|
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.
|
private |
List of directly descending joints (each connects to a child link)
Definition at line 241 of file link_model.h.
|
private |
The constant transform applied to the collision geometry of the link (local)
Definition at line 253 of file link_model.h.
|
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.
|
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.
|
private |
True if the parent joint of this link is fixed.
Definition at line 244 of file link_model.h.
|
private |
The constant transform applied to the link (local)
Definition at line 250 of file link_model.h.
|
private |
True of the joint origin transform is identity.
Definition at line 247 of file link_model.h.
|
private |
Index of the transform for this link in the full robot frame.
Definition at line 285 of file link_model.h.
|
private |
Name of the link.
Definition at line 232 of file link_model.h.
|
private |
JointModel that connects this link to the parent link.
Definition at line 235 of file link_model.h.
|
private |
The parent link model (NULL for the root link)
Definition at line 238 of file link_model.h.
|
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.
|
private |
The collision geometry of the link.
Definition at line 263 of file link_model.h.
|
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.
|
private |
The additional origin transform for the mesh.
Definition at line 275 of file link_model.h.
|
private |
Scale factor associated with the visual geometry mesh of this link.
Definition at line 278 of file link_model.h.