Go to the documentation of this file.
43 #include <boost/function.hpp>
44 #include <trajectory_msgs/JointTrajectory.h>
66 AttachedBody(
const LinkModel* parent,
const std::string&
id,
const Eigen::Isometry3d& pose,
68 const std::set<std::string>& touch_links,
const trajectory_msgs::JointTrajectory& detach_posture,
74 const std::string&
getName()
const
80 const Eigen::Isometry3d&
getPose()
const
104 const std::vector<shapes::ShapeConstPtr>&
getShapes()
const
164 for (
const auto&
t : subframe_poses)
176 const Eigen::Isometry3d&
getSubframeTransform(
const std::string& frame_name,
bool* found =
nullptr)
const;
204 void computeTransform(
const Eigen::Isometry3d& parent_link_global_transform);
214 Eigen::Isometry3d
pose_;
220 std::vector<shapes::ShapeConstPtr>
shapes_;
A link from the robot. Contains the constant transform applied to the link and its geometry.
void computeTransform(const Eigen::Isometry3d &parent_link_global_transform)
Recompute global_collision_body_transform given the transform of the parent link.
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...
std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > vector_Isometry3d
const EigenSTL::vector_Isometry3d & getFixedTransforms() const
Get the fixed transforms (the transforms to the shapes of this body, relative to the 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....
const EigenSTL::vector_Isometry3d & getShapePosesInLinkFrame() const
Get the fixed transforms (the transforms to the shapes of this body, relative to the link)....
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.
const std::set< std::string > & getTouchLinks() const
Get the links that the attached body is allowed to touch.
moveit::core::FixedTransformsMap subframe_poses_
Transforms to subframes on the object, relative to the object's pose.
const Eigen::Isometry3d & getGlobalPose() const
Get the pose of the attached body, relative to the world.
moveit::core::FixedTransformsMap global_subframe_poses_
Transforms to subframes on the object, relative to the model frame.
EigenSTL::vector_Isometry3d shape_poses_in_link_frame_
The transforms from the link to the object's geometries.
void setScale(double scale)
Set the scale for the shapes of this attached object.
std::string id_
string id for reference
void setPadding(double padding)
Set the padding for the shapes of this attached object.
EigenSTL::vector_Isometry3d shape_poses_
The transforms from the object's pose to the object's geometries.
bool hasSubframeTransform(const std::string &frame_name) const
Check whether a subframe of given.
#define ASSERT_ISOMETRY(transform)
const EigenSTL::vector_Isometry3d & getGlobalCollisionBodyTransforms() const
Get the global transforms (in world frame) for the collision bodies. The returned transforms are guar...
const moveit::core::FixedTransformsMap & getSubframes() const
Get subframes of this object (relative to the object pose). The returned transforms are guaranteed to...
const moveit::core::FixedTransformsMap & getGlobalSubframeTransforms() const
Get subframes of this object (in the world frame)
boost::function< void(AttachedBody *body, bool attached)> AttachedBodyCallback
std::map< std::string, Eigen::Isometry3d, std::less< std::string >, Eigen::aligned_allocator< std::pair< const std::string, Eigen::Isometry3d > > > FixedTransformsMap
Map frame names to the transformation matrix that can transform objects from the frame name to the pl...
const LinkModel * getAttachedLink() const
Get the model of the link this body is attached to.
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)
Main namespace for MoveIt.
Eigen::Isometry3d pose_
The transform from the parent link to the attached body's pose.
const std::string & getAttachedLinkName() const
Get the name of the link this body is attached to.
EigenSTL::vector_Isometry3d global_collision_body_transforms_
The global transforms for the attached bodies (computed by forward kinematics)
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get the shapes that make up this attached body.
void setSubframeTransforms(const moveit::core::FixedTransformsMap &subframe_poses)
Set all subframes of this object.
const LinkModel * parent_link_model_
The link that owns this attached body.
const std::string & getName() const
The name of this link.
std::vector< shapes::ShapeConstPtr > shapes_
The geometries of the attached body.
const Eigen::Isometry3d & getPose() const
Get the pose of the attached body relative to the parent link.
const EigenSTL::vector_Isometry3d & getShapePoses() const
Get the shape poses (the transforms to the shapes of this body, relative to the pose)....
const std::string & getName() const
Get the name 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...
geometry_msgs::TransformStamped t
std::set< std::string > touch_links_
The set of links this body is allowed to touch.
Eigen::Isometry3d global_pose_
The transform from the model frame to the attached body's pose
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:14