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

Object defining bodies that can be attached to robot links. This is useful when handling objects picked up by the robot. More...

#include <attached_body.h>

Public Member Functions

 AttachedBody (const LinkModel *link, const std::string &id, const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Affine3d &attach_trans, const std::set< std::string > &touch_links, const trajectory_msgs::JointTrajectory &attach_posture)
 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 attach_trans. The set of links that are allowed to be touched by this object is specified by touch_links. More...
 
void computeTransform (const Eigen::Affine3d &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_Affine3dgetFixedTransforms () const
 Get the fixed transform (the transforms to the shapes associated with this body) More...
 
const EigenSTL::vector_Affine3dgetGlobalCollisionBodyTransforms () const
 Get the global transforms for the collision bodies. More...
 
const std::string & getName () const
 Get the name of the attached body. More...
 
const std::vector< shapes::ShapeConstPtr > & getShapes () const
 Get the shapes that make up this attached body. More...
 
const std::set< std::string > & getTouchLinks () const
 Get the links that the attached body is allowed to touch. 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...
 
 ~AttachedBody ()
 

Private Attributes

EigenSTL::vector_Affine3d attach_trans_
 The constant transforms applied to the link (needs to be specified by user) More...
 
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_Affine3d global_collision_body_transforms_
 The global transforms for these attached bodies (computed by forward kinematics) More...
 
std::string id_
 string id for reference More...
 
const LinkModelparent_link_model_
 The link that owns this attached body. More...
 
std::vector< shapes::ShapeConstPtrshapes_
 The geometries of the attached body. 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 56 of file attached_body.h.

Constructor & Destructor Documentation

moveit::core::AttachedBody::AttachedBody ( const LinkModel link,
const std::string &  id,
const std::vector< shapes::ShapeConstPtr > &  shapes,
const EigenSTL::vector_Affine3d attach_trans,
const std::set< std::string > &  touch_links,
const trajectory_msgs::JointTrajectory &  attach_posture 
)

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 attach_trans. The set of links that are allowed to be touched by this object is specified by touch_links.

Definition at line 40 of file attached_body.cpp.

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

Member Function Documentation

void moveit::core::AttachedBody::computeTransform ( const Eigen::Affine3d &  parent_link_global_transform)
inline

Recompute global_collision_body_transform given the transform of the parent link.

Definition at line 126 of file attached_body.h.

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

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

Definition at line 82 of file attached_body.h.

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

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

Definition at line 76 of file attached_body.h.

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 102 of file attached_body.h.

const EigenSTL::vector_Affine3d& moveit::core::AttachedBody::getFixedTransforms ( ) const
inline

Get the fixed transform (the transforms to the shapes associated with this body)

Definition at line 108 of file attached_body.h.

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

Get the global transforms for the collision bodies.

Definition at line 114 of file attached_body.h.

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

Get the name of the attached body.

Definition at line 70 of file attached_body.h.

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

Get the shapes that make up this attached body.

Definition at line 88 of file attached_body.h.

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 94 of file attached_body.h.

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

Set the padding for the shapes of this attached object.

Definition at line 76 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 59 of file attached_body.cpp.

Member Data Documentation

EigenSTL::vector_Affine3d moveit::core::AttachedBody::attach_trans_
private

The constant transforms applied to the link (needs to be specified by user)

Definition at line 143 of file attached_body.h.

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 150 of file attached_body.h.

EigenSTL::vector_Affine3d moveit::core::AttachedBody::global_collision_body_transforms_
private

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

Definition at line 153 of file attached_body.h.

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

string id for reference

Definition at line 137 of file attached_body.h.

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

The link that owns this attached body.

Definition at line 134 of file attached_body.h.

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

The geometries of the attached body.

Definition at line 140 of file attached_body.h.

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

The set of links this body is allowed to touch.

Definition at line 146 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 Sun Oct 18 2020 13:16:34