moveit2
The MoveIt Motion Planning Framework for ROS 2.
compute_default_collisions.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, 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: Dave Coleman */
36 
39 #include <boost/math/special_functions/binomial.hpp> // for statistics at end
40 #include <boost/thread.hpp>
41 #include <boost/assign.hpp>
42 #include <unordered_map>
43 
44 namespace moveit_setup
45 {
46 namespace srdf_setup
47 {
48 // ******************************************************************************************
49 // Custom Types, Enums and Structs
50 // ******************************************************************************************
51 
52 // Mapping of reasons for disabling a link pair to strings
53 const std::unordered_map<DisabledReason, std::string> REASONS_TO_STRING = boost::assign::map_list_of(NEVER, "Never")(
54  DEFAULT, "Default")(ADJACENT, "Adjacent")(ALWAYS, "Always")(USER, "User")(NOT_DISABLED, "Not Disabled");
55 
56 const std::unordered_map<std::string, DisabledReason> REASONS_FROM_STRING = boost::assign::map_list_of("Never", NEVER)(
57  "Default", DEFAULT)("Adjacent", ADJACENT)("Always", ALWAYS)("User", USER)("Not Disabled", NOT_DISABLED);
58 
59 // Used for logging
60 static const rclcpp::Logger LOGGER = rclcpp::get_logger("collision_updater");
61 
62 // Unique set of pairs of links in string-based form
63 typedef std::set<std::pair<std::string, std::string> > StringPairSet;
64 
65 // Struct for passing parameters to threads, for cleaner code
67 {
69  int thread_id, int num_trials, StringPairSet* links_seen_colliding, std::mutex* lock,
70  unsigned int* progress)
71  : scene_(scene)
72  , req_(req)
73  , thread_id_(thread_id)
74  , num_trials_(num_trials)
75  , links_seen_colliding_(links_seen_colliding)
76  , lock_(lock)
77  , progress_(progress)
78  {
79  }
83  unsigned int num_trials_;
85  std::mutex* lock_;
86  unsigned int* progress_; // only to be updated by thread 0
87 };
88 
89 // LinkGraph defines a Link's model and a set of unique links it connects
90 typedef std::map<const moveit::core::LinkModel*, std::set<const moveit::core::LinkModel*> > LinkGraph;
91 
92 // ******************************************************************************************
93 // Static Prototypes
94 // ******************************************************************************************
95 
104 static bool setLinkPair(const std::string& linkA, const std::string& linkB, const DisabledReason reason,
105  LinkPairMap& link_pairs);
106 
112 static void computeConnectionGraph(const moveit::core::LinkModel* link, LinkGraph& link_graph);
113 
119 static void computeConnectionGraphRec(const moveit::core::LinkModel* link, LinkGraph& link_graph);
120 
128 static unsigned int disableAdjacentLinks(planning_scene::PlanningScene& scene, LinkGraph& link_graph,
129  LinkPairMap& link_pairs);
130 
138 static unsigned int disableDefaultCollisions(planning_scene::PlanningScene& scene, LinkPairMap& link_pairs,
140 
151 static unsigned int disableAlwaysInCollision(planning_scene::PlanningScene& scene, LinkPairMap& link_pairs,
153  StringPairSet& links_seen_colliding, double min_collision_faction = 0.95);
154 
163 static unsigned int disableNeverInCollision(const unsigned int num_trials, planning_scene::PlanningScene& scene,
164  LinkPairMap& link_pairs, const collision_detection::CollisionRequest& req,
165  StringPairSet& links_seen_colliding, unsigned int* progress);
166 
171 static void disableNeverInCollisionThread(ThreadComputation tc);
172 
173 // ******************************************************************************************
174 // Generates an adjacency list of links that are always and never in collision, to speed up collision detection
175 // ******************************************************************************************
176 LinkPairMap computeDefaultCollisions(const planning_scene::PlanningSceneConstPtr& parent_scene, unsigned int* progress,
177  const bool include_never_colliding, const unsigned int num_trials,
178  const double min_collision_fraction, const bool verbose)
179 {
180  // Create new instance of planning scene using pointer
181  planning_scene::PlanningScenePtr scene = parent_scene->diff();
182 
183  // Map of disabled collisions that contains a link as a key and an ordered list of links that are connected.
184  LinkPairMap link_pairs;
185 
186  // Track unique edges that have been found to be in collision in some state
187  StringPairSet links_seen_colliding;
188 
189  // LinkGraph is a custom type of a map with a LinkModel as key and a set of LinkModels as second
190  LinkGraph link_graph;
191 
192  // RCLCPP_INFO_STREAM_STREAM(LOGGER, "Initial allowed Collision Matrix Size = " << scene.getAllowedCollisions().getSize() );
193 
194  // 0. GENERATE ALL POSSIBLE LINK PAIRS -------------------------------------------------------------
195  // Generate a list of unique link pairs for all links with geometry. Order pairs alphabetically.
196  // There should be n choose 2 pairs
197  computeLinkPairs(*scene, link_pairs);
198  *progress = 1;
199 
200  // 1. FIND CONNECTING LINKS ------------------------------------------------------------------------
201  // For each link, compute the set of other links it connects to via a single joint (adjacent links)
202  // or via a chain of joints with intermediate links with no geometry (like a socket joint)
203 
204  // Create Connection Graph
205  computeConnectionGraph(scene->getRobotModel()->getRootLink(), link_graph);
206  *progress = 2; // Progress bar feedback
207  boost::this_thread::interruption_point();
208 
209  // 2. DISABLE ALL ADJACENT LINK COLLISIONS ---------------------------------------------------------
210  // if 2 links are adjacent, or adjacent with a zero-shape between them, disable collision checking for them
211  unsigned int num_adjacent = disableAdjacentLinks(*scene, link_graph, link_pairs);
212  *progress = 4; // Progress bar feedback
213  boost::this_thread::interruption_point();
214 
215  // 3. INITIAL CONTACTS TO CONSIDER GUESS -----------------------------------------------------------
216  // Create collision detection request object
218  req.contacts = true;
219  // max number of contacts to compute. initial guess is number of links on robot
220  req.max_contacts = int(link_graph.size());
221  req.max_contacts_per_pair = 1;
222  req.verbose = false;
223 
224  // 4. DISABLE "DEFAULT" COLLISIONS --------------------------------------------------------
225  // Disable all collision checks that occur when the robot is started in its default state
226  unsigned int num_default = disableDefaultCollisions(*scene, link_pairs, req);
227  *progress = 6; // Progress bar feedback
228  boost::this_thread::interruption_point();
229 
230  // 5. ALWAYS IN COLLISION --------------------------------------------------------------------
231  // Compute the links that are always in collision
232  unsigned int num_always =
233  disableAlwaysInCollision(*scene, link_pairs, req, links_seen_colliding, min_collision_fraction);
234  // RCLCPP_INFO_STREAM(LOGGER, "Links seen colliding total = %d", int(links_seen_colliding.size()));
235  *progress = 8; // Progress bar feedback
236  boost::this_thread::interruption_point();
237 
238  // 6. NEVER IN COLLISION -------------------------------------------------------------------
239  // Get the pairs of links that are never in collision
240  unsigned int num_never = 0;
241  if (include_never_colliding) // option of function
242  {
243  num_never = disableNeverInCollision(num_trials, *scene, link_pairs, req, links_seen_colliding, progress);
244  }
245 
246  // RCLCPP_INFO_STREAM(LOGGER, "Link pairs seen colliding ever: %d", int(links_seen_colliding.size()));
247 
248  if (verbose)
249  {
250  // Calculate number of disabled links:
251  unsigned int num_disabled = 0;
252  for (LinkPairMap::const_iterator pair_it = link_pairs.begin(); pair_it != link_pairs.end(); ++pair_it)
253  {
254  if (pair_it->second.disable_check) // has a reason to be disabled
255  ++num_disabled;
256  }
257 
258  RCLCPP_INFO_STREAM(LOGGER, "-------------------------------------------------------------------------------");
259  RCLCPP_INFO_STREAM(LOGGER, "Statistics:");
260  unsigned int num_links = int(link_graph.size());
261  double num_possible = boost::math::binomial_coefficient<double>(num_links, 2); // n choose 2
262  unsigned int num_sometimes = num_possible - num_disabled;
263 
264  RCLCPP_INFO_STREAM(LOGGER, "Total Links : " + std::to_string(num_links));
265  RCLCPP_INFO_STREAM(LOGGER, "Total possible collisions : " + std::to_string(num_possible));
266  RCLCPP_INFO_STREAM(LOGGER, "Always in collision : " + std::to_string(num_always));
267  RCLCPP_INFO_STREAM(LOGGER, "Never in collision : " + std::to_string(num_never));
268  RCLCPP_INFO_STREAM(LOGGER, "Default in collision : " + std::to_string(num_default));
269  RCLCPP_INFO_STREAM(LOGGER, "Adjacent links disabled : " + std::to_string(num_adjacent));
270  RCLCPP_INFO_STREAM(LOGGER, "Sometimes in collision : " + std::to_string(num_sometimes));
271  RCLCPP_INFO_STREAM(LOGGER, "TOTAL DISABLED : " + std::to_string(num_disabled));
272 
273  /*ROS_INFO("Copy to Spreadsheet:");
274  ROS_INFO_STREAM(num_links << "\t" << num_possible << "\t" << num_always << "\t" << num_never
275  << "\t" << num_default << "\t" << num_adjacent << "\t" << num_sometimes
276  << "\t" << num_disabled);
277  */
278  }
279 
280  *progress = 100; // end the status bar
281 
282  return link_pairs;
283 }
284 
285 // ******************************************************************************************
286 // Helper function for adding two links to the disabled links data structure
287 // ******************************************************************************************
288 bool setLinkPair(const std::string& linkA, const std::string& linkB, const DisabledReason reason,
289  LinkPairMap& link_pairs)
290 {
291  bool is_unique = false; // determine if this link pair had already existsed in the link_pairs datastructure
292 
293  // Determine order of the 2 links in the pair
294  std::pair<std::string, std::string> link_pair;
295 
296  // compare the string names of the two links and add the lesser alphabetically, s.t. the pair is only added once
297  if (linkA < linkB)
298  {
299  link_pair = std::pair<std::string, std::string>(linkA, linkB);
300  }
301  else
302  {
303  link_pair = std::pair<std::string, std::string>(linkB, linkA);
304  }
305 
306  // Update properties of this link pair using only 1 search
307  LinkPairData* link_pair_ptr = &link_pairs[link_pair];
308 
309  // Check if link pair was already disabled. It also creates the entry if none existed
310  if (!link_pairs[link_pair].disable_check) // it was not previously disabled
311  {
312  is_unique = true;
313  link_pair_ptr->reason = reason; // only change the reason if the pair was previously enabled
314  }
315 
316  // Only disable collision checking if there is a reason to disable it. This func is also used for initializing pairs
317  link_pair_ptr->disable_check = (reason != NOT_DISABLED);
318 
319  return is_unique;
320 }
321 
322 // ******************************************************************************************
323 // Generate a list of unique link pairs for all links with geometry. Order pairs alphabetically. n choose 2 pairs
324 // ******************************************************************************************
326 {
327  // Get the names of the link models that have some collision geometry associated to themselves
328  const std::vector<std::string>& names = scene.getRobotModel()->getLinkModelNamesWithCollisionGeometry();
329 
330  std::pair<std::string, std::string> temp_pair;
331 
332  // Loop through every combination of name pairs, AB and BA, n^2
333  for (std::size_t i = 0; i < names.size(); ++i)
334  {
335  for (std::size_t j = i + 1; j < names.size(); ++j)
336  {
337  // Add to link pairs list
338  setLinkPair(names[i], names[j], NOT_DISABLED, link_pairs);
339  }
340  }
341 }
342 // ******************************************************************************************
343 // Build the robot links connection graph and then check for links with no geomotry
344 // ******************************************************************************************
345 void computeConnectionGraph(const moveit::core::LinkModel* start_link, LinkGraph& link_graph)
346 {
347  link_graph.clear(); // make sure the edges structure is clear
348 
349  // Recursively build adj list of link connections
350  computeConnectionGraphRec(start_link, link_graph);
351 
352  // Repeatidly check for links with no geometry and remove them, then re-check until no more removals are detected
353  bool update = true; // track if a no geometry link was found
354  while (update)
355  {
356  update = false; // default
357 
358  // Check if each edge has a shape
359  for (LinkGraph::const_iterator edge_it = link_graph.begin(); edge_it != link_graph.end(); ++edge_it)
360  {
361  if (edge_it->first->getShapes().empty()) // link in adjList "link_graph" does not have shape, remove!
362  {
363  // Temporary list for connected links
364  std::vector<const moveit::core::LinkModel*> temp_list;
365 
366  // Copy link's parent and child links to temp_list
367  for (const moveit::core::LinkModel* adj_it : edge_it->second)
368  {
369  temp_list.push_back(adj_it);
370  }
371 
372  // Make all preceding and succeeding links to the no-shape link fully connected
373  // so that they don't collision check with themselves
374  for (std::size_t i = 0; i < temp_list.size(); ++i)
375  {
376  for (std::size_t j = i + 1; j < temp_list.size(); ++j)
377  {
378  // for each LinkModel in temp_list, find its location in the link_graph structure and insert the rest
379  // of the links into its unique set.
380  // if the LinkModel is not already in the set, update is set to true so that we keep searching
381  if (link_graph[temp_list[i]].insert(temp_list[j]).second)
382  update = true;
383  if (link_graph[temp_list[j]].insert(temp_list[i]).second)
384  update = true;
385  }
386  }
387  }
388  }
389  }
390  // RCLCPP_INFO_STREAM(LOGGER, "Generated connection graph with %d links", int(link_graph.size()));
391 }
392 
393 // ******************************************************************************************
394 // Recursively build the adj list of link connections
395 // ******************************************************************************************
396 void computeConnectionGraphRec(const moveit::core::LinkModel* start_link, LinkGraph& link_graph)
397 {
398  if (start_link) // check that the link is a valid pointer
399  {
400  // Loop through every link attached to start_link
401  for (std::size_t i = 0; i < start_link->getChildJointModels().size(); ++i)
402  {
403  const moveit::core::LinkModel* next = start_link->getChildJointModels()[i]->getChildLinkModel();
404 
405  // Bi-directional connection
406  link_graph[next].insert(start_link);
407  link_graph[start_link].insert(next);
408 
409  // Iterate with subsequent link
410  computeConnectionGraphRec(next, link_graph);
411  }
412  }
413  else
414  {
415  RCLCPP_ERROR_STREAM(LOGGER, "Joint exists in URDF with no link!");
416  }
417 }
418 
419 // ******************************************************************************************
420 // Disable collision checking for adjacent links, or adjacent with no geometry links between them
421 // ******************************************************************************************
422 unsigned int disableAdjacentLinks(planning_scene::PlanningScene& scene, LinkGraph& link_graph, LinkPairMap& link_pairs)
423 {
424  int num_disabled = 0;
425  for (LinkGraph::const_iterator link_graph_it = link_graph.begin(); link_graph_it != link_graph.end(); ++link_graph_it)
426  {
427  // disable all connected links to current link by looping through them
428  for (std::set<const moveit::core::LinkModel*>::const_iterator adj_it = link_graph_it->second.begin();
429  adj_it != link_graph_it->second.end(); ++adj_it)
430  {
431  // RCLCPP_INFO_STREAM(LOGGER, "Disabled %s to %s", link_graph_it->first->getName().c_str(), (*adj_it)->getName().c_str() );
432 
433  // Check if either of the links have no geometry. If so, do not add (are we sure?)
434  if (!link_graph_it->first->getShapes().empty() && !(*adj_it)->getShapes().empty()) // both links have geometry
435  {
436  num_disabled += setLinkPair(link_graph_it->first->getName(), (*adj_it)->getName(), ADJACENT, link_pairs);
437 
438  // disable link checking in the collision matrix
439  scene.getAllowedCollisionMatrixNonConst().setEntry(link_graph_it->first->getName(), (*adj_it)->getName(), true);
440  }
441  }
442  }
443  // RCLCPP_INFO_STREAM(LOGGER, "Disabled %d adjacent link pairs from collision checking", num_disabled);
444 
445  return num_disabled;
446 }
447 
448 // ******************************************************************************************
449 // Disable all collision checks that occur when the robot is started in its default state
450 // ******************************************************************************************
451 unsigned int disableDefaultCollisions(planning_scene::PlanningScene& scene, LinkPairMap& link_pairs,
453 {
454  // Setup environment
456  scene.getCurrentStateNonConst().setToDefaultValues(); // set to default values of 0 OR half between low and high
457  // joint values
458  scene.checkSelfCollision(req, res);
459 
460  // For each collision in default state, always add to disabled links set
461  int num_disabled = 0;
462  for (collision_detection::CollisionResult::ContactMap::const_iterator it = res.contacts.begin();
463  it != res.contacts.end(); ++it)
464  {
465  num_disabled += setLinkPair(it->first.first, it->first.second, DEFAULT, link_pairs);
466 
467  // disable link checking in the collision matrix
468  scene.getAllowedCollisionMatrixNonConst().setEntry(it->first.first, it->first.second, true);
469  }
470 
471  // RCLCPP_INFO_STREAM(LOGGER, "Disabled %d link pairs that are in collision in default state from collision checking", num_disabled);
472 
473  return num_disabled;
474 }
475 
476 // ******************************************************************************************
477 // Compute the links that are always in collision
478 // ******************************************************************************************
479 unsigned int disableAlwaysInCollision(planning_scene::PlanningScene& scene, LinkPairMap& link_pairs,
480  collision_detection::CollisionRequest& req, StringPairSet& links_seen_colliding,
481  double min_collision_faction)
482 {
483  // Trial count variables
484  static const unsigned int SMALL_TRIAL_COUNT = 200;
485  static const unsigned int SMALL_TRIAL_LIMIT = (unsigned int)((double)SMALL_TRIAL_COUNT * min_collision_faction);
486 
487  bool done = false;
488  unsigned int num_disabled = 0;
489 
490  while (!done)
491  {
492  // DO 'SMALL_TRIAL_COUNT' COLLISION CHECKS AND RECORD STATISTICS ---------------------------------------
493  std::map<std::pair<std::string, std::string>, unsigned int> collision_count;
494 
495  // Do a large number of tests
496  for (unsigned int i = 0; i < SMALL_TRIAL_COUNT; ++i)
497  {
498  // Check for collisions
500  scene.getCurrentStateNonConst().setToRandomPositions();
501  scene.checkSelfCollision(req, res);
502 
503  // Sum the number of collisions
504  unsigned int nc = 0;
505  for (collision_detection::CollisionResult::ContactMap::const_iterator it = res.contacts.begin();
506  it != res.contacts.end(); ++it)
507  {
508  collision_count[it->first]++;
509  links_seen_colliding.insert(it->first);
510  nc += it->second.size();
511  }
512 
513  // Check if the number of contacts is greater than the max count
514  if (nc >= req.max_contacts)
515  {
516  req.max_contacts *= 2; // double the max contacts that the CollisionRequest checks for
517  // RCLCPP_INFO_STREAM(LOGGER, "Doubling max_contacts to %d", int(req.max_contacts));
518  }
519  }
520 
521  // >= XX% OF TIME IN COLLISION DISABLE -----------------------------------------------------
522  // Disable collision checking for links that are >= XX% of the time in collision (XX% = 95% by default)
523  int found = 0;
524 
525  // Loop through every pair of link collisions and disable if it meets the threshold
526  for (std::map<std::pair<std::string, std::string>, unsigned int>::const_iterator it = collision_count.begin();
527  it != collision_count.end(); ++it)
528  {
529  // Disable these two links permanently
530  if (it->second > SMALL_TRIAL_LIMIT)
531  {
532  num_disabled += setLinkPair(it->first.first, it->first.second, ALWAYS, link_pairs);
533 
534  // disable link checking in the collision matrix
535  scene.getAllowedCollisionMatrixNonConst().setEntry(it->first.first, it->first.second, true);
536 
537  found++;
538  }
539  }
540 
541  // if no updates were made to the collision matrix, we stop
542  if (found == 0)
543  done = true;
544 
545  // RCLCPP_INFO_STREAM(LOGGER, "Disabled %u link pairs that are always in collision from collision checking", found);
546  }
547 
548  return num_disabled;
549 }
550 
551 // ******************************************************************************************
552 // Get the pairs of links that are never in collision
553 // ******************************************************************************************
554 unsigned int disableNeverInCollision(const unsigned int num_trials, planning_scene::PlanningScene& scene,
555  LinkPairMap& link_pairs, const collision_detection::CollisionRequest& req,
556  StringPairSet& links_seen_colliding, unsigned int* progress)
557 {
558  unsigned int num_disabled = 0;
559  std::vector<std::thread> bgroup;
560  std::mutex lock; // used for sharing the same data structures
561 
562  int num_threads = std::thread::hardware_concurrency(); // how many cores does this computer have?
563  // RCLCPP_INFO_STREAM_STREAM(LOGGER, "Performing " << num_trials << " trials for 'always in collision' checking on " <<
564  // num_threads << " threads...");
565 
566  for (int i = 0; i < num_threads; ++i)
567  {
568  ThreadComputation tc(scene, req, i, num_trials / num_threads, &links_seen_colliding, &lock, progress);
569  bgroup.push_back(std::thread([tc] { return disableNeverInCollisionThread(tc); }));
570  }
571 
572  for (auto& thread : bgroup)
573  {
574  thread.join();
575  }
576 
577  // Loop through every possible link pair and check if it has ever been seen in collision
578  for (std::pair<const std::pair<std::string, std::string>, LinkPairData>& link_pair : link_pairs)
579  {
580  if (!link_pair.second.disable_check) // is not disabled yet
581  {
582  // Check if current pair has been seen colliding ever. If it has never been seen colliding, add it to disabled
583  // list
584  if (links_seen_colliding.find(link_pair.first) == links_seen_colliding.end())
585  {
586  // Add to disabled list using pair ordering
587  link_pair.second.reason = NEVER;
588  link_pair.second.disable_check = true;
589 
590  // Count it
591  ++num_disabled;
592  }
593  }
594  }
595  // RCLCPP_INFO_STREAM(LOGGER, "Disabled %d link pairs that are never in collision", num_disabled);
596 
597  return num_disabled;
598 }
599 
600 // ******************************************************************************************
601 // Thread for getting the pairs of links that are never in collision
602 // ******************************************************************************************
603 void disableNeverInCollisionThread(ThreadComputation tc)
604 {
605  // RCLCPP_INFO_STREAM_STREAM(LOGGER, "Thread " << tc.thread_id_ << " running " << tc.num_trials_ << " trials");
606 
607  // User feedback vars
608  const unsigned int progress_interval = tc.num_trials_ / 20; // show progress update every 5%
609 
610  // Create a new kinematic state for this thread to work on
611  moveit::core::RobotState robot_state(tc.scene_.getRobotModel());
612 
613  // Do a large number of tests
614  for (unsigned int i = 0; i < tc.num_trials_; ++i)
615  {
616  boost::this_thread::interruption_point();
617 
618  // Status update at intervals and only for 0 thread
619  if (i % progress_interval == 0 && tc.thread_id_ == 0)
620  {
621  (*tc.progress_) = i * 92 / tc.num_trials_ + 8; // 8 is the amount of progress already completed in prev steps
622  }
623 
625  robot_state.setToRandomPositions();
626  tc.scene_.checkSelfCollision(tc.req_, res, robot_state);
627 
628  // Check all contacts
629  for (collision_detection::CollisionResult::ContactMap::const_iterator it = res.contacts.begin();
630  it != res.contacts.end(); ++it)
631  {
632  // Check if this collision pair is unique before doing a thread lock
633  if (tc.links_seen_colliding_->find(it->first) == tc.links_seen_colliding_->end())
634  {
635  // Collision Matrix and links_seen_colliding is modified only if needed, based on above if statement
636 
637  std::scoped_lock slock(*tc.lock_);
638  tc.links_seen_colliding_->insert(it->first);
639 
640  tc.scene_.getAllowedCollisionMatrixNonConst().setEntry(it->first.first, it->first.second,
641  true); // disable link checking in the collision matrix
642  }
643  }
644  }
645 }
646 
647 // ******************************************************************************************
648 // Converts a reason for disabling a link pair into a string
649 // ******************************************************************************************
650 const std::string disabledReasonToString(DisabledReason reason)
651 {
652  return REASONS_TO_STRING.at(reason);
653 }
654 
655 // ******************************************************************************************
656 // Converts a string reason for disabling a link pair into a struct data type
657 // ******************************************************************************************
658 DisabledReason disabledReasonFromString(const std::string& reason)
659 {
661  try
662  {
663  r = REASONS_FROM_STRING.at(reason);
664  }
665  catch (const std::out_of_range&)
666  {
667  r = USER;
668  }
669 
670  return r;
671 }
672 
673 } // namespace srdf_setup
674 } // namespace moveit_setup
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition: link_model.h:72
const std::vector< const JointModel * > & getChildJointModels() const
A link may have 0 or more child joints. From those joints there will certainly be other descendant li...
Definition: link_model.h:128
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
This class maintains the representation of the environment as seen by a planning instance....
const std::unordered_map< DisabledReason, std::string > REASONS_TO_STRING
LinkPairMap computeDefaultCollisions(const planning_scene::PlanningSceneConstPtr &parent_scene, unsigned int *progress, const bool include_never_colliding, const unsigned int trials, const double min_collision_faction, const bool verbose)
Generate an adjacency list of links that are always and never in collision, to speed up collision det...
DisabledReason
Reasons for disabling link pairs. Append "in collision" for understanding. NOT_DISABLED means the lin...
std::set< std::pair< std::string, std::string > > StringPairSet
void computeLinkPairs(const planning_scene::PlanningScene &scene, LinkPairMap &link_pairs)
Generate a list of unique link pairs for all links with geometry. Order pairs alphabetically....
DisabledReason disabledReasonFromString(const std::string &reason)
Converts a string reason for disabling a link pair into a struct data type.
const std::string disabledReasonToString(DisabledReason reason)
Converts a reason for disabling a link pair into a string.
std::map< std::pair< std::string, std::string >, LinkPairData > LinkPairMap
LinkPairMap is an adjacency list structure containing links in string-based form. Used for disabled l...
std::map< const moveit::core::LinkModel *, std::set< const moveit::core::LinkModel * > > LinkGraph
const std::unordered_map< std::string, DisabledReason > REASONS_FROM_STRING
scene
Definition: pick.py:52
r
Definition: plan.py:56
Representation of a collision checking request.
bool verbose
Flag indicating whether information about detected collisions should be reported.
bool contacts
If true, compute contacts. Otherwise only a binary collision yes/no is reported.
std::size_t max_contacts
Overall maximum number of contacts to compute.
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...
Representation of a collision checking result.
ContactMap contacts
A map returning the pairs of body ids in contact, plus their contact details.
ThreadComputation(planning_scene::PlanningScene &scene, const collision_detection::CollisionRequest &req, int thread_id, int num_trials, StringPairSet *links_seen_colliding, std::mutex *lock, unsigned int *progress)
const collision_detection::CollisionRequest & req_