moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Object defining bodies that can be attached to robot links. More...
#include <attached_body.h>
Public Member Functions | |
AttachedBody (const LinkModel *parent, const std::string &id, const Eigen::Isometry3d &pose, const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Isometry3d &shape_poses, const std::set< std::string > &touch_links, const trajectory_msgs::msg::JointTrajectory &detach_posture, const moveit::core::FixedTransformsMap &subframe_poses=moveit::core::FixedTransformsMap()) | |
Construct an attached body for a specified link. | |
~AttachedBody () | |
const std::string & | getName () const |
Get the name of the attached body. | |
const Eigen::Isometry3d & | getPose () const |
Get the pose of the attached body relative to the parent link. | |
const Eigen::Isometry3d & | getGlobalPose () const |
Get the pose of the attached body, relative to the world. | |
const std::string & | getAttachedLinkName () const |
Get the name of the link this body is attached to. | |
const LinkModel * | getAttachedLink () const |
Get the model of the link this body is attached to. | |
const std::vector< shapes::ShapeConstPtr > & | getShapes () const |
Get the shapes that make up this attached body. | |
const EigenSTL::vector_Isometry3d & | getShapePoses () const |
Get the shape poses (the transforms to the shapes of this body, relative to the pose). The returned transforms are guaranteed to be valid isometries. | |
const std::set< std::string > & | getTouchLinks () const |
Get the links that the attached body is allowed to touch. | |
const trajectory_msgs::msg::JointTrajectory & | getDetachPosture () const |
Return the posture that is necessary for the object to be released, (if any). This is useful for example when storing the configuration of a gripper holding an object. | |
const EigenSTL::vector_Isometry3d & | getShapePosesInLinkFrame () const |
Get the fixed transforms (the transforms to the shapes of this body, relative to the link). The returned transforms are guaranteed to be valid isometries. | |
const moveit::core::FixedTransformsMap & | getSubframes () const |
Get subframes of this object (relative to the object pose). The returned transforms are guaranteed to be valid isometries. | |
const moveit::core::FixedTransformsMap & | getGlobalSubframeTransforms () const |
Get subframes of this object (in the world frame) | |
void | setSubframeTransforms (const moveit::core::FixedTransformsMap &subframe_poses) |
Set all subframes of this object. | |
const Eigen::Isometry3d & | getSubframeTransform (const std::string &frame_name, bool *found=nullptr) const |
Get the fixed transform to a named subframe on this body (relative to the body's pose) | |
const Eigen::Isometry3d & | getSubframeTransformInLinkFrame (const std::string &frame_name, bool *found=nullptr) const |
Get the fixed transform to a named subframe on this body (relative to the robot link) | |
const Eigen::Isometry3d & | getGlobalSubframeTransform (const std::string &frame_name, bool *found=nullptr) const |
Get the fixed transform to a named subframe on this body, relative to the world frame. The frame_name needs to have the object's name prepended (e.g. "screwdriver/tip" returns true if the object's name is "screwdriver"). Returns an identity transform if frame_name is unknown (and set found to false). The returned transform is guaranteed to be a valid isometry. | |
bool | hasSubframeTransform (const std::string &frame_name) const |
Check whether a subframe of given @frame_name is present in this object. | |
const EigenSTL::vector_Isometry3d & | getGlobalCollisionBodyTransforms () const |
Get the global transforms (in world frame) for the collision bodies. The returned transforms are guaranteed to be valid isometries. | |
void | setPadding (double padding) |
Set the padding for the shapes of this attached object. | |
void | setScale (double scale) |
Set the scale for the shapes of this attached object. | |
void | computeTransform (const Eigen::Isometry3d &parent_link_global_transform) |
Recompute global_collision_body_transform given the transform of the parent link. | |
Object defining bodies that can be attached to robot links.
This is useful when handling objects picked up by the robot.
Definition at line 57 of file attached_body.h.
moveit::core::AttachedBody::AttachedBody | ( | const LinkModel * | parent, |
const std::string & | id, | ||
const Eigen::Isometry3d & | pose, | ||
const std::vector< shapes::ShapeConstPtr > & | shapes, | ||
const EigenSTL::vector_Isometry3d & | shape_poses, | ||
const std::set< std::string > & | touch_links, | ||
const trajectory_msgs::msg::JointTrajectory & | detach_posture, | ||
const moveit::core::FixedTransformsMap & | subframe_poses = moveit::core::FixedTransformsMap() |
||
) |
Construct an attached body for a specified link.
The name of this body is id and it consists of shapes that attach to the link by the transforms shape_poses. The set of links that are allowed to be touched by this object is specified by touch_links. detach_posture may describe a detach motion for the gripper when placing the object. The shape and subframe poses are relative to the pose, and pose is relative to the parent link.
Definition at line 45 of file attached_body.cpp.
|
default |
void moveit::core::AttachedBody::computeTransform | ( | const Eigen::Isometry3d & | parent_link_global_transform | ) |
Recompute global_collision_body_transform given the transform of the parent link.
Definition at line 105 of file attached_body.cpp.
|
inline |
Get the model of the link this body is attached to.
Definition at line 98 of file attached_body.h.
|
inline |
Get the name of the link this body is attached to.
Definition at line 92 of file attached_body.h.
|
inline |
Return the posture that is necessary for the object to be released, (if any). This is useful for example when storing the configuration of a gripper holding an object.
Definition at line 124 of file attached_body.h.
|
inline |
Get the global transforms (in world frame) for the collision bodies. The returned transforms are guaranteed to be valid isometries.
Definition at line 191 of file attached_body.h.
|
inline |
Get the pose of the attached body, relative to the world.
Definition at line 86 of file attached_body.h.
const Eigen::Isometry3d & moveit::core::AttachedBody::getGlobalSubframeTransform | ( | const std::string & | frame_name, |
bool * | found = nullptr |
||
) | const |
Get the fixed transform to a named subframe on this body, relative to the world frame. The frame_name needs to have the object's name prepended (e.g. "screwdriver/tip" returns true if the object's name is "screwdriver"). Returns an identity transform if frame_name is unknown (and set found to false). The returned transform is guaranteed to be a valid isometry.
Definition at line 157 of file attached_body.cpp.
|
inline |
Get subframes of this object (in the world frame)
Definition at line 144 of file attached_body.h.
|
inline |
Get the name of the attached body.
Definition at line 74 of file attached_body.h.
|
inline |
Get the pose of the attached body relative to the parent link.
Definition at line 80 of file attached_body.h.
|
inline |
Get the shape poses (the transforms to the shapes of this body, relative to the pose). The returned transforms are guaranteed to be valid isometries.
Definition at line 111 of file attached_body.h.
|
inline |
Get the fixed transforms (the transforms to the shapes of this body, relative to the link). The returned transforms are guaranteed to be valid isometries.
Definition at line 131 of file attached_body.h.
|
inline |
Get the shapes that make up this attached body.
Definition at line 104 of file attached_body.h.
|
inline |
Get subframes of this object (relative to the object pose). The returned transforms are guaranteed to be valid isometries.
Definition at line 138 of file attached_body.h.
const Eigen::Isometry3d & moveit::core::AttachedBody::getSubframeTransform | ( | const std::string & | frame_name, |
bool * | found = nullptr |
||
) | const |
Get the fixed transform to a named subframe on this body (relative to the body's pose)
The frame_name needs to have the object's name prepended (e.g. "screwdriver/tip" returns true if the object's name is "screwdriver"). Returns an identity transform if frame_name is unknown (and set found to false). The returned transform is guaranteed to be a valid isometry.
Definition at line 139 of file attached_body.cpp.
const Eigen::Isometry3d & moveit::core::AttachedBody::getSubframeTransformInLinkFrame | ( | const std::string & | frame_name, |
bool * | found = nullptr |
||
) | const |
Get the fixed transform to a named subframe on this body (relative to the robot link)
The frame_name needs to have the object's name prepended (e.g. "screwdriver/tip" returns true if the object's name is "screwdriver"). Returns an identity transform if frame_name is unknown (and set found to false). The returned transform is guaranteed to be a valid isometry.
|
inline |
Get the links that the attached body is allowed to touch.
Definition at line 117 of file attached_body.h.
bool moveit::core::AttachedBody::hasSubframeTransform | ( | const std::string & | frame_name | ) | const |
Check whether a subframe of given @frame_name is present in this object.
The frame_name needs to have the object's name prepended (e.g. "screwdriver/tip" returns true if the object's name is "screwdriver").
Definition at line 175 of file attached_body.cpp.
void moveit::core::AttachedBody::setPadding | ( | double | padding | ) |
Set the padding for the shapes of this attached object.
Definition at line 120 of file attached_body.cpp.
void moveit::core::AttachedBody::setScale | ( | double | scale | ) |
Set the scale for the shapes of this attached object.
Definition at line 86 of file attached_body.cpp.
|
inline |
Set all subframes of this object.
Use these to define points of interest on the object to plan with (e.g. screwdriver/tip, kettle/spout, mug/base).
Definition at line 154 of file attached_body.h.