37 #ifndef MOVEIT_ROBOT_STATE_ATTACHED_BODY_ 38 #define MOVEIT_ROBOT_STATE_ATTACHED_BODY_ 42 #include <boost/function.hpp> 43 #include <trajectory_msgs/JointTrajectory.h> 65 const trajectory_msgs::JointTrajectory& attach_posture);
88 const std::vector<shapes::ShapeConstPtr>&
getShapes()
const const std::string & getAttachedLinkName() const
Get the name of the link this body is attached to.
const std::string & getName() const
The name of this link.
EigenSTL::vector_Affine3d attach_trans_
The constant transforms applied to the link (needs to be specified by user)
std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > vector_Affine3d
const std::string & getName() const
Get the name of the attached body.
std::vector< shapes::ShapeConstPtr > shapes_
The geometries of the attached body.
trajectory_msgs::JointTrajectory detach_posture_
Posture of links for releasing the object (if any). This is useful for example when storing the confi...
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get the shapes that make up this attached body.
std::string id_
string id for reference
const EigenSTL::vector_Affine3d & getFixedTransforms() const
Get the fixed transform (the transforms to the shapes associated with this body)
boost::function< void(AttachedBody *body, bool attached)> AttachedBodyCallback
EigenSTL::vector_Affine3d global_collision_body_transforms_
The global transforms for these attached bodies (computed by forward kinematics)
std::set< std::string > touch_links_
The set of links this body is allowed to touch.
const std::set< std::string > & getTouchLinks() const
Get the links that the attached body is allowed to touch.
const LinkModel * getAttachedLink() const
Get the model of the link this body is attached to.
void computeTransform(const Eigen::Affine3d &parent_link_global_transform)
Recompute global_collision_body_transform given the transform of the parent link. ...
const EigenSTL::vector_Affine3d & getGlobalCollisionBodyTransforms() const
Get the global transforms for the collision bodies.
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 shape...
const LinkModel * parent_link_model_
The link that owns this attached body.
A link from the robot. Contains the constant transform applied to the link and its geometry...
Main namespace for MoveIt!
Object defining bodies that can be attached to robot links. This is useful when handling objects pick...
void setScale(double scale)
Set the scale for the shapes of this attached object.
void setPadding(double padding)
Set the padding for the shapes of this attached object.
const trajectory_msgs::JointTrajectory & getDetachPosture() const
Return the posture that is necessary for the object to be released, (if any). This is useful for exam...