Public Member Functions | Private Attributes | Friends
robot_state::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>

List of all members.

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW AttachedBody (const robot_model::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 sensor_msgs::JointState &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.
void computeTransform (const Eigen::Affine3d &parent_link_global_transform)
 Recompute global_collision_body_transform given the transform of the parent link.
const robot_model::LinkModelgetAttachedLink () const
 Get the model of the link this body is attached to.
const std::string & getAttachedLinkName () const
 Get the name of the link this body is attached to.
const sensor_msgs::JointState & 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_Affine3dgetFixedTransforms () const
const EigenSTL::vector_Affine3dgetGlobalCollisionBodyTransforms () const
 Get the global transforms for the collision bodies.
const std::string & getName () const
 Get the name of the attached body.
const std::vector
< shapes::ShapeConstPtr > & 
getShapes () const
 Get the shapes that make up this attached body.
const std::set< std::string > & getTouchLinks () const
 Get the fixed transform (the transforms to the shapes associated with this body)
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.
 ~AttachedBody ()

Private Attributes

EigenSTL::vector_Affine3d attach_trans_
 The constant transforms applied to the link (needs to be specified by user)
sensor_msgs::JointState 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.
EigenSTL::vector_Affine3d global_collision_body_transforms_
 The global transforms for these attached bodies (computed by forward kinematics)
std::string id_
 string id for reference
const robot_model::LinkModelparent_link_model_
 The link that owns this attached body.
std::vector
< shapes::ShapeConstPtr
shapes_
 The geometries of the attached body.
std::set< std::string > touch_links_
 The set of links this body is allowed to touch.

Friends

class RobotState

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


Constructor & Destructor Documentation

robot_state::AttachedBody::AttachedBody ( const robot_model::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 sensor_msgs::JointState &  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 39 of file attached_body.cpp.

Definition at line 57 of file attached_body.cpp.


Member Function Documentation

void robot_state::AttachedBody::computeTransform ( const Eigen::Affine3d &  parent_link_global_transform)

Recompute global_collision_body_transform given the transform of the parent link.

Definition at line 95 of file attached_body.cpp.

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

Definition at line 83 of file attached_body.h.

const std::string& robot_state::AttachedBody::getAttachedLinkName ( ) const [inline]

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

Definition at line 77 of file attached_body.h.

const sensor_msgs::JointState& robot_state::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 104 of file attached_body.h.

Definition at line 109 of file attached_body.h.

Get the global transforms for the collision bodies.

Definition at line 115 of file attached_body.h.

const std::string& robot_state::AttachedBody::getName ( ) const [inline]

Get the name of the attached body.

Definition at line 71 of file attached_body.h.

const std::vector<shapes::ShapeConstPtr>& robot_state::AttachedBody::getShapes ( ) const [inline]

Get the shapes that make up this attached body.

Definition at line 89 of file attached_body.h.

const std::set<std::string>& robot_state::AttachedBody::getTouchLinks ( ) const [inline]

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

Get the links that the attached body is allowed to touch

Definition at line 97 of file attached_body.h.

void robot_state::AttachedBody::setPadding ( double  padding)

Set the padding for the shapes of this attached object.

Definition at line 78 of file attached_body.cpp.

void robot_state::AttachedBody::setScale ( double  scale)

Set the scale for the shapes of this attached object.

Definition at line 61 of file attached_body.cpp.


Friends And Related Function Documentation

friend class RobotState [friend]

Definition at line 55 of file attached_body.h.


Member Data Documentation

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

Definition at line 141 of file attached_body.h.

sensor_msgs::JointState robot_state::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 148 of file attached_body.h.

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

Definition at line 151 of file attached_body.h.

std::string robot_state::AttachedBody::id_ [private]

string id for reference

Definition at line 135 of file attached_body.h.

The link that owns this attached body.

Definition at line 132 of file attached_body.h.

The geometries of the attached body.

Definition at line 138 of file attached_body.h.

The set of links this body is allowed to touch.

Definition at line 144 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 Mon Oct 6 2014 02:24:48