A link from the robot. Contains the constant transform applied to the link and its geometry. More...
#include <link_model.h>
Public Member Functions | |
const AssociatedFixedTransformMap & | getAssociatedFixedTransforms () const |
Get the set of links that are attached to this one via fixed transforms. | |
const std::vector< JointModel * > & | getChildJointModels () const |
A link may have 0 or more child joints. From those joints there will certainly be other descendant links. | |
const Eigen::Affine3d & | getCollisionOriginTransform () 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. | |
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. | |
const std::string & | getName () const |
The name of this link. | |
const JointModel * | getParentJointModel () const |
Get the joint model whose child this link is. There will always be a parent joint. | |
const shapes::ShapeConstPtr & | getShape () const |
Get shape associated to the collision geometry for this link. | |
const Eigen::Vector3d & | getShapeExtentsAtOrigin () const |
Get the extenrs of the link's geometry (dimensions of axis-aligned bounding box when the link is positioned at origin) | |
const shapes::ShapeMsg & | getShapeMsg () const |
Get shape associated to the collision geometry for this link. | |
int | getTreeIndex () const |
The index of this joint when traversing the kinematic tree in depth first fashion. | |
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. | |
LinkModel () | |
~LinkModel () | |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef std::map< const LinkModel *, Eigen::Affine3d, std::less< const LinkModel * > , Eigen::aligned_allocator < std::pair< const LinkModel *, Eigen::Affine3d > > > | AssociatedFixedTransformMap |
Private Attributes | |
AssociatedFixedTransformMap | associated_fixed_transforms_ |
The set of links that are attached to this one via fixed transforms. | |
std::vector< JointModel * > | child_joint_models_ |
List of descending joints (each connects to a child link) | |
Eigen::Affine3d | collision_origin_transform_ |
The constant transform applied to the collision geometry of the link (local) | |
Eigen::Affine3d | joint_origin_transform_ |
The constant transform applied to the link (local) | |
std::string | name_ |
Name of the link. | |
JointModel * | parent_joint_model_ |
JointModel that connects this link to the parent link. | |
shapes::ShapeConstPtr | shape_ |
The collision geometry of the link. | |
Eigen::Vector3d | shape_extents_ |
The extents if shape (dimensions of axis aligned bounding box when shape is at origin. | |
shapes::ShapeMsg | shape_msg_ |
The collision geometry of the link as a message. | |
int | tree_index_ |
The index assigned to this link when traversing the kinematic tree in depth first fashion. | |
std::string | visual_mesh_filename_ |
Filename associated with the visual geometry mesh of this link. If empty, no mesh was used. | |
Eigen::Vector3d | visual_mesh_scale_ |
Scale factor associated with the visual geometry mesh of this link. | |
Friends | |
class | RobotModel |
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition at line 54 of file link_model.h.
Definition at line 39 of file link_model.cpp.
Definition at line 45 of file link_model.cpp.
const AssociatedFixedTransformMap& robot_model::LinkModel::getAssociatedFixedTransforms | ( | ) | const [inline] |
Get the set of links that are attached to this one via fixed transforms.
Definition at line 128 of file link_model.h.
const std::vector<JointModel*>& robot_model::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 86 of file link_model.h.
const Eigen::Affine3d& robot_model::LinkModel::getCollisionOriginTransform | ( | ) | 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.
Definition at line 104 of file link_model.h.
const Eigen::Affine3d& robot_model::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 95 of file link_model.h.
const std::string& robot_model::LinkModel::getName | ( | ) | const [inline] |
The name of this link.
Definition at line 68 of file link_model.h.
const JointModel* robot_model::LinkModel::getParentJointModel | ( | ) | const [inline] |
Get the joint model whose child this link is. There will always be a parent joint.
Definition at line 80 of file link_model.h.
const shapes::ShapeConstPtr& robot_model::LinkModel::getShape | ( | ) | const [inline] |
Get shape associated to the collision geometry for this link.
Definition at line 110 of file link_model.h.
const Eigen::Vector3d& robot_model::LinkModel::getShapeExtentsAtOrigin | ( | ) | const [inline] |
Get the extenrs of the link's geometry (dimensions of axis-aligned bounding box when the link is positioned at origin)
Definition at line 122 of file link_model.h.
const shapes::ShapeMsg& robot_model::LinkModel::getShapeMsg | ( | ) | const [inline] |
Get shape associated to the collision geometry for this link.
Definition at line 116 of file link_model.h.
int robot_model::LinkModel::getTreeIndex | ( | ) | const [inline] |
The index of this joint when traversing the kinematic tree in depth first fashion.
Definition at line 74 of file link_model.h.
const std::string& robot_model::LinkModel::getVisualMeshFilename | ( | ) | const [inline] |
Get the filename of the mesh resource used for visual display of this link.
Definition at line 134 of file link_model.h.
const Eigen::Vector3d& robot_model::LinkModel::getVisualMeshScale | ( | ) | const [inline] |
Get the scale of the mesh resource for this link.
Definition at line 140 of file link_model.h.
friend class RobotModel [friend] |
Definition at line 56 of file link_model.h.
The set of links that are attached to this one via fixed transforms.
Definition at line 157 of file link_model.h.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef std::map<const LinkModel*, Eigen::Affine3d, std::less<const LinkModel*>, Eigen::aligned_allocator<std::pair<const LinkModel*, Eigen::Affine3d> > > robot_model::LinkModel::AssociatedFixedTransformMap |
Definition at line 62 of file link_model.h.
std::vector<JointModel*> robot_model::LinkModel::child_joint_models_ [private] |
List of descending joints (each connects to a child link)
Definition at line 154 of file link_model.h.
Eigen::Affine3d robot_model::LinkModel::collision_origin_transform_ [private] |
The constant transform applied to the collision geometry of the link (local)
Definition at line 163 of file link_model.h.
Eigen::Affine3d robot_model::LinkModel::joint_origin_transform_ [private] |
The constant transform applied to the link (local)
Definition at line 160 of file link_model.h.
std::string robot_model::LinkModel::name_ [private] |
Name of the link.
Definition at line 148 of file link_model.h.
JointModel that connects this link to the parent link.
Definition at line 151 of file link_model.h.
The collision geometry of the link.
Definition at line 166 of file link_model.h.
Eigen::Vector3d robot_model::LinkModel::shape_extents_ [private] |
The extents if shape (dimensions of axis aligned bounding box when shape is at origin.
Definition at line 172 of file link_model.h.
The collision geometry of the link as a message.
Definition at line 169 of file link_model.h.
int robot_model::LinkModel::tree_index_ [private] |
The index assigned to this link when traversing the kinematic tree in depth first fashion.
Definition at line 181 of file link_model.h.
std::string robot_model::LinkModel::visual_mesh_filename_ [private] |
Filename associated with the visual geometry mesh of this link. If empty, no mesh was used.
Definition at line 175 of file link_model.h.
Eigen::Vector3d robot_model::LinkModel::visual_mesh_scale_ [private] |
Scale factor associated with the visual geometry mesh of this link.
Definition at line 178 of file link_model.h.