Public Member Functions | Private Attributes | List of all members
moveit::core::AttachedBody Class Reference

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::JointTrajectory &detach_posture, const moveit::core::FixedTransformsMap &subframe_poses=moveit::core::FixedTransformsMap())
 Construct an attached body for a specified link. More...
 
void computeTransform (const Eigen::Isometry3d &parent_link_global_transform)
 Recompute global_collision_body_transform given the transform of the parent link. More...
 
const LinkModelgetAttachedLink () const
 Get the model of the link this body is attached to. More...
 
const std::string & getAttachedLinkName () const
 Get the name of the link this body is attached to. More...
 
const trajectory_msgs::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. More...
 
const EigenSTL::vector_Isometry3dgetFixedTransforms () 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. Deprecated. Use getShapePosesInLinkFrame instead. More...
 
const EigenSTL::vector_Isometry3dgetGlobalCollisionBodyTransforms () const
 Get the global transforms (in world frame) for the collision bodies. The returned transforms are guaranteed to be valid isometries. More...
 
const Eigen::Isometry3d & getGlobalPose () const
 Get the pose of the attached body, relative to the world. More...
 
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. More...
 
const moveit::core::FixedTransformsMapgetGlobalSubframeTransforms () const
 Get subframes of this object (in the world frame) More...
 
const std::string & getName () const
 Get the name of the attached body. More...
 
const Eigen::Isometry3d & getPose () const
 Get the pose of the attached body relative to the parent link. More...
 
const EigenSTL::vector_Isometry3dgetShapePoses () 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. More...
 
const EigenSTL::vector_Isometry3dgetShapePosesInLinkFrame () 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. More...
 
const std::vector< shapes::ShapeConstPtr > & getShapes () const
 Get the shapes that make up this attached body. More...
 
const moveit::core::FixedTransformsMapgetSubframes () const
 Get subframes of this object (relative to the object pose). The returned transforms are guaranteed to be valid isometries. More...
 
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) More...
 
const std::set< std::string > & getTouchLinks () const
 Get the links that the attached body is allowed to touch. More...
 
bool hasSubframeTransform (const std::string &frame_name) const
 Check whether a subframe of given. More...
 
void setPadding (double padding)
 Set the padding for the shapes of this attached object. More...
 
void setScale (double scale)
 Set the scale for the shapes of this attached object. More...
 
void setSubframeTransforms (const moveit::core::FixedTransformsMap &subframe_poses)
 Set all subframes of this object. More...
 
 ~AttachedBody ()
 

Private Attributes

trajectory_msgs::JointTrajectory detach_posture_
 Posture of links for releasing the object (if any). This is useful for example when storing the configuration of a gripper holding an object. More...
 
EigenSTL::vector_Isometry3d global_collision_body_transforms_
 The global transforms for the attached bodies (computed by forward kinematics) More...
 
Eigen::Isometry3d global_pose_
 The transform from the model frame to the attached body's pose
More...
 
moveit::core::FixedTransformsMap global_subframe_poses_
 Transforms to subframes on the object, relative to the model frame. More...
 
std::string id_
 string id for reference More...
 
const LinkModelparent_link_model_
 The link that owns this attached body. More...
 
Eigen::Isometry3d pose_
 The transform from the parent link to the attached body's pose. More...
 
EigenSTL::vector_Isometry3d shape_poses_
 The transforms from the object's pose to the object's geometries. More...
 
EigenSTL::vector_Isometry3d shape_poses_in_link_frame_
 The transforms from the link to the object's geometries. More...
 
std::vector< shapes::ShapeConstPtrshapes_
 The geometries of the attached body. More...
 
moveit::core::FixedTransformsMap subframe_poses_
 Transforms to subframes on the object, relative to the object's pose. More...
 
std::set< std::string > touch_links_
 The set of links this body is allowed to touch. More...
 

Detailed Description

Object defining bodies that can be attached to robot links.

This is useful when handling objects picked up by the robot.

Definition at line 121 of file attached_body.h.

Constructor & Destructor Documentation

◆ AttachedBody()

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::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 110 of file attached_body.cpp.

◆ ~AttachedBody()

moveit::core::AttachedBody::~AttachedBody ( )
default

Member Function Documentation

◆ computeTransform()

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 168 of file attached_body.cpp.

◆ getAttachedLink()

const LinkModel* moveit::core::AttachedBody::getAttachedLink ( ) const
inline

Get the model of the link this body is attached to.

Definition at line 162 of file attached_body.h.

◆ getAttachedLinkName()

const std::string& moveit::core::AttachedBody::getAttachedLinkName ( ) const
inline

Get the name of the link this body is attached to.

Definition at line 156 of file attached_body.h.

◆ getDetachPosture()

const trajectory_msgs::JointTrajectory& moveit::core::AttachedBody::getDetachPosture ( ) const
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 188 of file attached_body.h.

◆ getFixedTransforms()

const EigenSTL::vector_Isometry3d& moveit::core::AttachedBody::getFixedTransforms ( ) const
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. Deprecated. Use getShapePosesInLinkFrame instead.

Definition at line 203 of file attached_body.h.

◆ getGlobalCollisionBodyTransforms()

const EigenSTL::vector_Isometry3d& moveit::core::AttachedBody::getGlobalCollisionBodyTransforms ( ) const
inline

Get the global transforms (in world frame) for the collision bodies. The returned transforms are guaranteed to be valid isometries.

Definition at line 256 of file attached_body.h.

◆ getGlobalPose()

const Eigen::Isometry3d& moveit::core::AttachedBody::getGlobalPose ( ) const
inline

Get the pose of the attached body, relative to the world.

Definition at line 150 of file attached_body.h.

◆ getGlobalSubframeTransform()

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 218 of file attached_body.cpp.

◆ getGlobalSubframeTransforms()

const moveit::core::FixedTransformsMap& moveit::core::AttachedBody::getGlobalSubframeTransforms ( ) const
inline

Get subframes of this object (in the world frame)

Definition at line 216 of file attached_body.h.

◆ getName()

const std::string& moveit::core::AttachedBody::getName ( ) const
inline

Get the name of the attached body.

Definition at line 138 of file attached_body.h.

◆ getPose()

const Eigen::Isometry3d& moveit::core::AttachedBody::getPose ( ) const
inline

Get the pose of the attached body relative to the parent link.

Definition at line 144 of file attached_body.h.

◆ getShapePoses()

const EigenSTL::vector_Isometry3d& moveit::core::AttachedBody::getShapePoses ( ) const
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 175 of file attached_body.h.

◆ getShapePosesInLinkFrame()

const EigenSTL::vector_Isometry3d& moveit::core::AttachedBody::getShapePosesInLinkFrame ( ) const
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 195 of file attached_body.h.

◆ getShapes()

const std::vector<shapes::ShapeConstPtr>& moveit::core::AttachedBody::getShapes ( ) const
inline

Get the shapes that make up this attached body.

Definition at line 168 of file attached_body.h.

◆ getSubframes()

const moveit::core::FixedTransformsMap& moveit::core::AttachedBody::getSubframes ( ) const
inline

Get subframes of this object (relative to the object pose). The returned transforms are guaranteed to be valid isometries.

Definition at line 210 of file attached_body.h.

◆ getSubframeTransform()

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 200 of file attached_body.cpp.

◆ getTouchLinks()

const std::set<std::string>& moveit::core::AttachedBody::getTouchLinks ( ) const
inline

Get the links that the attached body is allowed to touch.

Definition at line 181 of file attached_body.h.

◆ hasSubframeTransform()

bool moveit::core::AttachedBody::hasSubframeTransform ( const std::string &  frame_name) const

Check whether a subframe of given.

Parameters
frame_nameis 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 236 of file attached_body.cpp.

◆ setPadding()

void moveit::core::AttachedBody::setPadding ( double  padding)

Set the padding for the shapes of this attached object.

Definition at line 183 of file attached_body.cpp.

◆ setScale()

void moveit::core::AttachedBody::setScale ( double  scale)

Set the scale for the shapes of this attached object.

Definition at line 151 of file attached_body.cpp.

◆ setSubframeTransforms()

void moveit::core::AttachedBody::setSubframeTransforms ( const moveit::core::FixedTransformsMap subframe_poses)
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 226 of file attached_body.h.

Member Data Documentation

◆ detach_posture_

trajectory_msgs::JointTrajectory moveit::core::AttachedBody::detach_posture_
private

Posture of links for releasing the object (if any). This is useful for example when storing the configuration of a gripper holding an object.

Definition at line 300 of file attached_body.h.

◆ global_collision_body_transforms_

EigenSTL::vector_Isometry3d moveit::core::AttachedBody::global_collision_body_transforms_
private

The global transforms for the attached bodies (computed by forward kinematics)

Definition at line 293 of file attached_body.h.

◆ global_pose_

Eigen::Isometry3d moveit::core::AttachedBody::global_pose_
private

The transform from the model frame to the attached body's pose

Definition at line 281 of file attached_body.h.

◆ global_subframe_poses_

moveit::core::FixedTransformsMap moveit::core::AttachedBody::global_subframe_poses_
private

Transforms to subframes on the object, relative to the model frame.

Definition at line 306 of file attached_body.h.

◆ id_

std::string moveit::core::AttachedBody::id_
private

string id for reference

Definition at line 275 of file attached_body.h.

◆ parent_link_model_

const LinkModel* moveit::core::AttachedBody::parent_link_model_
private

The link that owns this attached body.

Definition at line 272 of file attached_body.h.

◆ pose_

Eigen::Isometry3d moveit::core::AttachedBody::pose_
private

The transform from the parent link to the attached body's pose.

Definition at line 278 of file attached_body.h.

◆ shape_poses_

EigenSTL::vector_Isometry3d moveit::core::AttachedBody::shape_poses_
private

The transforms from the object's pose to the object's geometries.

Definition at line 287 of file attached_body.h.

◆ shape_poses_in_link_frame_

EigenSTL::vector_Isometry3d moveit::core::AttachedBody::shape_poses_in_link_frame_
private

The transforms from the link to the object's geometries.

Definition at line 290 of file attached_body.h.

◆ shapes_

std::vector<shapes::ShapeConstPtr> moveit::core::AttachedBody::shapes_
private

The geometries of the attached body.

Definition at line 284 of file attached_body.h.

◆ subframe_poses_

moveit::core::FixedTransformsMap moveit::core::AttachedBody::subframe_poses_
private

Transforms to subframes on the object, relative to the object's pose.

Definition at line 303 of file attached_body.h.

◆ touch_links_

std::set<std::string> moveit::core::AttachedBody::touch_links_
private

The set of links this body is allowed to touch.

Definition at line 296 of file attached_body.h.


The documentation for this class was generated from the following files:


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Apr 18 2024 02:23:41