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