moveit2
The MoveIt Motion Planning Framework for ROS 2.
collision_env_bullet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2019, Jens Petit
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 the copyright holder 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: Jens Petit */
36 
41 #include <functional>
42 #include <bullet/btBulletCollisionCommon.h>
43 #include <rclcpp/logger.hpp>
44 #include <rclcpp/logging.hpp>
45 
46 namespace collision_detection
47 {
48 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.core.collision_detection.bullet");
49 const std::string CollisionDetectorAllocatorBullet::NAME("Bullet");
50 const double MAX_DISTANCE_MARGIN = 99;
51 
52 CollisionEnvBullet::CollisionEnvBullet(const moveit::core::RobotModelConstPtr& model, double padding, double scale)
53  : CollisionEnv(model, padding, scale)
54 {
55  // request notifications about changes to new world
56  observer_handle_ = getWorld()->addObserver(
57  [this](const World::ObjectConstPtr& object, World::Action action) { notifyObjectChange(object, action); });
58 
59  for (const std::pair<const std::string, urdf::LinkSharedPtr>& link : robot_model_->getURDF()->links_)
60  {
61  addLinkAsCollisionObject(link.second);
62  }
63 }
64 
65 CollisionEnvBullet::CollisionEnvBullet(const moveit::core::RobotModelConstPtr& model, const WorldPtr& world,
66  double padding, double scale)
67  : CollisionEnv(model, world, padding, scale)
68 {
69  // request notifications about changes to new world
70  observer_handle_ = getWorld()->addObserver(
71  [this](const World::ObjectConstPtr& object, World::Action action) { notifyObjectChange(object, action); });
72 
73  for (const std::pair<const std::string, urdf::LinkSharedPtr>& link : robot_model_->getURDF()->links_)
74  {
75  addLinkAsCollisionObject(link.second);
76  }
77 
78  getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE);
79 }
80 
81 CollisionEnvBullet::CollisionEnvBullet(const CollisionEnvBullet& other, const WorldPtr& world)
82  : CollisionEnv(other, world)
83 {
84  // request notifications about changes to new world
85  observer_handle_ = getWorld()->addObserver(
86  [this](const World::ObjectConstPtr& object, World::Action action) { notifyObjectChange(object, action); });
87 
88  for (const std::pair<const std::string, urdf::LinkSharedPtr>& link : other.robot_model_->getURDF()->links_)
89  {
90  addLinkAsCollisionObject(link.second);
91  }
92 
93  // get notifications any objects already in the new world
94  getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE);
95 }
96 
98 {
99  getWorld()->removeObserver(observer_handle_);
100 }
101 
103  const moveit::core::RobotState& state) const
104 {
105  checkSelfCollisionHelper(req, res, state, nullptr);
106 }
107 
109  const moveit::core::RobotState& state,
110  const AllowedCollisionMatrix& acm) const
111 {
112  checkSelfCollisionHelper(req, res, state, &acm);
113 }
114 
116  const moveit::core::RobotState& state,
117  const AllowedCollisionMatrix* acm) const
118 {
119  std::lock_guard<std::mutex> guard(collision_env_mutex_);
120 
121  std::vector<collision_detection_bullet::CollisionObjectWrapperPtr> cows;
122  addAttachedOjects(state, cows);
123 
124  if (req.distance)
125  {
126  manager_->setContactDistanceThreshold(MAX_DISTANCE_MARGIN);
127  }
128 
129  for (const collision_detection_bullet::CollisionObjectWrapperPtr& cow : cows)
130  {
131  manager_->addCollisionObject(cow);
132  manager_->setCollisionObjectsTransform(
133  cow->getName(), state.getAttachedBody(cow->getName())->getGlobalCollisionBodyTransforms()[0]);
134  }
135 
136  // updating link positions with the current robot state
137  for (const std::string& link : active_)
138  {
139  manager_->setCollisionObjectsTransform(link, state.getCollisionBodyTransform(link, 0));
140  }
141 
142  manager_->contactTest(res, req, acm, true);
143 
144  for (const collision_detection_bullet::CollisionObjectWrapperPtr& cow : cows)
145  {
146  manager_->removeCollisionObject(cow->getName());
147  }
148 }
149 
151  const moveit::core::RobotState& state) const
152 {
153  checkRobotCollisionHelper(req, res, state, nullptr);
154 }
155 
157  const moveit::core::RobotState& state,
158  const AllowedCollisionMatrix& acm) const
159 {
160  checkRobotCollisionHelper(req, res, state, &acm);
161 }
162 
164  const moveit::core::RobotState& state1,
165  const moveit::core::RobotState& state2) const
166 {
167  checkRobotCollisionHelperCCD(req, res, state1, state2, nullptr);
168 }
169 
171  const moveit::core::RobotState& state1,
172  const moveit::core::RobotState& state2,
173  const AllowedCollisionMatrix& acm) const
174 {
175  checkRobotCollisionHelperCCD(req, res, state1, state2, &acm);
176 }
177 
179  const moveit::core::RobotState& state,
180  const AllowedCollisionMatrix* acm) const
181 {
182  std::lock_guard<std::mutex> guard(collision_env_mutex_);
183 
184  if (req.distance)
185  {
186  manager_->setContactDistanceThreshold(MAX_DISTANCE_MARGIN);
187  }
188 
189  std::vector<collision_detection_bullet::CollisionObjectWrapperPtr> attached_cows;
190  addAttachedOjects(state, attached_cows);
192 
193  for (const collision_detection_bullet::CollisionObjectWrapperPtr& cow : attached_cows)
194  {
195  manager_->addCollisionObject(cow);
196  manager_->setCollisionObjectsTransform(
197  cow->getName(), state.getAttachedBody(cow->getName())->getGlobalCollisionBodyTransforms()[0]);
198  }
199 
200  manager_->contactTest(res, req, acm, false);
201 
202  for (const collision_detection_bullet::CollisionObjectWrapperPtr& cow : attached_cows)
203  {
204  manager_->removeCollisionObject(cow->getName());
205  }
206 }
207 
209  const moveit::core::RobotState& state1,
210  const moveit::core::RobotState& state2,
211  const AllowedCollisionMatrix* acm) const
212 {
213  std::lock_guard<std::mutex> guard(collision_env_mutex_);
214 
215  std::vector<collision_detection_bullet::CollisionObjectWrapperPtr> attached_cows;
216  addAttachedOjects(state1, attached_cows);
217 
218  for (const collision_detection_bullet::CollisionObjectWrapperPtr& cow : attached_cows)
219  {
220  manager_CCD_->addCollisionObject(cow);
221  manager_CCD_->setCastCollisionObjectsTransform(
222  cow->getName(), state1.getAttachedBody(cow->getName())->getGlobalCollisionBodyTransforms()[0],
223  state2.getAttachedBody(cow->getName())->getGlobalCollisionBodyTransforms()[0]);
224  }
225 
226  for (const std::string& link : active_)
227  {
228  manager_CCD_->setCastCollisionObjectsTransform(link, state1.getCollisionBodyTransform(link, 0),
229  state2.getCollisionBodyTransform(link, 0));
230  }
231 
232  manager_CCD_->contactTest(res, req, acm, false);
233 
234  for (const collision_detection_bullet::CollisionObjectWrapperPtr& cow : attached_cows)
235  {
236  manager_CCD_->removeCollisionObject(cow->getName());
237  }
238 }
239 
241  const moveit::core::RobotState& /*state*/) const
242 {
243  RCLCPP_INFO(LOGGER, "distanceSelf is not implemented for Bullet.");
244 }
245 
247  const moveit::core::RobotState& /*state*/) const
248 {
249  RCLCPP_INFO(LOGGER, "distanceRobot is not implemented for Bullet.");
250 }
251 
253 {
254  std::vector<collision_detection_bullet::CollisionObjectType> collision_object_types;
255 
256  for (const shapes::ShapeConstPtr& shape : obj->shapes_)
257  {
258  if (shape->type == shapes::MESH)
259  collision_object_types.push_back(collision_detection_bullet::CollisionObjectType::CONVEX_HULL);
260  else
261  collision_object_types.push_back(collision_detection_bullet::CollisionObjectType::USE_SHAPE_TYPE);
262  }
263 
264  auto cow = std::make_shared<collision_detection_bullet::CollisionObjectWrapper>(
266  collision_object_types, false);
267 
268  manager_->addCollisionObject(cow);
269  manager_CCD_->addCollisionObject(cow->clone());
270 }
271 
272 void CollisionEnvBullet::updateManagedObject(const std::string& id)
273 {
274  if (getWorld()->hasObject(id))
275  {
276  auto it = getWorld()->find(id);
277  if (manager_->hasCollisionObject(id))
278  {
279  manager_->removeCollisionObject(id);
280  manager_CCD_->removeCollisionObject(id);
281  addToManager(it->second.get());
282  }
283  else
284  {
285  addToManager(it->second.get());
286  }
287  }
288  else
289  {
290  if (manager_->hasCollisionObject(id))
291  {
292  manager_->removeCollisionObject(id);
293  manager_CCD_->removeCollisionObject(id);
294  }
295  }
296 }
297 
298 void CollisionEnvBullet::setWorld(const WorldPtr& world)
299 {
300  if (world == getWorld())
301  return;
302 
303  // turn off notifications about old world
304  getWorld()->removeObserver(observer_handle_);
305 
306  CollisionEnv::setWorld(world);
307 
308  // request notifications about changes to new world
309  observer_handle_ = getWorld()->addObserver(
310  [this](const World::ObjectConstPtr& object, World::Action action) { notifyObjectChange(object, action); });
311 
312  // get notifications any objects already in the new world
313  getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE);
314 }
315 
316 void CollisionEnvBullet::notifyObjectChange(const ObjectConstPtr& obj, World::Action action)
317 {
318  std::lock_guard<std::mutex> guard(collision_env_mutex_);
319  if (action == World::DESTROY)
320  {
321  manager_->removeCollisionObject(obj->id_);
322  manager_CCD_->removeCollisionObject(obj->id_);
323  }
324  else
325  {
326  updateManagedObject(obj->id_);
327  }
328 }
329 
331  std::vector<collision_detection_bullet::CollisionObjectWrapperPtr>& cows) const
332 {
333  std::vector<const moveit::core::AttachedBody*> attached_bodies;
334  state.getAttachedBodies(attached_bodies);
335 
336  for (const moveit::core::AttachedBody*& body : attached_bodies)
337  {
338  const EigenSTL::vector_Isometry3d& attached_body_transform = body->getGlobalCollisionBodyTransforms();
339 
340  std::vector<collision_detection_bullet::CollisionObjectType> collision_object_types(
342 
343  try
344  {
345  collision_detection_bullet::CollisionObjectWrapperPtr cow =
346  std::make_shared<collision_detection_bullet::CollisionObjectWrapper>(
347  body->getName(), collision_detection::BodyType::ROBOT_ATTACHED, body->getShapes(),
348  attached_body_transform, collision_object_types, body->getTouchLinks());
349  cows.push_back(cow);
350  }
351  catch (std::exception&)
352  {
353  RCLCPP_ERROR_STREAM(LOGGER, "Not adding " << body->getName() << " due to bad arguments.");
354  }
355  }
356 }
357 
358 void CollisionEnvBullet::updatedPaddingOrScaling(const std::vector<std::string>& links)
359 {
360  for (const std::string& link : links)
361  {
362  if (robot_model_->getURDF()->links_.find(link) != robot_model_->getURDF()->links_.end())
363  {
364  addLinkAsCollisionObject(robot_model_->getURDF()->links_[link]);
365  }
366  else
367  {
368  RCLCPP_ERROR(LOGGER, "Updating padding or scaling for unknown link: '%s'", link.c_str());
369  }
370  }
371 }
372 
374  const moveit::core::RobotState& state, const collision_detection_bullet::BulletDiscreteBVHManagerPtr& manager) const
375 {
376  // updating link positions with the current robot state
377  for (const std::string& link : active_)
378  {
379  // select the first of the transformations for each link (composed of multiple shapes...)
380  manager->setCollisionObjectsTransform(link, state.getCollisionBodyTransform(link, 0));
381  }
382 }
383 
384 void CollisionEnvBullet::addLinkAsCollisionObject(const urdf::LinkSharedPtr& link)
385 {
386  if (!link->collision_array.empty())
387  {
388  const std::vector<urdf::CollisionSharedPtr>& col_array =
389  link->collision_array.empty() ? std::vector<urdf::CollisionSharedPtr>(1, link->collision) :
390  link->collision_array;
391 
392  std::vector<shapes::ShapeConstPtr> shapes;
394  std::vector<collision_detection_bullet::CollisionObjectType> collision_object_types;
395 
396  for (const auto& i : col_array)
397  {
398  if (i && i->geometry)
399  {
400  shapes::ShapePtr shape = collision_detection_bullet::constructShape(i->geometry.get());
401 
402  if (shape)
403  {
404  if (fabs(getLinkScale(link->name) - 1.0) >= std::numeric_limits<double>::epsilon() ||
405  fabs(getLinkPadding(link->name)) >= std::numeric_limits<double>::epsilon())
406  {
407  shape->scaleAndPadd(getLinkScale(link->name), getLinkPadding(link->name));
408  }
409 
410  shapes.push_back(shape);
411  shape_poses.push_back(collision_detection_bullet::urdfPose2Eigen(i->origin));
412 
413  if (shape->type == shapes::MESH)
414  {
415  collision_object_types.push_back(collision_detection_bullet::CollisionObjectType::CONVEX_HULL);
416  }
417  else
418  {
419  collision_object_types.push_back(collision_detection_bullet::CollisionObjectType::USE_SHAPE_TYPE);
420  }
421  }
422  }
423  }
424 
425  if (manager_->hasCollisionObject(link->name))
426  {
427  manager_->removeCollisionObject(link->name);
428  manager_CCD_->removeCollisionObject(link->name);
429  }
430 
431  try
432  {
433  collision_detection_bullet::CollisionObjectWrapperPtr cow =
434  std::make_shared<collision_detection_bullet::CollisionObjectWrapper>(
435  link->name, collision_detection::BodyType::ROBOT_LINK, shapes, shape_poses, collision_object_types, true);
436  manager_->addCollisionObject(cow);
437  manager_CCD_->addCollisionObject(cow->clone());
438  active_.push_back(cow->getName());
439  }
440  catch (std::exception&)
441  {
442  RCLCPP_ERROR_STREAM(LOGGER, "Not adding " << link->name << " due to bad arguments.");
443  }
444  }
445 }
446 
447 } // end of namespace collision_detection
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
collision_detection_bullet::BulletCastBVHManagerPtr manager_CCD_
Handles continuous robot world collision checks.
void setWorld(const WorldPtr &world) override
void updateTransformsFromState(const moveit::core::RobotState &state, const collision_detection_bullet::BulletDiscreteBVHManagerPtr &manager) const
Updates the poses of the objects in the manager according to given robot state.
void distanceSelf(const DistanceRequest &req, DistanceResult &res, const moveit::core::RobotState &state) const override
The distance to self-collision given the robot is at state state.
void updatedPaddingOrScaling(const std::vector< std::string > &links) override
Updates the collision objects saved in the manager to reflect a new padding or scaling of the robot l...
std::vector< std::string > active_
The active links where active refers to the group which can collide with everything.
void checkRobotCollisionHelperCCD(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state1, const moveit::core::RobotState &state2, const AllowedCollisionMatrix *acm) const
void checkRobotCollisionHelper(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm) const
void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const override
Check whether the robot model is in collision with the world. Any collisions between a robot link and...
void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const override
Check for robot self collision. Any collision between any pair of links is checked for,...
void checkSelfCollisionHelper(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm) const
Bundles the different checkSelfCollision functions into a single function.
void distanceRobot(const DistanceRequest &req, DistanceResult &res, const moveit::core::RobotState &state) const override
Compute the distance between a robot and the world.
void addLinkAsCollisionObject(const urdf::LinkSharedPtr &link)
Construts a bullet collision object out of a robot link.
collision_detection_bullet::BulletDiscreteBVHManagerPtr manager_
Handles self collision checks.
void updateManagedObject(const std::string &id)
Updates a managed collision object with its world representation.
void addAttachedOjects(const moveit::core::RobotState &state, std::vector< collision_detection_bullet::CollisionObjectWrapperPtr > &cows) const
All of the attached objects in the robot state are wrapped into bullet collision objects.
void addToManager(const World::Object *obj)
Adds a world object to the collision managers.
Provides the interface to the individual collision checking libraries.
Definition: collision_env.h:52
virtual void setWorld(const WorldPtr &world)
moveit::core::RobotModelConstPtr robot_model_
The kinematic model corresponding to this collision model.
const std::map< std::string, double > & getLinkScale() const
Get the link scaling as a map (from link names to scale value)
const std::map< std::string, double > & getLinkPadding() const
Get the link paddings as a map (from link names to padding value)
Represents an action that occurred on an object in the world. Several bits may be set indicating seve...
Definition: world.h:265
Object defining bodies that can be attached to robot links.
Definition: attached_body.h:58
const EigenSTL::vector_Isometry3d & getGlobalCollisionBodyTransforms() const
Get the global transforms (in world frame) for the collision bodies. The returned transforms are guar...
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
const Eigen::Isometry3d & getCollisionBodyTransform(const std::string &link_name, std::size_t index)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
Definition: robot_state.h:1379
void getAttachedBodies(std::vector< const AttachedBody * > &attached_bodies) const
Get all bodies attached to the model corresponding to this state.
const AttachedBody * getAttachedBody(const std::string &name) const
Get the attached body named name. Return nullptr if not found.
@ ROBOT_LINK
A link on the robot.
@ ROBOT_ATTACHED
A body attached to a robot link.
@ WORLD_OBJECT
A body in the environment.
Eigen::Isometry3d urdfPose2Eigen(const urdf::Pose &pose)
std::vector< T, Eigen::aligned_allocator< T > > AlignedVector
Definition: basic_types.h:37
@ USE_SHAPE_TYPE
Infer the type from the type specified in the shapes::Shape class.
@ CONVEX_HULL
Use the mesh in shapes::Shape but make it a convex hulls collision object (if not convex it will be c...
shapes::ShapePtr constructShape(const urdf::Geometry *geom)
Definition: world.h:49
Representation of a collision checking request.
bool distance
If true, compute proximity distance.
Representation of a collision checking result.
Representation of a distance-reporting request.
Result of a distance request.
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
EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::string id_
The id for this object.
Definition: world.h:87
std::vector< shapes::ShapeConstPtr > shapes_
All the shapes making up this object.
Definition: world.h:96