Go to the documentation of this file.
43 #include <Eigen/Geometry>
67 using LinkTransformMap = std::map<const LinkModel*, Eigen::Isometry3d, std::less<const LinkModel*>,
68 Eigen::aligned_allocator<std::pair<const LinkModel* const, Eigen::Isometry3d> > >;
74 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
175 const std::vector<shapes::ShapeConstPtr>&
getShapes()
const
const Eigen::Isometry3d & getJointOriginTransform() const
When transforms are computed for this link, they are usually applied to the link's origin....
A link from the robot. Contains the constant transform applied to the link and its geometry.
std::vector< shapes::ShapeConstPtr > shapes_
The collision geometry of the link.
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 ...
Eigen::Isometry3d visual_mesh_origin_
The additional origin transform for the mesh.
void setJointOriginTransform(const Eigen::Isometry3d &transform)
std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > vector_Isometry3d
void setGeometry(const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Isometry3d &origins)
const std::string & getVisualMeshFilename() const
Get the filename of the mesh resource used for visual display of this 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 li...
Eigen::Vector3d visual_mesh_scale_
Scale factor associated with the visual geometry mesh of this link.
const Eigen::Vector3d & getShapeExtentsAtOrigin() const
Get the extents of the link's geometry (dimensions of axis-aligned bounding box around all shapes tha...
const JointModel * getParentJointModel() const
Get the joint model whose child this link is. There will always be a parent joint.
std::vector< const JointModel * > child_joint_models_
List of directly descending joints (each connects to a child link)
MOVEIT_CLASS_FORWARD(Shape)
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.
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW LinkModel(const std::string &name)
void setParentJointModel(const JointModel *joint)
Eigen::Isometry3d joint_origin_transform_
The constant transform applied to the link (local)
const std::vector< int > & areCollisionOriginTransformsIdentity() const
Return flags for each transform specifying whether they are identity or not.
const Eigen::Vector3d & getVisualMeshScale() const
Get the scale of the mesh resource for this link.
std::string name_
Name of the link.
int link_index_
Index of the transform for this link in the full robot frame.
bool is_parent_joint_fixed_
True if the parent joint of this link is fixed.
void setLinkIndex(int index)
std::string visual_mesh_filename_
Filename associated with the visual geometry mesh of this link. If empty, no mesh was used.
#define ASSERT_ISOMETRY(transform)
const LinkTransformMap & getAssociatedFixedTransforms() const
Get the set of links that are attached to this one via fixed transforms. The returned transforms are ...
void addChildJointModel(const JointModel *joint)
const LinkModel * parent_link_model_
The parent link model (NULL for the root link)
EigenSTL::vector_Isometry3d collision_origin_transform_
The constant transform applied to the collision geometry of the link (local)
const EigenSTL::vector_Isometry3d & getCollisionOriginTransforms() const
In addition to the link transform, the geometry of a link that is used for collision checking may hav...
int getFirstCollisionBodyTransformIndex() const
LinkTransformMap associated_fixed_transforms_
The set of links that are attached to this one via fixed transforms.
std::map< std::string, const LinkModel * > LinkModelMapConst
Map of names to const instances for LinkModel.
std::map< const LinkModel *, Eigen::Isometry3d, std::less< const LinkModel * >, Eigen::aligned_allocator< std::pair< const LinkModel *const, Eigen::Isometry3d > > > LinkTransformMap
Map from link model instances to Eigen transforms.
std::map< std::string, LinkModel * > LinkModelMap
Map of names to instances for LinkModel.
void setParentLinkModel(const LinkModel *link)
bool joint_origin_transform_is_identity_
True of the joint origin transform is identity.
void setFirstCollisionBodyTransformIndex(int index)
int getLinkIndex() const
The index of this joint when traversing the kinematic tree in depth first fashion.
Main namespace for MoveIt.
const Eigen::Isometry3d & getVisualMeshOrigin() const
Get the transform for the visual mesh origin.
bool jointOriginTransformIsIdentity() const
const JointModel * parent_joint_model_
JointModel that connects this link to the parent link.
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get shape associated to the collision geometry for this link.
const std::string & getName() const
The name of this link.
Eigen::Vector3d centered_bounding_box_offset_
Center of the axis aligned bounding box with size shape_extents_ (zero if symmetric along all axes).
void addAssociatedFixedTransform(const LinkModel *link_model, const Eigen::Isometry3d &transform)
Remember that link_model is attached to this link using a fixed transform.
std::vector< int > collision_origin_transform_is_identity_
Flag indicating if the constant transform applied to the collision geometry of the link (local) is id...
void setVisualMesh(const std::string &visual_mesh, const Eigen::Isometry3d &origin, const Eigen::Vector3d &scale)
bool parentJointIsFixed() const
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
const LinkModel * getParentLinkModel() const
Get the link model whose child this link is (through some joint). There may not always be a parent li...
Vec3fX< details::Vec3Data< double > > Vector3d
Eigen::Vector3d shape_extents_
The extents of shape (dimensions of axis aligned bounding box when shape is at origin).
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:14