moveit2
The MoveIt Motion Planning Framework for ROS 2.
collision_common.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, 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, Jia Pan */
36 
38 #include <geometric_shapes/shapes.h>
40 #include <rclcpp/logger.hpp>
41 #include <rclcpp/logging.hpp>
42 
43 #if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0))
44 #include <fcl/geometry/bvh/BVH_model.h>
45 #include <fcl/geometry/octree/octree.h>
46 #else
47 #include <fcl/BVH/BVH_model.h>
48 #include <fcl/shape/geometric_shapes.h>
49 #include <fcl/octree.h>
50 #endif
51 
52 #include <memory>
53 #include <type_traits>
54 #include <mutex>
55 
56 namespace collision_detection
57 {
58 // Logger
59 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_collision_detection_fcl.collision_common");
60 
62 {
63  CollisionData* cdata = reinterpret_cast<CollisionData*>(data);
64  if (cdata->done_)
65  return true;
66  const CollisionGeometryData* cd1 = static_cast<const CollisionGeometryData*>(o1->collisionGeometry()->getUserData());
67  const CollisionGeometryData* cd2 = static_cast<const CollisionGeometryData*>(o2->collisionGeometry()->getUserData());
68 
69  // do not collision check geoms part of the same object / link / attached body
70  if (cd1->sameObject(*cd2))
71  return false;
72 
73  // If active components are specified
74  if (cdata->active_components_only_)
75  {
76  const moveit::core::LinkModel* l1 =
77  cd1->type == BodyTypes::ROBOT_LINK ?
78  cd1->ptr.link :
79  (cd1->type == BodyTypes::ROBOT_ATTACHED ? cd1->ptr.ab->getAttachedLink() : nullptr);
80  const moveit::core::LinkModel* l2 =
81  cd2->type == BodyTypes::ROBOT_LINK ?
82  cd2->ptr.link :
83  (cd2->type == BodyTypes::ROBOT_ATTACHED ? cd2->ptr.ab->getAttachedLink() : nullptr);
84 
85  // If neither of the involved components is active
86  if ((!l1 || cdata->active_components_only_->find(l1) == cdata->active_components_only_->end()) &&
87  (!l2 || cdata->active_components_only_->find(l2) == cdata->active_components_only_->end()))
88  return false;
89  }
90 
91  // use the collision matrix (if any) to avoid certain collision checks
92  DecideContactFn dcf;
93  bool always_allow_collision = false;
94  if (cdata->acm_)
95  {
97  bool found = cdata->acm_->getAllowedCollision(cd1->getID(), cd2->getID(), type);
98  if (found)
99  {
100  // if we have an entry in the collision matrix, we read it
102  {
103  always_allow_collision = true;
104  if (cdata->req_->verbose)
105  RCLCPP_DEBUG(LOGGER,
106  "Collision between '%s' (type '%s') and '%s' (type '%s') is always allowed. "
107  "No contacts are computed.",
108  cd1->getID().c_str(), cd1->getTypeString().c_str(), cd2->getID().c_str(),
109  cd2->getTypeString().c_str());
110  }
112  {
113  cdata->acm_->getAllowedCollision(cd1->getID(), cd2->getID(), dcf);
114  if (cdata->req_->verbose)
115  RCLCPP_DEBUG(LOGGER, "Collision between '%s' and '%s' is conditionally allowed", cd1->getID().c_str(),
116  cd2->getID().c_str());
117  }
118  }
119  }
120 
121  // check if a link is touching an attached object
123  {
124  const std::set<std::string>& tl = cd2->ptr.ab->getTouchLinks();
125  if (tl.find(cd1->getID()) != tl.end())
126  {
127  always_allow_collision = true;
128  if (cdata->req_->verbose)
129  RCLCPP_DEBUG(LOGGER, "Robot link '%s' is allowed to touch attached object '%s'. No contacts are computed.",
130  cd1->getID().c_str(), cd2->getID().c_str());
131  }
132  }
133  else if (cd2->type == BodyTypes::ROBOT_LINK && cd1->type == BodyTypes::ROBOT_ATTACHED)
134  {
135  const std::set<std::string>& tl = cd1->ptr.ab->getTouchLinks();
136  if (tl.find(cd2->getID()) != tl.end())
137  {
138  always_allow_collision = true;
139  if (cdata->req_->verbose)
140  RCLCPP_DEBUG(LOGGER, "Robot link '%s' is allowed to touch attached object '%s'. No contacts are computed.",
141  cd2->getID().c_str(), cd1->getID().c_str());
142  }
143  }
144 
145  // bodies attached to the same link should not collide
146  // If one of the attached objects lists the other in touch links set, then collisions are also allowed
148  {
149  if (cd1->ptr.ab->getAttachedLink() == cd2->ptr.ab->getAttachedLink())
150  {
151  always_allow_collision = true;
152  }
153  else
154  {
155  const std::set<std::string>& tl1 = cd1->ptr.ab->getTouchLinks();
156  const std::set<std::string>& tl2 = cd2->ptr.ab->getTouchLinks();
157  if (tl1.find(cd2->getID()) != tl1.end() || tl2.find(cd1->getID()) != tl2.end())
158  {
159  always_allow_collision = true;
160  }
161  }
162  if (always_allow_collision && cdata->req_->verbose)
163  {
164  RCLCPP_DEBUG(LOGGER, "Attached object '%s' is allowed to touch attached object '%s'. No contacts are computed.",
165  cd2->getID().c_str(), cd1->getID().c_str());
166  }
167  }
168 
169  // if collisions are always allowed, we are done
170  if (always_allow_collision)
171  return false;
172 
173  if (cdata->req_->verbose)
174  RCLCPP_DEBUG(LOGGER, "Actually checking collisions between %s and %s", cd1->getID().c_str(), cd2->getID().c_str());
175 
176  // see if we need to compute a contact
177  std::size_t want_contact_count = 0;
178  if (cdata->req_->contacts)
179  if (cdata->res_->contact_count < cdata->req_->max_contacts)
180  {
181  std::size_t have;
182  if (cd1->getID() < cd2->getID())
183  {
184  std::pair<std::string, std::string> cp(cd1->getID(), cd2->getID());
185  have = cdata->res_->contacts.find(cp) != cdata->res_->contacts.end() ? cdata->res_->contacts[cp].size() : 0;
186  }
187  else
188  {
189  std::pair<std::string, std::string> cp(cd2->getID(), cd1->getID());
190  have = cdata->res_->contacts.find(cp) != cdata->res_->contacts.end() ? cdata->res_->contacts[cp].size() : 0;
191  }
192  if (have < cdata->req_->max_contacts_per_pair)
193  want_contact_count =
194  std::min(cdata->req_->max_contacts_per_pair - have, cdata->req_->max_contacts - cdata->res_->contact_count);
195  }
196 
197  if (dcf)
198  {
199  // if we have a decider for allowed contacts, we need to look at all the contacts
200  bool enable_cost = cdata->req_->cost;
201  std::size_t num_max_cost_sources = cdata->req_->max_cost_sources;
202  bool enable_contact = true;
203  fcl::CollisionResultd col_result;
204  int num_contacts = fcl::collide(o1, o2,
205  fcl::CollisionRequestd(std::numeric_limits<size_t>::max(), enable_contact,
206  num_max_cost_sources, enable_cost),
207  col_result);
208  if (num_contacts > 0)
209  {
210  if (cdata->req_->verbose)
211  RCLCPP_INFO(LOGGER,
212  "Found %d contacts between '%s' and '%s'. "
213  "These contacts will be evaluated to check if they are accepted or not",
214  num_contacts, cd1->getID().c_str(), cd2->getID().c_str());
215  Contact c;
216  const std::pair<std::string, std::string>& pc = cd1->getID() < cd2->getID() ?
217  std::make_pair(cd1->getID(), cd2->getID()) :
218  std::make_pair(cd2->getID(), cd1->getID());
219  for (int i = 0; i < num_contacts; ++i)
220  {
221  fcl2contact(col_result.getContact(i), c);
222  // if the contact is not allowed, we have a collision
223  if (!dcf(c))
224  {
225  // store the contact, if it is needed
226  if (want_contact_count > 0)
227  {
228  --want_contact_count;
229  cdata->res_->contacts[pc].push_back(c);
230  cdata->res_->contact_count++;
231  if (cdata->req_->verbose)
232  RCLCPP_INFO(LOGGER, "Found unacceptable contact between '%s' and '%s'. Contact was stored.",
233  cd1->getID().c_str(), cd2->getID().c_str());
234  }
235  else if (cdata->req_->verbose)
236  RCLCPP_INFO(LOGGER,
237  "Found unacceptable contact between '%s' (type '%s') and '%s' "
238  "(type '%s'). Contact was stored.",
239  cd1->getID().c_str(), cd1->getTypeString().c_str(), cd2->getID().c_str(),
240  cd2->getTypeString().c_str());
241  cdata->res_->collision = true;
242  if (want_contact_count == 0)
243  break;
244  }
245  }
246  }
247 
248  if (enable_cost)
249  {
250  std::vector<fcl::CostSourced> cost_sources;
251  col_result.getCostSources(cost_sources);
252 
253  CostSource cs;
254  for (auto& cost_source : cost_sources)
255  {
256  fcl2costsource(cost_source, cs);
257  cdata->res_->cost_sources.insert(cs);
258  while (cdata->res_->cost_sources.size() > cdata->req_->max_cost_sources)
259  cdata->res_->cost_sources.erase(--cdata->res_->cost_sources.end());
260  }
261  }
262  }
263  else
264  {
265  if (want_contact_count > 0)
266  {
267  // otherwise, we need to compute more things
268  bool enable_cost = cdata->req_->cost;
269  std::size_t num_max_cost_sources = cdata->req_->max_cost_sources;
270  bool enable_contact = true;
271 
272  fcl::CollisionResultd col_result;
273  int num_contacts =
274  fcl::collide(o1, o2,
275  fcl::CollisionRequestd(want_contact_count, enable_contact, num_max_cost_sources, enable_cost),
276  col_result);
277  if (num_contacts > 0)
278  {
279  int num_contacts_initial = num_contacts;
280 
281  // make sure we don't get more contacts than we want
282  if (want_contact_count >= (std::size_t)num_contacts)
283  want_contact_count -= num_contacts;
284  else
285  {
286  num_contacts = want_contact_count;
287  want_contact_count = 0;
288  }
289 
290  if (cdata->req_->verbose)
291  RCLCPP_INFO(LOGGER,
292  "Found %d contacts between '%s' (type '%s') and '%s' (type '%s'), "
293  "which constitute a collision. %d contacts will be stored",
294  num_contacts_initial, cd1->getID().c_str(), cd1->getTypeString().c_str(), cd2->getID().c_str(),
295  cd2->getTypeString().c_str(), num_contacts);
296 
297  const std::pair<std::string, std::string>& pc = cd1->getID() < cd2->getID() ?
298  std::make_pair(cd1->getID(), cd2->getID()) :
299  std::make_pair(cd2->getID(), cd1->getID());
300  cdata->res_->collision = true;
301  for (int i = 0; i < num_contacts; ++i)
302  {
303  Contact c;
304  fcl2contact(col_result.getContact(i), c);
305  cdata->res_->contacts[pc].push_back(c);
306  cdata->res_->contact_count++;
307  }
308  }
309 
310  if (enable_cost)
311  {
312  std::vector<fcl::CostSourced> cost_sources;
313  col_result.getCostSources(cost_sources);
314 
315  CostSource cs;
316  for (auto& cost_source : cost_sources)
317  {
318  fcl2costsource(cost_source, cs);
319  cdata->res_->cost_sources.insert(cs);
320  while (cdata->res_->cost_sources.size() > cdata->req_->max_cost_sources)
321  cdata->res_->cost_sources.erase(--cdata->res_->cost_sources.end());
322  }
323  }
324  }
325  else
326  {
327  bool enable_cost = cdata->req_->cost;
328  std::size_t num_max_cost_sources = cdata->req_->max_cost_sources;
329  bool enable_contact = false;
330  fcl::CollisionResultd col_result;
331  int num_contacts = fcl::collide(
332  o1, o2, fcl::CollisionRequestd(1, enable_contact, num_max_cost_sources, enable_cost), col_result);
333  if (num_contacts > 0)
334  {
335  cdata->res_->collision = true;
336  if (cdata->req_->verbose)
337  RCLCPP_INFO(LOGGER,
338  "Found a contact between '%s' (type '%s') and '%s' (type '%s'), "
339  "which constitutes a collision. "
340  "Contact information is not stored.",
341  cd1->getID().c_str(), cd1->getTypeString().c_str(), cd2->getID().c_str(),
342  cd2->getTypeString().c_str());
343  }
344 
345  if (enable_cost)
346  {
347  std::vector<fcl::CostSourced> cost_sources;
348  col_result.getCostSources(cost_sources);
349 
350  CostSource cs;
351  for (auto& cost_source : cost_sources)
352  {
353  fcl2costsource(cost_source, cs);
354  cdata->res_->cost_sources.insert(cs);
355  while (cdata->res_->cost_sources.size() > cdata->req_->max_cost_sources)
356  cdata->res_->cost_sources.erase(--cdata->res_->cost_sources.end());
357  }
358  }
359  }
360  }
361 
362  if (cdata->res_->collision)
363  if (!cdata->req_->contacts || cdata->res_->contact_count >= cdata->req_->max_contacts)
364  {
365  if (!cdata->req_->cost)
366  cdata->done_ = true;
367  if (cdata->req_->verbose)
368  RCLCPP_INFO(LOGGER,
369  "Collision checking is considered complete (collision was found and %u contacts are stored)",
370  (unsigned int)cdata->res_->contact_count);
371  }
372 
373  if (!cdata->done_ && cdata->req_->is_done)
374  {
375  cdata->done_ = cdata->req_->is_done(*cdata->res_);
376  if (cdata->done_ && cdata->req_->verbose)
377  RCLCPP_INFO(LOGGER,
378  "Collision checking is considered complete due to external callback. "
379  "%s was found. %u contacts are stored.",
380  cdata->res_->collision ? "Collision" : "No collision", (unsigned int)cdata->res_->contact_count);
381  }
382 
383  return cdata->done_;
384 }
385 
390 {
391  using ShapeKey = shapes::ShapeConstWeakPtr;
392  using ShapeMap = std::map<ShapeKey, FCLGeometryConstPtr, std::owner_less<ShapeKey>>;
393 
395  {
396  }
397 
398  void bumpUseCount(bool force = false)
399  {
400  clean_count_++;
401 
402  // clean-up for cache (we don't want to keep infinitely large number of weak ptrs stored)
403  if (clean_count_ > MAX_CLEAN_COUNT || force)
404  {
405  clean_count_ = 0;
406  for (auto it = map_.begin(); it != map_.end();)
407  {
408  auto nit = it;
409  ++nit;
410  if (it->first.expired())
411  map_.erase(it);
412  it = nit;
413  }
414  // RCLCPP_DEBUG(LOGGER, "Cleaning up cache for FCL objects that correspond to static
415  // shapes. Cache size
416  // reduced from %u
417  // to %u", from, (unsigned int)map_.size());
418  }
419  }
420 
421  static const unsigned int MAX_CLEAN_COUNT = 100; // every this many uses of the cache, a cleaning operation is
422  // executed (this is only removal of expired entries)
425 
427  unsigned int clean_count_;
428 };
429 
430 bool distanceCallback(fcl::CollisionObjectd* o1, fcl::CollisionObjectd* o2, void* data, double& /*min_dist*/)
431 {
432  DistanceData* cdata = reinterpret_cast<DistanceData*>(data);
433 
434  const CollisionGeometryData* cd1 = static_cast<const CollisionGeometryData*>(o1->collisionGeometry()->getUserData());
435  const CollisionGeometryData* cd2 = static_cast<const CollisionGeometryData*>(o2->collisionGeometry()->getUserData());
436 
437  // do not distance check for geoms part of the same object / link / attached body
438  if (cd1->sameObject(*cd2))
439  return false;
440 
441  // If active components are specified
442  if (cdata->req->active_components_only)
443  {
444  const moveit::core::LinkModel* l1 =
445  cd1->type == BodyTypes::ROBOT_LINK ?
446  cd1->ptr.link :
447  (cd1->type == BodyTypes::ROBOT_ATTACHED ? cd1->ptr.ab->getAttachedLink() : nullptr);
448  const moveit::core::LinkModel* l2 =
449  cd2->type == BodyTypes::ROBOT_LINK ?
450  cd2->ptr.link :
451  (cd2->type == BodyTypes::ROBOT_ATTACHED ? cd2->ptr.ab->getAttachedLink() : nullptr);
452 
453  // If neither of the involved components is active
454  if ((!l1 || cdata->req->active_components_only->find(l1) == cdata->req->active_components_only->end()) &&
455  (!l2 || cdata->req->active_components_only->find(l2) == cdata->req->active_components_only->end()))
456  {
457  return false;
458  }
459  }
460 
461  // use the collision matrix (if any) to avoid certain distance checks
462  bool always_allow_collision = false;
463  if (cdata->req->acm)
464  {
466  bool found = cdata->req->acm->getAllowedCollision(cd1->getID(), cd2->getID(), type);
467  if (found)
468  {
469  // if we have an entry in the collision matrix, we read it
471  {
472  always_allow_collision = true;
473  if (cdata->req->verbose)
474  RCLCPP_DEBUG(LOGGER, "Collision between '%s' and '%s' is always allowed. No distances are computed.",
475  cd1->getID().c_str(), cd2->getID().c_str());
476  }
477  }
478  }
479 
480  // check if a link is touching an attached object
482  {
483  const std::set<std::string>& tl = cd2->ptr.ab->getTouchLinks();
484  if (tl.find(cd1->getID()) != tl.end())
485  {
486  always_allow_collision = true;
487  if (cdata->req->verbose)
488  RCLCPP_DEBUG(LOGGER, "Robot link '%s' is allowed to touch attached object '%s'. No distances are computed.",
489  cd1->getID().c_str(), cd2->getID().c_str());
490  }
491  }
492  else if (cd2->type == BodyTypes::ROBOT_LINK && cd1->type == BodyTypes::ROBOT_ATTACHED)
493  {
494  const std::set<std::string>& tl = cd1->ptr.ab->getTouchLinks();
495  if (tl.find(cd2->getID()) != tl.end())
496  {
497  always_allow_collision = true;
498  if (cdata->req->verbose)
499  RCLCPP_DEBUG(LOGGER, "Robot link '%s' is allowed to touch attached object '%s'. No distances are computed.",
500  cd2->getID().c_str(), cd1->getID().c_str());
501  }
502  }
503 
504  if (always_allow_collision)
505  {
506  return false;
507  }
508  if (cdata->req->verbose)
509  RCLCPP_DEBUG(LOGGER, "Actually checking collisions between %s and %s", cd1->getID().c_str(), cd2->getID().c_str());
510 
511  double dist_threshold = cdata->req->distance_threshold;
512 
513  const std::pair<const std::string&, const std::string&> pc =
514  cd1->getID() < cd2->getID() ? std::make_pair(std::cref(cd1->getID()), std::cref(cd2->getID())) :
515  std::make_pair(std::cref(cd2->getID()), std::cref(cd1->getID()));
516 
517  DistanceMap::iterator it = cdata->res->distances.find(pc);
518 
519  // GLOBAL search: for efficiency, distance_threshold starts at the smallest distance between any pairs found so far
520  if (cdata->req->type == DistanceRequestType::GLOBAL)
521  {
522  dist_threshold = cdata->res->minimum_distance.distance;
523  }
524  // Check if a distance between this pair has been found yet. Decrease threshold_distance if so, to narrow the search
525  else if (it != cdata->res->distances.end())
526  {
527  if (cdata->req->type == DistanceRequestType::LIMITED)
528  {
529  // If at the limit for a given pair just return
530  if (it->second.size() >= cdata->req->max_contacts_per_body)
531  {
532  return cdata->done;
533  }
534  }
535  else if (cdata->req->type == DistanceRequestType::SINGLE)
536  {
537  dist_threshold = it->second[0].distance;
538  }
539  }
540 
541  fcl::DistanceResultd fcl_result;
542  fcl_result.min_distance = dist_threshold;
543  // fcl::distance segfaults when given an octree with a null root pointer (using FCL 0.6.1)
544  if ((o1->getObjectType() == fcl::OT_OCTREE &&
545  !std::static_pointer_cast<const fcl::OcTreed>(o1->collisionGeometry())->getRoot()) ||
546  (o2->getObjectType() == fcl::OT_OCTREE &&
547  !std::static_pointer_cast<const fcl::OcTreed>(o2->collisionGeometry())->getRoot()))
548  {
549  return false;
550  }
551  double distance = fcl::distance(o1, o2, fcl::DistanceRequestd(cdata->req->enable_nearest_points), fcl_result);
552 
553  // Check if either object is already in the map. If not add it or if present
554  // check to see if the new distance is closer. If closer remove the existing
555  // one and add the new distance information.
556  if (distance < dist_threshold)
557  {
558  // thread_local storage makes this variable persistent. We do not clear it at every iteration because all members
559  // get overwritten.
560  thread_local DistanceResultsData dist_result;
561  dist_result.distance = fcl_result.min_distance;
562 
563  // Careful here: Get the collision geometry data again, since FCL might
564  // swap o1 and o2 in the result.
565  const CollisionGeometryData* res_cd1 = static_cast<const CollisionGeometryData*>(fcl_result.o1->getUserData());
566  const CollisionGeometryData* res_cd2 = static_cast<const CollisionGeometryData*>(fcl_result.o2->getUserData());
567 
568 #if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0))
569  dist_result.nearest_points[0] = fcl_result.nearest_points[0];
570  dist_result.nearest_points[1] = fcl_result.nearest_points[1];
571 #else
572  dist_result.nearest_points[0] = Eigen::Map<const Eigen::Vector3d>(fcl_result.nearest_points[0].data.vs);
573  dist_result.nearest_points[1] = Eigen::Map<const Eigen::Vector3d>(fcl_result.nearest_points[1].data.vs);
574 #endif
575  dist_result.link_names[0] = res_cd1->getID();
576  dist_result.link_names[1] = res_cd2->getID();
577  dist_result.body_types[0] = res_cd1->type;
578  dist_result.body_types[1] = res_cd2->type;
579  if (cdata->req->enable_nearest_points)
580  {
581  dist_result.normal = (dist_result.nearest_points[1] - dist_result.nearest_points[0]).normalized();
582  }
583 
584  if (distance <= 0 && cdata->req->enable_signed_distance)
585  {
586  dist_result.nearest_points[0].setZero();
587  dist_result.nearest_points[1].setZero();
588  dist_result.normal.setZero();
589 
590  fcl::CollisionRequestd coll_req;
591  thread_local fcl::CollisionResultd coll_res;
592  coll_res.clear(); // thread_local storage makes the variable persistent. Ensure that it is cleared!
593  coll_req.enable_contact = true;
594  coll_req.num_max_contacts = 200;
595  std::size_t contacts = fcl::collide(o1, o2, coll_req, coll_res);
596  if (contacts > 0)
597  {
598  double max_dist = 0;
599  int max_index = 0;
600  for (std::size_t i = 0; i < contacts; ++i)
601  {
602  const fcl::Contactd& contact = coll_res.getContact(i);
603  if (contact.penetration_depth > max_dist)
604  {
605  max_dist = contact.penetration_depth;
606  max_index = i;
607  }
608  }
609 
610  const fcl::Contactd& contact = coll_res.getContact(max_index);
611  dist_result.distance = -contact.penetration_depth;
612 
613 #if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0))
614  dist_result.nearest_points[0] = contact.pos;
615  dist_result.nearest_points[1] = contact.pos;
616 #else
617  dist_result.nearest_points[0] = Eigen::Map<const Eigen::Vector3d>(contact.pos.data.vs);
618  dist_result.nearest_points[1] = Eigen::Map<const Eigen::Vector3d>(contact.pos.data.vs);
619 #endif
620 
621  if (cdata->req->enable_nearest_points)
622  {
623 #if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0))
624  Eigen::Vector3d normal(contact.normal);
625 #else
626  Eigen::Vector3d normal(contact.normal.data.vs);
627 #endif
628 
629  // Check order of o1/o2 again, we might need to flip the normal
630  if (contact.o1 == o1->collisionGeometry().get())
631  dist_result.normal = normal;
632  else
633  dist_result.normal = -normal;
634  }
635  }
636  }
637 
638  if (dist_result.distance < cdata->res->minimum_distance.distance)
639  {
640  cdata->res->minimum_distance = dist_result;
641  }
642 
643  if (dist_result.distance <= 0)
644  {
645  cdata->res->collision = true;
646  }
647 
648  if (cdata->req->type != DistanceRequestType::GLOBAL)
649  {
650  if (it == cdata->res->distances.end())
651  {
652  std::vector<DistanceResultsData> data;
653  data.reserve(cdata->req->type == DistanceRequestType::SINGLE ? 1 : cdata->req->max_contacts_per_body);
654  data.push_back(dist_result);
655  cdata->res->distances.insert(std::make_pair(pc, data));
656  }
657  else
658  {
659  if (cdata->req->type == DistanceRequestType::ALL)
660  {
661  it->second.push_back(dist_result);
662  }
663  else if (cdata->req->type == DistanceRequestType::SINGLE)
664  {
665  if (dist_result.distance < it->second[0].distance)
666  it->second[0] = dist_result;
667  }
668  else if (cdata->req->type == DistanceRequestType::LIMITED)
669  {
670  assert(it->second.size() < cdata->req->max_contacts_per_body);
671  it->second.push_back(dist_result);
672  }
673  }
674  }
675 
676  if (!cdata->req->enable_signed_distance && cdata->res->collision)
677  {
678  cdata->done = true;
679  }
680  }
681 
682  return cdata->done;
683 }
684 
685 /* Templated function to get a different cache for each of the template arguments combinations.
686  *
687  * The returned cache is a quasi-singleton for each thread as it is created \e thread_local. */
688 template <typename BV, typename T>
690 {
691  /* The cache is created thread_local, that is each thread calling
692  * this quasi-singleton function will get its own instance. Once
693  * the thread joins/exits, the cache gets deleted.
694  * Reasoning is that multi-threaded planners (eg OMPL) or user-code
695  * will often need to do collision checks with the same object
696  * simultaneously (especially true for attached objects). Having only
697  * one global cache leads to many cache misses. Also as the cache can
698  * only be accessed by one thread we don't need any locking.
699  */
700  static thread_local FCLShapeCache cache;
701  return cache;
702 }
703 
709 template <typename BV, typename T>
710 FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr& shape, const T* data, int shape_index)
711 {
712  using ShapeKey = shapes::ShapeConstWeakPtr;
713  using ShapeMap = std::map<ShapeKey, FCLGeometryConstPtr, std::owner_less<ShapeKey>>;
714 
715  FCLShapeCache& cache = GetShapeCache<BV, T>();
716 
717  shapes::ShapeConstWeakPtr wptr(shape);
718  {
719  ShapeMap::const_iterator cache_it = cache.map_.find(wptr);
720  if (cache_it != cache.map_.end())
721  {
722  if (cache_it->second->collision_geometry_data_->ptr.raw == data)
723  {
724  // RCLCPP_DEBUG(LOGGER, "Collision data structures for object %s retrieved from
725  // cache.",
726  // cache_it->second->collision_geometry_data_->getID().c_str());
727  return cache_it->second;
728  }
729  else if (cache_it->second.unique())
730  {
731  const_cast<FCLGeometry*>(cache_it->second.get())->updateCollisionGeometryData(data, shape_index, false);
732  // RCLCPP_DEBUG(LOGGER, "Collision data structures for object %s retrieved from
733  // cache after updating
734  // the source
735  // object.", cache_it->second->collision_geometry_data_->getID().c_str());
736  return cache_it->second;
737  }
738  }
739  }
740 
741  // attached objects could have previously been World::Object; we try to move them
742  // from their old cache to the new one, if possible. the code is not pretty, but should help
743  // when we attach/detach objects that are in the world
744  if (std::is_same<T, moveit::core::AttachedBody>::value)
745  {
746  // get the cache that corresponds to objects; maybe this attached object used to be a world object
747  FCLShapeCache& othercache = GetShapeCache<BV, World::Object>();
748 
749  // attached bodies could be just moved from the environment.
750  auto cache_it = othercache.map_.find(wptr);
751  if (cache_it != othercache.map_.end())
752  {
753  if (cache_it->second.unique())
754  {
755  // remove from old cache
756  FCLGeometryConstPtr obj_cache = cache_it->second;
757  othercache.map_.erase(cache_it);
758  // update the CollisionGeometryData; nobody has a pointer to this, so we can safely modify it
759  const_cast<FCLGeometry*>(obj_cache.get())->updateCollisionGeometryData(data, shape_index, true);
760 
761  // RCLCPP_DEBUG(LOGGER, "Collision data structures for attached body %s retrieved
762  // from the cache for
763  // world objects.",
764  // obj_cache->collision_geometry_data_->getID().c_str());
765 
766  // add to the new cache
767  cache.map_[wptr] = obj_cache;
768  cache.bumpUseCount();
769  return obj_cache;
770  }
771  }
772  }
773  else
774  // world objects could have previously been attached objects; we try to move them
775  // from their old cache to the new one, if possible. the code is not pretty, but should help
776  // when we attach/detach objects that are in the world
777  if (std::is_same<T, World::Object>::value)
778  {
779  // get the cache that corresponds to objects; maybe this attached object used to be a world object
780  FCLShapeCache& othercache = GetShapeCache<BV, moveit::core::AttachedBody>();
781 
782  // attached bodies could be just moved from the environment.
783  auto cache_it = othercache.map_.find(wptr);
784  if (cache_it != othercache.map_.end())
785  {
786  if (cache_it->second.unique())
787  {
788  // remove from old cache
789  FCLGeometryConstPtr obj_cache = cache_it->second;
790  othercache.map_.erase(cache_it);
791 
792  // update the CollisionGeometryData; nobody has a pointer to this, so we can safely modify it
793  const_cast<FCLGeometry*>(obj_cache.get())->updateCollisionGeometryData(data, shape_index, true);
794 
795  // RCLCPP_DEBUG(LOGGER, "Collision data structures for world object %s retrieved
796  // from the cache for
797  // attached
798  // bodies.",
799  // obj_cache->collision_geometry_data_->getID().c_str());
800 
801  // add to the new cache
802  cache.map_[wptr] = obj_cache;
803  cache.bumpUseCount();
804  return obj_cache;
805  }
806  }
807  }
808 
809  fcl::CollisionGeometryd* cg_g = nullptr;
810  // handle cases individually
811  switch (shape->type)
812  {
813  case shapes::PLANE:
814  {
815  const shapes::Plane* p = static_cast<const shapes::Plane*>(shape.get());
816  cg_g = new fcl::Planed(p->a, p->b, p->c, p->d);
817  }
818  break;
819  case shapes::SPHERE:
820  {
821  const shapes::Sphere* s = static_cast<const shapes::Sphere*>(shape.get());
822  cg_g = new fcl::Sphered(s->radius);
823  }
824  break;
825  case shapes::BOX:
826  {
827  const shapes::Box* s = static_cast<const shapes::Box*>(shape.get());
828  const double* size = s->size;
829  cg_g = new fcl::Boxd(size[0], size[1], size[2]);
830  }
831  break;
832  case shapes::CYLINDER:
833  {
834  const shapes::Cylinder* s = static_cast<const shapes::Cylinder*>(shape.get());
835  cg_g = new fcl::Cylinderd(s->radius, s->length);
836  }
837  break;
838  case shapes::CONE:
839  {
840  const shapes::Cone* s = static_cast<const shapes::Cone*>(shape.get());
841  cg_g = new fcl::Coned(s->radius, s->length);
842  }
843  break;
844  case shapes::MESH:
845  {
846  auto g = new fcl::BVHModel<BV>();
847  const shapes::Mesh* mesh = static_cast<const shapes::Mesh*>(shape.get());
848  if (mesh->vertex_count > 0 && mesh->triangle_count > 0)
849  {
850  std::vector<fcl::Triangle> tri_indices(mesh->triangle_count);
851  for (unsigned int i = 0; i < mesh->triangle_count; ++i)
852  tri_indices[i] =
853  fcl::Triangle(mesh->triangles[3 * i], mesh->triangles[3 * i + 1], mesh->triangles[3 * i + 2]);
854 
855  std::vector<fcl::Vector3d> points(mesh->vertex_count);
856  for (unsigned int i = 0; i < mesh->vertex_count; ++i)
857  points[i] = fcl::Vector3d(mesh->vertices[3 * i], mesh->vertices[3 * i + 1], mesh->vertices[3 * i + 2]);
858 
859  g->beginModel();
860  g->addSubModel(points, tri_indices);
861  g->endModel();
862  }
863  cg_g = g;
864  }
865  break;
866  case shapes::OCTREE:
867  {
868  const shapes::OcTree* g = static_cast<const shapes::OcTree*>(shape.get());
869  cg_g = new fcl::OcTreed(g->octree);
870  }
871  break;
872  default:
873  RCLCPP_ERROR(LOGGER, "This shape type (%d) is not supported using FCL yet", static_cast<int>(shape->type));
874  cg_g = nullptr;
875  }
876 
877  if (cg_g)
878  {
879  cg_g->computeLocalAABB();
880  FCLGeometryConstPtr res = std::make_shared<const FCLGeometry>(cg_g, data, shape_index);
881  cache.map_[wptr] = res;
882  cache.bumpUseCount();
883  return res;
884  }
885  return FCLGeometryConstPtr();
886 }
887 
888 FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr& shape, const moveit::core::LinkModel* link,
889  int shape_index)
890 {
891  return createCollisionGeometry<fcl::OBBRSSd, moveit::core::LinkModel>(shape, link, shape_index);
892 }
893 
894 FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr& shape, const moveit::core::AttachedBody* ab,
895  int shape_index)
896 {
897  return createCollisionGeometry<fcl::OBBRSSd, moveit::core::AttachedBody>(shape, ab, shape_index);
898 }
899 
900 FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr& shape, const World::Object* obj)
901 {
902  return createCollisionGeometry<fcl::OBBRSSd, World::Object>(shape, obj, 0);
903 }
904 
907 template <typename BV, typename T>
908 FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr& shape, double scale, double padding,
909  const T* data, int shape_index)
910 {
911  if (fabs(scale - 1.0) <= std::numeric_limits<double>::epsilon() &&
912  fabs(padding) <= std::numeric_limits<double>::epsilon())
913  return createCollisionGeometry<BV, T>(shape, data, shape_index);
914  else
915  {
916  shapes::ShapePtr scaled_shape(shape->clone());
917  scaled_shape->scaleAndPadd(scale, padding);
918  return createCollisionGeometry<BV, T>(scaled_shape, data, shape_index);
919  }
920 }
921 
922 FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr& shape, double scale, double padding,
923  const moveit::core::LinkModel* link, int shape_index)
924 {
925  return createCollisionGeometry<fcl::OBBRSSd, moveit::core::LinkModel>(shape, scale, padding, link, shape_index);
926 }
927 
928 FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr& shape, double scale, double padding,
929  const moveit::core::AttachedBody* ab, int shape_index)
930 {
931  return createCollisionGeometry<fcl::OBBRSSd, moveit::core::AttachedBody>(shape, scale, padding, ab, shape_index);
932 }
933 
934 FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr& shape, double scale, double padding,
935  const World::Object* obj)
936 {
937  return createCollisionGeometry<fcl::OBBRSSd, World::Object>(shape, scale, padding, obj, 0);
938 }
939 
941 {
942  FCLShapeCache& cache1 = GetShapeCache<fcl::OBBRSSd, World::Object>();
943  {
944  cache1.bumpUseCount(true);
945  }
946  FCLShapeCache& cache2 = GetShapeCache<fcl::OBBRSSd, moveit::core::AttachedBody>();
947  {
948  cache2.bumpUseCount(true);
949  }
950 }
951 
952 void CollisionData::enableGroup(const moveit::core::RobotModelConstPtr& robot_model)
953 {
954  if (robot_model->hasJointModelGroup(req_->group_name))
955  active_components_only_ = &robot_model->getJointModelGroup(req_->group_name)->getUpdatedLinkModelsSet();
956  else
957  active_components_only_ = nullptr;
958 }
959 
961 {
962  std::vector<fcl::CollisionObjectd*> collision_objects(collision_objects_.size());
963  for (std::size_t i = 0; i < collision_objects_.size(); ++i)
964  collision_objects[i] = collision_objects_[i].get();
965  if (!collision_objects.empty())
966  manager->registerObjects(collision_objects);
967 }
968 
970 {
971  for (auto& collision_object : collision_objects_)
972  manager->unregisterObject(collision_object.get());
973 }
974 
976 {
977  collision_objects_.clear();
978  collision_geometry_.clear();
979 }
980 } // namespace collision_detection
bool getAllowedCollision(const std::string &name1, const std::string &name2, DecideContactFn &fn) const
Get the allowed collision predicate between two elements. Return true if a predicate for entry is inc...
Object defining bodies that can be attached to robot links.
Definition: attached_body.h:58
const std::set< std::string > & getTouchLinks() const
Get the links that the attached body is allowed to touch.
const LinkModel * getAttachedLink() const
Get the model of the link this body is attached to.
Definition: attached_body.h:98
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition: link_model.h:72
@ CONDITIONAL
The collision is allowed depending on a predicate evaluated on the produced contact....
@ ALWAYS
Collisions between a particular pair of bodies does not imply that the robot configuration is in coll...
@ ROBOT_LINK
A link on the robot.
@ ROBOT_ATTACHED
A body attached to a robot link.
@ ALL
Find all the contacts for a given pair.
@ LIMITED
Find a limited(max_contacts_per_body) set of contacts for a given pair.
@ SINGLE
Find the global minimum for each pair.
void fcl2contact(const fcl::Contactd &fc, Contact &c)
Transforms an FCL contact into a MoveIt contact point.
FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr &shape, const moveit::core::LinkModel *link, int shape_index)
Create new FCLGeometry object out of robot link model.
void cleanCollisionGeometryCache()
Increases the counter of the caches which can trigger the cleaning of expired entries from them.
bool collisionCallback(fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, void *data)
Callback function used by the FCLManager used for each pair of collision objects to calculate object ...
FCLShapeCache & GetShapeCache()
std::function< bool(collision_detection::Contact &)> DecideContactFn
Signature of predicate that decides whether a contact is allowed or not (when AllowedCollision::Type ...
void fcl2costsource(const fcl::CostSourced &fcs, CostSource &cs)
Transforms the FCL internal representation to the MoveIt CostSource data structure.
bool distanceCallback(fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, void *data, double &min_dist)
Callback function used by the FCLManager used for each pair of collision objects to calculate collisi...
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
fcl::CollisionObject CollisionObjectd
Definition: fcl_compat.h:50
fcl::DistanceResult DistanceResultd
Definition: fcl_compat.h:66
fcl::BroadPhaseCollisionManager BroadPhaseCollisionManagerd
Definition: fcl_compat.h:52
fcl::Sphere Sphered
Definition: fcl_compat.h:70
fcl::DistanceRequest DistanceRequestd
Definition: fcl_compat.h:64
fcl::OcTree OcTreed
Definition: fcl_compat.h:93
fcl::Box Boxd
Definition: fcl_compat.h:72
fcl::CollisionGeometry CollisionGeometryd
Definition: fcl_compat.h:48
fcl::Contact Contactd
Definition: fcl_compat.h:56
fcl::CollisionResult CollisionResultd
Definition: fcl_compat.h:62
fcl::Cylinder Cylinderd
Definition: fcl_compat.h:74
fcl::CollisionRequest CollisionRequestd
Definition: fcl_compat.h:60
fcl::Plane Planed
Definition: fcl_compat.h:68
fcl::Cone Coned
Definition: fcl_compat.h:76
p
Definition: pick.py:62
double distance(const urdf::Pose &transform)
Definition: pr2_arm_ik.h:55
Data structure which is passed to the collision callback function of the collision manager.
const std::set< const moveit::core::LinkModel * > * active_components_only_
If the collision request includes a group name, this set contains the pointers to the link models tha...
const AllowedCollisionMatrix * acm_
The user-specified collision matrix (may be nullptr).
void enableGroup(const moveit::core::RobotModelConstPtr &robot_model)
Compute active_components_only_ based on the joint group specified in req_.
bool done_
Flag indicating whether collision checking is complete.
CollisionResult * res_
The user-specified response location.
const CollisionRequest * req_
The collision request passed by the user.
Wrapper around world, link and attached objects' geometry data.
const moveit::core::LinkModel * link
bool sameObject(const CollisionGeometryData &other) const
Check if two CollisionGeometryData objects point to the same source object.
const std::string & getID() const
Returns the name which is saved in the member pointed to in ptr.
std::string getTypeString() const
Returns a string of the corresponding type.
const moveit::core::AttachedBody * ab
union collision_detection::CollisionGeometryData::@0 ptr
Points to the type of body which contains the geometry.
BodyType type
Indicates the body type of the object.
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot)
bool verbose
Flag indicating whether information about detected collisions should be reported.
std::size_t max_cost_sources
When costs are computed, this value defines how many of the top cost sources should be returned.
bool contacts
If true, compute contacts. Otherwise only a binary collision yes/no is reported.
bool cost
If true, a collision cost is computed.
std::size_t max_contacts
Overall maximum number of contacts to compute.
std::function< bool(const CollisionResult &)> is_done
Function call that decides whether collision detection should stop.
std::size_t max_contacts_per_pair
Maximum number of contacts to compute per pair of bodies (multiple bodies may be in contact at differ...
std::set< CostSource > cost_sources
These are the individual cost sources when costs are computed.
bool collision
True if collision was found, false otherwise.
std::size_t contact_count
Number of contacts returned.
Definition of a contact point.
When collision costs are computed, this structure contains information about the partial cost incurre...
Data structure which is passed to the distance callback function of the collision manager.
DistanceResult * res
Distance query results information.
const DistanceRequest * req
Distance query request information.
bool done
Indicates if distance query is finished.
const std::set< const moveit::core::LinkModel * > * active_components_only
The set of active components to check.
bool verbose
Log debug information.
std::size_t max_contacts_per_body
Maximum number of contacts to store for bodies (multiple bodies may be within distance threshold)
bool enable_signed_distance
Indicate if a signed distance should be calculated in a collision.
const AllowedCollisionMatrix * acm
The allowed collision matrix used to filter checks.
bool enable_nearest_points
Indicate if nearest point information should be calculated.
DistanceMap distances
A map of distance data for each link in the req.active_components_only.
bool collision
Indicates if two objects were in collision.
DistanceResultsData minimum_distance
ResultsData for the two objects with the minimum distance.
Generic representation of the distance information for a pair of objects.
double distance
The distance between two objects. If two objects are in collision, distance <= 0.
Bundles the CollisionGeometryData and FCL collision geometry representation into a single class.
std::vector< FCLCollisionObjectPtr > collision_objects_
void unregisterFrom(fcl::BroadPhaseCollisionManagerd *manager)
std::vector< FCLGeometryConstPtr > collision_geometry_
Geometry data corresponding to collision_objects_.
void registerTo(fcl::BroadPhaseCollisionManagerd *manager)
Cache for an arbitrary type of shape. It is assigned during the execution of createCollisionGeometry(...
ShapeMap map_
Map of weak pointers to the FCLGeometry.
static const unsigned int MAX_CLEAN_COUNT
shapes::ShapeConstWeakPtr ShapeKey
unsigned int clean_count_
Counts cache usage and triggers clearing of cache when \m MAX_CLEAN_COUNT is exceeded.
std::map< ShapeKey, FCLGeometryConstPtr, std::owner_less< ShapeKey > > ShapeMap
A representation of an object.
Definition: world.h:79