moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
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. | |
~LinkModel () | |
const std::string & | getName () const |
The name of this link. | |
size_t | getLinkIndex () const |
The index of this joint when traversing the kinematic tree in depth first fashion. | |
int | getFirstCollisionBodyTransformIndex () const |
void | setFirstCollisionBodyTransformIndex (int index) |
const JointModel * | getParentJointModel () const |
Get the joint model whose child this link is. There will always be a parent joint. | |
void | setParentJointModel (const JointModel *joint) |
const LinkModel * | getParentLinkModel () 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) | |
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. | |
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. | |
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. | |
const std::vector< int > & | areCollisionOriginTransformsIdentity () const |
Return flags for each transform specifying whether they are identity or not. | |
const std::vector< shapes::ShapeConstPtr > & | getShapes () const |
Get shape associated to the collision geometry for this link. | |
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) | |
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 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. | |
void | addAssociatedFixedTransform (const LinkModel *link_model, const Eigen::Isometry3d &transform) |
Remember that link_model is attached to this link using a fixed transform. | |
const std::string & | getVisualMeshFilename () const |
Get the filename of the mesh resource used for visual display of this link. | |
const Eigen::Vector3d & | getVisualMeshScale () const |
Get the scale of the mesh resource for this link. | |
const Eigen::Isometry3d & | getVisualMeshOrigin () const |
Get the transform for the visual mesh origin. | |
void | setVisualMesh (const std::string &visual_mesh, const Eigen::Isometry3d &origin, const Eigen::Vector3d &scale) |
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, |
size_t | link_index | ||
) |
Construct a link model named name.
[in] | name | The name of the link |
[in] | link_index | The link index in the RobotModel |
Definition at line 47 of file link_model.cpp.
|
default |
|
inline |
Remember that link_model is attached to this link using a fixed transform.
Definition at line 205 of file link_model.h.
|
inline |
Definition at line 133 of file link_model.h.
|
inline |
Return flags for each transform specifying whether they are identity or not.
Definition at line 170 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 199 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 192 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 128 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 164 of file link_model.h.
|
inline |
|
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.
|
inline |
The index of this joint when traversing the kinematic tree in depth first fashion.
Definition at line 92 of file link_model.h.
|
inline |
The name of this link.
Definition at line 86 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 108 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 (nullptr is returned for the root link)
Definition at line 117 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 186 of file link_model.h.
|
inline |
Get shape associated to the collision geometry for this link.
Definition at line 176 of file link_model.h.
|
inline |
Get the filename of the mesh resource used for visual display of this link.
Definition at line 212 of file link_model.h.
|
inline |
Get the transform for the visual mesh origin.
Definition at line 224 of file link_model.h.
|
inline |
Get the scale of the mesh resource for this link.
Definition at line 218 of file link_model.h.
|
inline |
Definition at line 148 of file link_model.h.
|
inline |
Definition at line 153 of file link_model.h.
|
inline |
Definition at line 102 of file link_model.h.
void moveit::core::LinkModel::setGeometry | ( | const std::vector< shapes::ShapeConstPtr > & | shapes, |
const EigenSTL::vector_Isometry3d & | origins | ||
) |
void moveit::core::LinkModel::setJointOriginTransform | ( | const Eigen::Isometry3d & | transform | ) |
Definition at line 61 of file link_model.cpp.
void moveit::core::LinkModel::setParentJointModel | ( | const JointModel * | joint | ) |
|
inline |
Definition at line 122 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 122 of file link_model.cpp.