41 #include <geometric_shapes/check_isometry.h>
42 #include <eigen_stl_containers/eigen_stl_containers.h>
43 #include <trajectory_msgs/msg/joint_trajectory.hpp>
67 const std::vector<shapes::ShapeConstPtr>&
shapes,
const EigenSTL::vector_Isometry3d& shape_poses,
68 const std::set<std::string>& touch_links,
const trajectory_msgs::msg::JointTrajectory& detach_posture,
94 return parent_link_model_->
getName();
100 return parent_link_model_;
104 const std::vector<shapes::ShapeConstPtr>&
getShapes()
const
126 return detach_posture_;
133 return shape_poses_in_link_frame_;
141 return shape_poses_in_link_frame_;
148 return subframe_poses_;
154 return global_subframe_poses_;
164 for (
const auto& t : subframe_poses)
166 ASSERT_ISOMETRY(t.second)
168 subframe_poses_ = subframe_poses;
176 const Eigen::Isometry3d&
getSubframeTransform(
const std::string& frame_name,
bool* found =
nullptr)
const;
201 return global_collision_body_transforms_;
211 void computeTransform(
const Eigen::Isometry3d& parent_link_global_transform);
221 Eigen::Isometry3d pose_;
224 Eigen::Isometry3d global_pose_;
227 std::vector<shapes::ShapeConstPtr> shapes_;
230 EigenSTL::vector_Isometry3d shape_poses_;
233 EigenSTL::vector_Isometry3d shape_poses_in_link_frame_;
236 EigenSTL::vector_Isometry3d global_collision_body_transforms_;
239 std::set<std::string> touch_links_;
243 trajectory_msgs::msg::JointTrajectory detach_posture_;
Object defining bodies that can be attached to robot links.
void setSubframeTransforms(const moveit::core::FixedTransformsMap &subframe_poses)
Set all subframes of this object.
const std::string & getAttachedLinkName() const
Get the name of the link this body is attached to.
const std::set< std::string > & getTouchLinks() const
Get the links that the attached body is allowed to touch.
const trajectory_msgs::msg::JointTrajectory & getDetachPosture() const
Return the posture that is necessary for the object to be released, (if any). This is useful for exam...
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 & getGlobalSubframeTransforms() const
Get subframes of this object (in the world frame)
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)
const Eigen::Isometry3d & getGlobalPose() const
Get the pose of the attached body, relative to the world.
void setPadding(double padding)
Set the padding for the shapes of this attached object.
const EigenSTL::vector_Isometry3d & getFixedTransforms() const
Get the fixed transforms (the transforms to the shapes of this body, relative to the link)....
const moveit::core::FixedTransformsMap & getSubframes() const
Get subframes of this object (relative to the object pose). The returned transforms are guaranteed to...
bool hasSubframeTransform(const std::string &frame_name) const
Check whether a subframe of given @frame_name is present in this object.
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 LinkModel * getAttachedLink() const
Get the model of the link this body is attached to.
const EigenSTL::vector_Isometry3d & getShapePosesInLinkFrame() const
Get the fixed transforms (the transforms to the shapes of this body, relative to the link)....
void computeTransform(const Eigen::Isometry3d &parent_link_global_transform)
Recompute global_collision_body_transform given the transform of the parent link.
const Eigen::Isometry3d & getSubframeTransformInLinkFrame(const std::string &frame_name, bool *found=nullptr) const
Get the fixed transform to a named subframe on this body (relative to the robot 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::msg::JointTrajectory &detach_posture, const moveit::core::FixedTransformsMap &subframe_poses=moveit::core::FixedTransformsMap())
Construct an attached body for a specified link.
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)....
void setScale(double scale)
Set the scale for the shapes of this attached object.
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....
A link from the robot. Contains the constant transform applied to the link and its geometry.
const std::string & getName() const
The name of this link.
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...
std::function< void(AttachedBody *body, bool attached)> AttachedBodyCallback
Main namespace for MoveIt.