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