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


moveit_setup_assistant
Author(s): Dave Coleman
autogenerated on Sat May 3 2025 02:28:04