moveit2
The MoveIt Motion Planning Framework for ROS 2.
world.cpp
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: Acorn Pooley, Ioan Sucan */
36 
38 #include <geometric_shapes/check_isometry.h>
39 #include <rclcpp/logger.hpp>
40 #include <rclcpp/logging.hpp>
41 
42 namespace collision_detection
43 {
44 // Logger
45 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_collision_detection.world");
46 
48 {
49 }
50 
51 World::World(const World& other)
52 {
53  objects_ = other.objects_;
54 }
55 
57 {
58  while (!observers_.empty())
59  removeObserver(observers_.front());
60 }
61 
62 inline void World::addToObjectInternal(const ObjectPtr& obj, const shapes::ShapeConstPtr& shape,
63  const Eigen::Isometry3d& shape_pose)
64 {
65  obj->shapes_.push_back(shape);
66  ASSERT_ISOMETRY(shape_pose) // unsanitized input, could contain a non-isometry
67  obj->shape_poses_.push_back(shape_pose);
68  obj->global_shape_poses_.push_back(obj->pose_ * shape_pose);
69 }
70 
71 void World::addToObject(const std::string& object_id, const Eigen::Isometry3d& pose,
72  const std::vector<shapes::ShapeConstPtr>& shapes,
73  const EigenSTL::vector_Isometry3d& shape_poses)
74 {
75  if (shapes.size() != shape_poses.size())
76  {
77  RCLCPP_ERROR(LOGGER,
78  "Number of shapes and number of poses do not match. Not adding this object to collision world.");
79  return;
80  }
81 
82  if (shapes.empty())
83  return;
84 
85  int action = ADD_SHAPE;
86 
87  ObjectPtr& obj = objects_[object_id];
88  if (!obj)
89  {
90  obj = std::make_shared<Object>(object_id);
91  action |= CREATE;
92  obj->pose_ = pose;
93  }
94  else
95  ensureUnique(obj);
96 
97  for (std::size_t i = 0; i < shapes.size(); ++i)
98  addToObjectInternal(obj, shapes[i], shape_poses[i]);
99 
100  notify(obj, Action(action));
101 }
102 
103 std::vector<std::string> World::getObjectIds() const
104 {
105  std::vector<std::string> ids;
106  for (const auto& object : objects_)
107  ids.push_back(object.first);
108  return ids;
109 }
110 
111 World::ObjectConstPtr World::getObject(const std::string& object_id) const
112 {
113  const auto it = objects_.find(object_id);
114  if (it == objects_.end())
115  return ObjectConstPtr();
116  else
117  return it->second;
118 }
119 
120 void World::ensureUnique(ObjectPtr& obj)
121 {
122  if (obj && !obj.unique())
123  obj = std::make_shared<Object>(*obj);
124 }
125 
126 bool World::hasObject(const std::string& object_id) const
127 {
128  return objects_.find(object_id) != objects_.end();
129 }
130 
131 bool World::knowsTransform(const std::string& name) const
132 {
133  // Check object names first
134  const std::map<std::string, ObjectPtr>::const_iterator it = objects_.find(name);
135  if (it != objects_.end())
136  return true;
137  else // Then objects' subframes
138  {
139  for (const std::pair<const std::string, ObjectPtr>& object : objects_)
140  {
141  // if "object name/" matches start of object_id, we found the matching object
142  // rfind searches name for object.first in the first index (returns 0 if found)
143  if (name.rfind(object.first, 0) == 0 && name[object.first.length()] == '/')
144  {
145  return object.second->global_subframe_poses_.find(name.substr(object.first.length() + 1)) !=
146  object.second->global_subframe_poses_.end();
147  }
148  }
149  }
150  return false;
151 }
152 
153 const Eigen::Isometry3d& World::getTransform(const std::string& name) const
154 {
155  bool found;
156  const Eigen::Isometry3d& result = getTransform(name, found);
157  if (!found)
158  throw std::runtime_error("No transform found with name: " + name);
159  return result;
160 }
161 
162 const Eigen::Isometry3d& World::getTransform(const std::string& name, bool& frame_found) const
163 {
164  // assume found
165  frame_found = true;
166 
167  const std::map<std::string, ObjectPtr>::const_iterator it = objects_.find(name);
168  if (it != objects_.end())
169  {
170  return it->second->pose_;
171  }
172  else // Search within subframes
173  {
174  for (const std::pair<const std::string, ObjectPtr>& object : objects_)
175  {
176  // if "object name/" matches start of object_id, we found the matching object
177  // rfind searches name for object.first in the first index (returns 0 if found)
178  if (name.rfind(object.first, 0) == 0 && name[object.first.length()] == '/')
179  {
180  const auto it = object.second->global_subframe_poses_.find(name.substr(object.first.length() + 1));
181  if (it != object.second->global_subframe_poses_.end())
182  {
183  return it->second;
184  }
185  }
186  }
187  }
188 
189  // we need a persisting isometry for the API
190  static const Eigen::Isometry3d IDENTITY_TRANSFORM = Eigen::Isometry3d::Identity();
191  frame_found = false;
192  return IDENTITY_TRANSFORM;
193 }
194 
195 const Eigen::Isometry3d& World::getGlobalShapeTransform(const std::string& object_id, const int shape_index) const
196 {
197  const auto it = objects_.find(object_id);
198  if (it != objects_.end())
199  {
200  return it->second->global_shape_poses_[shape_index];
201  }
202  else
203  {
204  RCLCPP_ERROR_STREAM(LOGGER, "Could not find global shape transform for object " << object_id);
205  static const Eigen::Isometry3d IDENTITY_TRANSFORM = Eigen::Isometry3d::Identity();
206  return IDENTITY_TRANSFORM;
207  }
208 }
209 
210 const EigenSTL::vector_Isometry3d& World::getGlobalShapeTransforms(const std::string& object_id) const
211 {
212  const auto it = objects_.find(object_id);
213  if (it != objects_.end())
214  {
215  return it->second->global_shape_poses_;
216  }
217  else
218  {
219  RCLCPP_ERROR_STREAM(LOGGER, "Could not find global shape transforms for object " << object_id);
220  static const EigenSTL::vector_Isometry3d IDENTITY_TRANSFORM_VECTOR;
221  return IDENTITY_TRANSFORM_VECTOR;
222  }
223 }
224 
225 bool World::moveShapeInObject(const std::string& object_id, const shapes::ShapeConstPtr& shape,
226  const Eigen::Isometry3d& shape_pose)
227 {
228  const auto it = objects_.find(object_id);
229  if (it != objects_.end())
230  {
231  const unsigned int n = it->second->shapes_.size();
232  for (unsigned int i = 0; i < n; ++i)
233  if (it->second->shapes_[i] == shape)
234  {
235  ensureUnique(it->second);
236  ASSERT_ISOMETRY(shape_pose) // unsanitized input, could contain a non-isometry
237  it->second->shape_poses_[i] = shape_pose;
238  it->second->global_shape_poses_[i] = it->second->pose_ * shape_pose;
239 
240  notify(it->second, MOVE_SHAPE);
241  return true;
242  }
243  }
244  return false;
245 }
246 
247 bool World::moveObject(const std::string& object_id, const Eigen::Isometry3d& transform)
248 {
249  const auto it = objects_.find(object_id);
250  if (it == objects_.end())
251  return false;
252  if (transform.isApprox(Eigen::Isometry3d::Identity()))
253  return true; // object already at correct location
254 
255  ASSERT_ISOMETRY(transform) // unsanitized input, could contain a non-isometry
256  return setObjectPose(object_id, transform * it->second->pose_);
257 }
258 
259 bool World::setObjectPose(const std::string& object_id, const Eigen::Isometry3d& pose)
260 {
261  ASSERT_ISOMETRY(pose); // unsanitized input, could contain a non-isometry
262  ObjectPtr& obj = objects_[object_id];
263  int action;
264  if (!obj)
265  {
266  obj = std::make_shared<Object>(object_id);
267  action = CREATE;
268  }
269  else
270  {
271  ensureUnique(obj);
272  action = obj->shapes_.empty() ? 0 : MOVE_SHAPE;
273  }
274 
275  obj->pose_ = pose;
276  updateGlobalPosesInternal(obj);
277  notify(obj, Action(action));
278  return true;
279 }
280 
281 bool World::removeShapeFromObject(const std::string& object_id, const shapes::ShapeConstPtr& shape)
282 {
283  const auto it = objects_.find(object_id);
284  if (it != objects_.end())
285  {
286  const unsigned int n = it->second->shapes_.size();
287  for (unsigned int i = 0; i < n; ++i)
288  if (it->second->shapes_[i] == shape)
289  {
290  ensureUnique(it->second);
291  it->second->shapes_.erase(it->second->shapes_.begin() + i);
292  it->second->shape_poses_.erase(it->second->shape_poses_.begin() + i);
293  it->second->global_shape_poses_.erase(it->second->global_shape_poses_.begin() + i);
294 
295  if (it->second->shapes_.empty())
296  {
297  notify(it->second, DESTROY);
298  objects_.erase(it);
299  }
300  else
301  {
302  notify(it->second, REMOVE_SHAPE);
303  }
304  return true;
305  }
306  }
307  return false;
308 }
309 
310 bool World::removeObject(const std::string& object_id)
311 {
312  const auto it = objects_.find(object_id);
313  if (it != objects_.end())
314  {
315  notify(it->second, DESTROY);
316  objects_.erase(it);
317  return true;
318  }
319  return false;
320 }
321 
323 {
324  notifyAll(DESTROY);
325  objects_.clear();
326 }
327 
328 bool World::setSubframesOfObject(const std::string& object_id, const moveit::core::FixedTransformsMap& subframe_poses)
329 {
330  const auto obj_pair = objects_.find(object_id);
331  if (obj_pair == objects_.end())
332  {
333  return false;
334  }
335  for (const auto& t : subframe_poses)
336  {
337  ASSERT_ISOMETRY(t.second) // unsanitized input, could contain a non-isometry
338  }
339  obj_pair->second->subframe_poses_ = subframe_poses;
340  obj_pair->second->global_subframe_poses_ = subframe_poses;
341  updateGlobalPosesInternal(obj_pair->second, false, true);
342  return true;
343 }
344 
345 void World::updateGlobalPosesInternal(ObjectPtr& obj, bool update_shape_poses, bool update_subframe_poses)
346 {
347  // Update global shape poses
348  if (update_shape_poses)
349  for (unsigned int i = 0; i < obj->global_shape_poses_.size(); ++i)
350  obj->global_shape_poses_[i] = obj->pose_ * obj->shape_poses_[i];
351 
352  // Update global subframe poses
353  if (update_subframe_poses)
354  {
355  for (auto it_global_pose = obj->global_subframe_poses_.begin(), it_local_pose = obj->subframe_poses_.begin(),
356  end_poses = obj->global_subframe_poses_.end();
357  it_global_pose != end_poses; ++it_global_pose, ++it_local_pose)
358  {
359  it_global_pose->second = obj->pose_ * it_local_pose->second;
360  }
361  }
362 }
363 
365 {
366  const auto o = new Observer(callback);
367  observers_.push_back(o);
368  return ObserverHandle(o);
369 }
370 
372 {
373  for (auto obs = observers_.begin(); obs != observers_.end(); ++obs)
374  {
375  if (*obs == observer_handle.observer_)
376  {
377  delete *obs;
378  observers_.erase(obs);
379  return;
380  }
381  }
382 }
383 
384 void World::notifyAll(Action action)
385 {
386  for (std::map<std::string, ObjectPtr>::const_iterator it = objects_.begin(); it != objects_.end(); ++it)
387  notify(it->second, action);
388 }
389 
390 void World::notify(const ObjectConstPtr& obj, Action action)
391 {
392  for (Observer* observer : observers_)
393  observer->callback_(obj, action);
394 }
395 
397 {
398  for (auto observer : observers_)
399  {
400  if (observer == observer_handle.observer_)
401  {
402  // call the callback for each object
403  for (const auto& object : objects_)
404  observer->callback_(object.second, action);
405  break;
406  }
407  }
408 }
409 
410 } // end of namespace collision_detection
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
void removeObserver(const ObserverHandle observer_handle)
remove a notifier callback
Definition: world.cpp:371
std::function< void(const ObjectConstPtr &, Action)> ObserverCallbackFn
Definition: world.h:301
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
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
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
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
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
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