moveit2
The MoveIt Motion Planning Framework for ROS 2.
world.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, 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 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, Acorn Pooley, Sachin Chitta */
36 
37 #pragma once
38 
40 #include <string>
41 #include <vector>
42 #include <map>
43 #include <functional>
44 #include <Eigen/Geometry>
45 #include <eigen_stl_containers/eigen_stl_vector_container.h>
47 
48 namespace shapes
49 {
50 MOVEIT_CLASS_FORWARD(Shape); // Defines ShapePtr, ConstPtr, WeakPtr... etc
51 }
52 
53 namespace collision_detection
54 {
55 MOVEIT_CLASS_FORWARD(World); // Defines WorldPtr, ConstPtr, WeakPtr... etc
56 
58 class World
59 {
60 public:
62  World();
63 
67  World(const World& other);
68 
69  virtual ~World();
70 
71  /**********************************************************************/
72  /* Collision Bodies */
73  /**********************************************************************/
74 
76 
78  struct Object
79  {
80  Object(const std::string& object_id) : id_(object_id)
81  {
82  }
83 
85 
87  std::string id_;
88 
91  Eigen::Isometry3d pose_;
92 
96  std::vector<shapes::ShapeConstPtr> shapes_;
97 
101  EigenSTL::vector_Isometry3d shape_poses_;
102 
106  EigenSTL::vector_Isometry3d global_shape_poses_;
107 
113 
117  };
118 
120  std::vector<std::string> getObjectIds() const;
121 
123  ObjectConstPtr getObject(const std::string& object_id) const;
124 
126  using const_iterator = std::map<std::string, ObjectPtr>::const_iterator;
129  {
130  return objects_.begin();
131  }
134  {
135  return objects_.end();
136  }
138  std::size_t size() const
139  {
140  return objects_.size();
141  }
143  const_iterator find(const std::string& object_id) const
144  {
145  return objects_.find(object_id);
146  }
147 
149  bool hasObject(const std::string& object_id) const;
150 
153  bool knowsTransform(const std::string& name) const;
154 
160  const Eigen::Isometry3d& getTransform(const std::string& name) const;
161 
167  const Eigen::Isometry3d& getTransform(const std::string& name, bool& frame_found) const;
168 
172  const Eigen::Isometry3d& getGlobalShapeTransform(const std::string& object_id, int shape_index) const;
173 
176  const EigenSTL::vector_Isometry3d& getGlobalShapeTransforms(const std::string& object_id) const;
177 
181  void addToObject(const std::string& object_id, const Eigen::Isometry3d& pose,
182  const std::vector<shapes::ShapeConstPtr>& shapes, const EigenSTL::vector_Isometry3d& shape_poses);
183 
187  void addToObject(const std::string& object_id, const std::vector<shapes::ShapeConstPtr>& shapes,
188  const EigenSTL::vector_Isometry3d& shape_poses)
189  {
190  addToObject(object_id, Eigen::Isometry3d::Identity(), shapes, shape_poses);
191  }
192 
198  void addToObject(const std::string& object_id, const Eigen::Isometry3d& pose, const shapes::ShapeConstPtr& shape,
199  const Eigen::Isometry3d& shape_pose)
200  {
201  addToObject(object_id, pose, std::vector<shapes::ShapeConstPtr>{ shape }, EigenSTL::vector_Isometry3d{ shape_pose });
202  }
203 
209  void addToObject(const std::string& object_id, const shapes::ShapeConstPtr& shape, const Eigen::Isometry3d& shape_pose)
210  {
211  addToObject(object_id, Eigen::Isometry3d::Identity(), std::vector<shapes::ShapeConstPtr>{ shape },
212  EigenSTL::vector_Isometry3d{ shape_pose });
213  }
214 
217  bool moveShapeInObject(const std::string& object_id, const shapes::ShapeConstPtr& shape,
218  const Eigen::Isometry3d& shape_pose);
219 
224  bool moveObject(const std::string& object_id, const Eigen::Isometry3d& transform);
225 
227  bool setObjectPose(const std::string& object_id, const Eigen::Isometry3d& pose);
228 
235  bool removeShapeFromObject(const std::string& object_id, const shapes::ShapeConstPtr& shape);
236 
241  bool removeObject(const std::string& object_id);
242 
244  bool setSubframesOfObject(const std::string& object_id, const moveit::core::FixedTransformsMap& subframe_poses);
245 
249  void clearObjects();
250 
252  {
254  CREATE = 1,
255  DESTROY = 2,
257  ADD_SHAPE = 8,
259  };
260 
264  class Action
265  {
266  public:
267  Action() : action_(UNINITIALIZED)
268  {
269  }
270  Action(int v) : action_(v)
271  {
272  }
273  operator ActionBits() const
274  {
275  return ActionBits(action_);
276  }
277 
278  private:
279  int action_;
280  };
281 
282 private:
283  class Observer;
284 
285 public:
287  {
288  public:
289  ObserverHandle() : observer_(nullptr)
290  {
291  }
292 
293  private:
294  ObserverHandle(const Observer* o) : observer_(o)
295  {
296  }
297  const Observer* observer_;
298  friend class World;
299  };
300 
301  using ObserverCallbackFn = std::function<void(const ObjectConstPtr&, Action)>;
302 
308 
310  void removeObserver(const ObserverHandle observer_handle);
311 
314  void notifyObserverAllObjects(const ObserverHandle observer_handle, Action action) const;
315 
316 private:
318  void notify(const ObjectConstPtr& /*obj*/, Action /*action*/);
319 
321  void notifyAll(Action action);
322 
326  void ensureUnique(ObjectPtr& obj);
327 
328  /* Add a shape with no checking */
329  virtual void addToObjectInternal(const ObjectPtr& obj, const shapes::ShapeConstPtr& shape,
330  const Eigen::Isometry3d& shape_pose);
331 
333  void updateGlobalPosesInternal(ObjectPtr& obj, bool update_shape_poses = true, bool update_subframe_poses = true);
334 
336  std::map<std::string, ObjectPtr> objects_;
337 
339  class Observer
340  {
341  public:
342  Observer(const ObserverCallbackFn& callback) : callback_(callback)
343  {
344  }
345  ObserverCallbackFn callback_;
346  };
347 
349  std::vector<Observer*> observers_;
350 };
351 } // namespace collision_detection
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
Represents an action that occurred on an object in the world. Several bits may be set indicating seve...
Definition: world.h:265
Maintain a representation of the environment.
Definition: world.h:59
const Eigen::Isometry3d & getTransform(const std::string &name) const
Get the transform to an object or subframe with given name. If name does not exist,...
Definition: world.cpp:153
const_iterator find(const std::string &object_id) const
Definition: world.h:143
void removeObserver(const ObserverHandle observer_handle)
remove a notifier callback
Definition: world.cpp:371
void addToObject(const std::string &object_id, const shapes::ShapeConstPtr &shape, const Eigen::Isometry3d &shape_pose)
Add a shape to an object. If the object already exists, this call will add the shape to the object at...
Definition: world.h:209
std::function< void(const ObjectConstPtr &, Action)> ObserverCallbackFn
Definition: world.h:301
std::size_t size() const
Definition: world.h:138
bool hasObject(const std::string &object_id) const
Check if a particular object exists in the collision world.
Definition: world.cpp:126
bool removeObject(const std::string &object_id)
Remove a particular object. If there are no external pointers to the corresponding instance of Object...
Definition: world.cpp:310
std::map< std::string, ObjectPtr >::const_iterator const_iterator
Definition: world.h:126
bool moveShapeInObject(const std::string &object_id, const shapes::ShapeConstPtr &shape, const Eigen::Isometry3d &shape_pose)
Update the pose of a shape in an object. Shape equality is verified by comparing pointers....
Definition: world.cpp:225
void notifyObserverAllObjects(const ObserverHandle observer_handle, Action action) const
Definition: world.cpp:396
bool removeShapeFromObject(const std::string &object_id, const shapes::ShapeConstPtr &shape)
Remove shape from object. Shape equality is verified by comparing pointers. Ownership of the object i...
Definition: world.cpp:281
const Eigen::Isometry3d & getGlobalShapeTransform(const std::string &object_id, int shape_index) const
Get the global transform to a shape of an object with multiple shapes. shape_index is the index of th...
Definition: world.cpp:195
void addToObject(const std::string &object_id, const Eigen::Isometry3d &pose, const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Isometry3d &shape_poses)
Add a pose and shapes to an object in the map. This function makes repeated calls to addToObjectInter...
Definition: world.cpp:71
World()
Constructor.
Definition: world.cpp:47
bool moveObject(const std::string &object_id, const Eigen::Isometry3d &transform)
Move the object pose (thus moving all shapes and subframes in the object) according to the given tran...
Definition: world.cpp:247
ObserverHandle addObserver(const ObserverCallbackFn &callback)
register a callback function for notification of changes. callback will be called right after any cha...
Definition: world.cpp:364
const_iterator begin() const
Definition: world.h:128
bool setObjectPose(const std::string &object_id, const Eigen::Isometry3d &pose)
Set the pose of an object. The pose is specified in the world frame.
Definition: world.cpp:259
bool setSubframesOfObject(const std::string &object_id, const moveit::core::FixedTransformsMap &subframe_poses)
Set subframes on an object. The frames are relative to the object pose.
Definition: world.cpp:328
void addToObject(const std::string &object_id, const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Isometry3d &shape_poses)
Add shapes to an object in the map. This function makes repeated calls to addToObjectInternal() to ad...
Definition: world.h:187
void addToObject(const std::string &object_id, const Eigen::Isometry3d &pose, const shapes::ShapeConstPtr &shape, const Eigen::Isometry3d &shape_pose)
Add a pose and shape to an object. If the object already exists, this call will add the shape to the ...
Definition: world.h:198
bool knowsTransform(const std::string &name) const
Check if an object or subframe with given name exists in the collision world. A subframe name needs t...
Definition: world.cpp:131
void clearObjects()
Clear all objects. If there are no other pointers to corresponding instances of Objects,...
Definition: world.cpp:322
const_iterator end() const
Definition: world.h:133
ObjectConstPtr getObject(const std::string &object_id) const
Get a particular object.
Definition: world.cpp:111
const EigenSTL::vector_Isometry3d & getGlobalShapeTransforms(const std::string &object_id) const
Get the global transforms to the shapes of an object. This function is used to construct the collisio...
Definition: world.cpp:210
std::vector< std::string > getObjectIds() const
Get the list of Object ids.
Definition: world.cpp:103
MOVEIT_CLASS_FORWARD(AllowedCollisionMatrix)
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
name
Definition: setup.py:7
Definition: world.h:49
MOVEIT_CLASS_FORWARD(Shape)
A representation of an object.
Definition: world.h:79
EigenSTL::vector_Isometry3d global_shape_poses_
The poses of the corresponding entries in shapes_, relative to the world frame.
Definition: world.h:106
moveit::core::FixedTransformsMap subframe_poses_
Transforms from the object pose to subframes on the object. Use them to define points of interest on ...
Definition: world.h:112
Eigen::Isometry3d pose_
The object's pose. All shapes and subframes are defined relative to this frame. This frame is returne...
Definition: world.h:91
Object(const std::string &object_id)
Definition: world.h:80
EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::string id_
The id for this object.
Definition: world.h:87
moveit::core::FixedTransformsMap global_subframe_poses_
Transforms from the world frame to the object subframes.
Definition: world.h:116
EigenSTL::vector_Isometry3d shape_poses_
The poses of the corresponding entries in shapes_, relative to the object pose.
Definition: world.h:101
std::vector< shapes::ShapeConstPtr > shapes_
All the shapes making up this object.
Definition: world.h:96