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 #ifndef MOVEIT_COLLISION_DETECTION_WORLD_
38 #define MOVEIT_COLLISION_DETECTION_WORLD_
39 
41 
42 #include <string>
43 #include <vector>
44 #include <map>
45 #include <memory>
46 #include <boost/function.hpp>
47 #include <Eigen/Geometry>
49 
50 namespace shapes
51 {
53 }
54 
55 namespace collision_detection
56 {
58 
60 class World
61 {
62 public:
64  World();
65 
69  World(const World& other);
70 
71  virtual ~World();
72 
73  /**********************************************************************/
74  /* Collision Bodies */
75  /**********************************************************************/
76 
78 
80  struct Object
81  {
82  Object(const std::string& id) : id_(id)
83  {
84  }
85 
87 
89  std::string id_;
90 
102  std::vector<shapes::ShapeConstPtr> shapes_;
103 
108  };
109 
111  std::vector<std::string> getObjectIds() const;
112 
114  ObjectConstPtr getObject(const std::string& id) const;
115 
117  typedef std::map<std::string, ObjectPtr>::const_iterator const_iterator;
119  const_iterator begin() const
120  {
121  return objects_.begin();
122  }
124  const_iterator end() const
125  {
126  return objects_.end();
127  }
129  std::size_t size() const
130  {
131  return objects_.size();
132  }
134  const_iterator find(const std::string& id) const
135  {
136  return objects_.find(id);
137  }
138 
140  bool hasObject(const std::string& id) const;
141 
147  void addToObject(const std::string& id, const std::vector<shapes::ShapeConstPtr>& shapes,
148  const EigenSTL::vector_Affine3d& poses);
149 
154  void addToObject(const std::string& id, const shapes::ShapeConstPtr& shape, const Eigen::Affine3d& pose);
155 
158  bool moveShapeInObject(const std::string& id, const shapes::ShapeConstPtr& shape, const Eigen::Affine3d& pose);
159 
161  bool moveObject(const std::string& id, const Eigen::Affine3d& transform);
162 
169  bool removeShapeFromObject(const std::string& id, const shapes::ShapeConstPtr& shape);
170 
175  bool removeObject(const std::string& id);
176 
180  void clearObjects();
181 
183  {
184  UNINITIALIZED = 0,
185  CREATE = 1,
186  DESTROY = 2,
187  MOVE_SHAPE = 4,
188  ADD_SHAPE = 8,
189  REMOVE_SHAPE = 16,
190  };
191 
195  class Action
196  {
197  public:
198  Action() : action_(UNINITIALIZED)
199  {
200  }
201  Action(int v) : action_(v)
202  {
203  }
204  operator ActionBits() const
205  {
206  return ActionBits(action_);
207  }
208 
209  private:
210  int action_;
211  };
212 
213 private:
214  class Observer;
215 
216 public:
218  {
219  public:
220  ObserverHandle() : observer_(NULL)
221  {
222  }
223 
224  private:
225  ObserverHandle(const Observer* o) : observer_(o)
226  {
227  }
229  friend class World;
230  };
231 
232  typedef boost::function<void(const ObjectConstPtr&, Action)> ObserverCallbackFn;
233 
238  ObserverHandle addObserver(const ObserverCallbackFn& callback);
239 
241  void removeObserver(const ObserverHandle observer_handle);
242 
245  void notifyObserverAllObjects(const ObserverHandle observer_handle, Action action) const;
246 
247 private:
249  void notify(const ObjectConstPtr&, Action);
250 
252  void notifyAll(Action action);
253 
257  void ensureUnique(ObjectPtr& obj);
258 
259  /* Add a shape with no checking */
260  virtual void addToObjectInternal(const ObjectPtr& obj, const shapes::ShapeConstPtr& shape,
261  const Eigen::Affine3d& pose);
262 
264  std::map<std::string, ObjectPtr> objects_;
265 
266  /* observers to call when something changes */
267  class Observer
268  {
269  public:
270  Observer(const ObserverCallbackFn& callback) : callback_(callback)
271  {
272  }
273  ObserverCallbackFn callback_;
274  };
275  std::vector<Observer*> observers_;
276 };
277 }
278 
279 #endif
ObserverCallbackFn callback_
Definition: world.h:273
std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > vector_Affine3d
std::vector< Observer * > observers_
Definition: world.h:275
const_iterator end() const
Definition: world.h:124
std::vector< shapes::ShapeConstPtr > shapes_
All the shapes making up this object.
Definition: world.h:102
Maintain a representation of the environment.
Definition: world.h:60
Represents an action that occurred on an object in the world. Several bits may be set indicating seve...
Definition: world.h:195
Object(const std::string &id)
Definition: world.h:82
std::map< std::string, ObjectPtr >::const_iterator const_iterator
Definition: world.h:117
Generic interface to collision detection.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::string id_
The id for this object.
Definition: world.h:89
boost::function< void(const ObjectConstPtr &, Action)> ObserverCallbackFn
Definition: world.h:232
MOVEIT_CLASS_FORWARD(Shape)
A representation of an object.
Definition: world.h:80
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
std::size_t size() const
Definition: world.h:129
#define MOVEIT_STRUCT_FORWARD(C)
Definition: class_forward.h:58
std::map< std::string, ObjectPtr > objects_
Definition: world.h:264
Observer(const ObserverCallbackFn &callback)
Definition: world.h:270
const_iterator begin() const
Definition: world.h:119
EigenSTL::vector_Affine3d shape_poses_
The poses of the corresponding entries in shapes_.
Definition: world.h:107
const_iterator find(const std::string &id) const
Definition: world.h:134
std::shared_ptr< const Shape > ShapeConstPtr


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Wed Jul 10 2019 04:03:05