moveit2
The MoveIt Motion Planning Framework for ROS 2.
attached_body.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
37 #pragma once
38 
41 #include <geometric_shapes/check_isometry.h>
42 #include <eigen_stl_containers/eigen_stl_containers.h>
43 #include <trajectory_msgs/msg/joint_trajectory.hpp>
44 #include <set>
45 #include <functional>
46 
47 namespace moveit
48 {
49 namespace core
50 {
51 class AttachedBody;
52 typedef std::function<void(AttachedBody* body, bool attached)> AttachedBodyCallback;
53 
58 {
59 public:
66  AttachedBody(const LinkModel* parent, const std::string& id, const Eigen::Isometry3d& pose,
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,
70 
72 
74  const std::string& getName() const
75  {
76  return id_;
77  }
78 
80  const Eigen::Isometry3d& getPose() const
81  {
82  return pose_;
83  }
84 
86  const Eigen::Isometry3d& getGlobalPose() const
87  {
88  return global_pose_;
89  }
90 
92  const std::string& getAttachedLinkName() const
93  {
94  return parent_link_model_->getName();
95  }
96 
98  const LinkModel* getAttachedLink() const
99  {
100  return parent_link_model_;
101  }
102 
104  const std::vector<shapes::ShapeConstPtr>& getShapes() const
105  {
106  return shapes_;
107  }
108 
111  const EigenSTL::vector_Isometry3d& getShapePoses() const
112  {
113  return shape_poses_;
114  }
115 
117  const std::set<std::string>& getTouchLinks() const
118  {
119  return touch_links_;
120  }
121 
124  const trajectory_msgs::msg::JointTrajectory& getDetachPosture() const
125  {
126  return detach_posture_;
127  }
128 
131  const EigenSTL::vector_Isometry3d& getShapePosesInLinkFrame() const
132  {
133  return shape_poses_in_link_frame_;
134  }
135 
139  [[deprecated]] const EigenSTL::vector_Isometry3d& getFixedTransforms() const
140  {
141  return shape_poses_in_link_frame_;
142  }
143 
147  {
148  return subframe_poses_;
149  }
150 
153  {
154  return global_subframe_poses_;
155  }
156 
163  {
164  for (const auto& t : subframe_poses)
165  {
166  ASSERT_ISOMETRY(t.second) // unsanitized input, could contain a non-isometry
167  }
168  subframe_poses_ = subframe_poses;
169  }
170 
176  const Eigen::Isometry3d& getSubframeTransform(const std::string& frame_name, bool* found = nullptr) const;
177 
183  const Eigen::Isometry3d& getSubframeTransformInLinkFrame(const std::string& frame_name, bool* found = nullptr) const;
184 
189  const Eigen::Isometry3d& getGlobalSubframeTransform(const std::string& frame_name, bool* found = nullptr) const;
190 
195  bool hasSubframeTransform(const std::string& frame_name) const;
196 
199  const EigenSTL::vector_Isometry3d& getGlobalCollisionBodyTransforms() const
200  {
201  return global_collision_body_transforms_;
202  }
203 
205  void setPadding(double padding);
206 
208  void setScale(double scale);
209 
211  void computeTransform(const Eigen::Isometry3d& parent_link_global_transform);
212 
213 private:
215  const LinkModel* parent_link_model_;
216 
218  std::string id_;
219 
221  Eigen::Isometry3d pose_;
222 
224  Eigen::Isometry3d global_pose_;
225 
227  std::vector<shapes::ShapeConstPtr> shapes_;
228 
230  EigenSTL::vector_Isometry3d shape_poses_;
231 
233  EigenSTL::vector_Isometry3d shape_poses_in_link_frame_;
234 
236  EigenSTL::vector_Isometry3d global_collision_body_transforms_;
237 
239  std::set<std::string> touch_links_;
240 
243  trajectory_msgs::msg::JointTrajectory detach_posture_;
244 
246  moveit::core::FixedTransformsMap subframe_poses_;
247 
249  moveit::core::FixedTransformsMap global_subframe_poses_;
250 };
251 } // namespace core
252 } // namespace moveit
Object defining bodies that can be attached to robot links.
Definition: attached_body.h:58
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.
Definition: attached_body.h:92
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.
Definition: attached_body.h:86
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.
Definition: attached_body.h:74
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.
Definition: attached_body.h:98
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.
Definition: attached_body.h:80
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.
Definition: link_model.h:72
const std::string & getName() const
The name of this link.
Definition: link_model.h:86
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...
Definition: transforms.h:53
std::function< void(AttachedBody *body, bool attached)> AttachedBodyCallback
Definition: attached_body.h:51
Main namespace for MoveIt.
Definition: exceptions.h:43
Definition: world.h:49