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 #include <moveit/utils/logger.hpp>
44 
45 namespace moveit_setup
46 {
47 namespace srdf_setup
48 {
49 namespace
50 {
51 rclcpp::Logger getLogger()
52 {
53  return moveit::getLogger("moveit.setup_assistant.collision_updater");
54 }
55 } // namespace
56 // ******************************************************************************************
57 // Custom Types, Enums and Structs
58 // ******************************************************************************************
59 
60 // Mapping of reasons for disabling a link pair to strings
61 const std::unordered_map<DisabledReason, std::string> REASONS_TO_STRING = boost::assign::map_list_of(NEVER, "Never")(
62  DEFAULT, "Default")(ADJACENT, "Adjacent")(ALWAYS, "Always")(USER, "User")(NOT_DISABLED, "Not Disabled");
63 
64 const std::unordered_map<std::string, DisabledReason> REASONS_FROM_STRING = boost::assign::map_list_of("Never", NEVER)(
65  "Default", DEFAULT)("Adjacent", ADJACENT)("Always", ALWAYS)("User", USER)("Not Disabled", NOT_DISABLED);
66 
67 // Unique set of pairs of links in string-based form
68 typedef std::set<std::pair<std::string, std::string> > StringPairSet;
69 
70 // Struct for passing parameters to threads, for cleaner code
72 {
74  int thread_id, int num_trials, StringPairSet* links_seen_colliding, std::mutex* lock,
75  unsigned int* progress)
76  : scene_(scene)
77  , req_(req)
78  , thread_id_(thread_id)
79  , num_trials_(num_trials)
80  , links_seen_colliding_(links_seen_colliding)
81  , lock_(lock)
82  , progress_(progress)
83  {
84  }
88  unsigned int num_trials_;
90  std::mutex* lock_;
91  unsigned int* progress_; // only to be updated by thread 0
92 };
93 
94 // LinkGraph defines a Link's model and a set of unique links it connects
95 typedef std::map<const moveit::core::LinkModel*, std::set<const moveit::core::LinkModel*> > LinkGraph;
96 
97 // ******************************************************************************************
98 // Static Prototypes
99 // ******************************************************************************************
100 
109 static bool setLinkPair(const std::string& linkA, const std::string& linkB, const DisabledReason reason,
110  LinkPairMap& link_pairs);
111 
117 static void computeConnectionGraph(const moveit::core::LinkModel* link, LinkGraph& link_graph);
118 
124 static void computeConnectionGraphRec(const moveit::core::LinkModel* link, LinkGraph& link_graph);
125 
133 static unsigned int disableAdjacentLinks(planning_scene::PlanningScene& scene, LinkGraph& link_graph,
134  LinkPairMap& link_pairs);
135 
143 static unsigned int disableDefaultCollisions(planning_scene::PlanningScene& scene, LinkPairMap& link_pairs,
145 
156 static unsigned int disableAlwaysInCollision(planning_scene::PlanningScene& scene, LinkPairMap& link_pairs,
158  StringPairSet& links_seen_colliding, double min_collision_faction = 0.95);
159 
168 static unsigned int disableNeverInCollision(const unsigned int num_trials, planning_scene::PlanningScene& scene,
169  LinkPairMap& link_pairs, const collision_detection::CollisionRequest& req,
170  StringPairSet& links_seen_colliding, unsigned int* progress);
171 
176 static void disableNeverInCollisionThread(ThreadComputation tc);
177 
178 // ******************************************************************************************
179 // Generates an adjacency list of links that are always and never in collision, to speed up collision detection
180 // ******************************************************************************************
181 LinkPairMap computeDefaultCollisions(const planning_scene::PlanningSceneConstPtr& parent_scene, unsigned int* progress,
182  const bool include_never_colliding, const unsigned int num_trials,
183  const double min_collision_fraction, const bool verbose)
184 {
185  // Create new instance of planning scene using pointer
186  planning_scene::PlanningScenePtr scene = parent_scene->diff();
187 
188  // Map of disabled collisions that contains a link as a key and an ordered list of links that are connected.
189  LinkPairMap link_pairs;
190 
191  // Track unique edges that have been found to be in collision in some state
192  StringPairSet links_seen_colliding;
193 
194  // LinkGraph is a custom type of a map with a LinkModel as key and a set of LinkModels as second
195  LinkGraph link_graph;
196 
197  // 0. GENERATE ALL POSSIBLE LINK PAIRS -------------------------------------------------------------
198  // Generate a list of unique link pairs for all links with geometry. Order pairs alphabetically.
199  // There should be n choose 2 pairs
200  computeLinkPairs(*scene, link_pairs);
201  *progress = 1;
202 
203  // 1. FIND CONNECTING LINKS ------------------------------------------------------------------------
204  // For each link, compute the set of other links it connects to via a single joint (adjacent links)
205  // or via a chain of joints with intermediate links with no geometry (like a socket joint)
206 
207  // Create Connection Graph
208  computeConnectionGraph(scene->getRobotModel()->getRootLink(), link_graph);
209  *progress = 2; // Progress bar feedback
210  boost::this_thread::interruption_point();
211 
212  // 2. DISABLE ALL ADJACENT LINK COLLISIONS ---------------------------------------------------------
213  // if 2 links are adjacent, or adjacent with a zero-shape between them, disable collision checking for them
214  unsigned int num_adjacent = disableAdjacentLinks(*scene, link_graph, link_pairs);
215  *progress = 4; // Progress bar feedback
216  boost::this_thread::interruption_point();
217 
218  // 3. INITIAL CONTACTS TO CONSIDER GUESS -----------------------------------------------------------
219  // Create collision detection request object
221  req.contacts = true;
222  // max number of contacts to compute. initial guess is number of links on robot
223  req.max_contacts = int(link_graph.size());
224  req.max_contacts_per_pair = 1;
225  req.verbose = false;
226 
227  // 4. DISABLE "DEFAULT" COLLISIONS --------------------------------------------------------
228  // Disable all collision checks that occur when the robot is started in its default state
229  unsigned int num_default = disableDefaultCollisions(*scene, link_pairs, req);
230  *progress = 6; // Progress bar feedback
231  boost::this_thread::interruption_point();
232 
233  // 5. ALWAYS IN COLLISION --------------------------------------------------------------------
234  // Compute the links that are always in collision
235  unsigned int num_always =
236  disableAlwaysInCollision(*scene, link_pairs, req, links_seen_colliding, min_collision_fraction);
237  // RCLCPP_INFO_STREAM(getLogger(), "Links seen colliding total = %d", int(links_seen_colliding.size()));
238  *progress = 8; // Progress bar feedback
239  boost::this_thread::interruption_point();
240 
241  // 6. NEVER IN COLLISION -------------------------------------------------------------------
242  // Get the pairs of links that are never in collision
243  unsigned int num_never = 0;
244  if (include_never_colliding) // option of function
245  {
246  num_never = disableNeverInCollision(num_trials, *scene, link_pairs, req, links_seen_colliding, progress);
247  }
248 
249  if (verbose)
250  {
251  // Calculate number of disabled links:
252  unsigned int num_disabled = 0;
253  for (LinkPairMap::const_iterator pair_it = link_pairs.begin(); pair_it != link_pairs.end(); ++pair_it)
254  {
255  if (pair_it->second.disable_check) // has a reason to be disabled
256  ++num_disabled;
257  }
258 
259  RCLCPP_INFO_STREAM(getLogger(), "-------------------------------------------------------------------------------");
260  RCLCPP_INFO_STREAM(getLogger(), "Statistics:");
261  unsigned int num_links = int(link_graph.size());
262  double num_possible = boost::math::binomial_coefficient<double>(num_links, 2); // n choose 2
263  unsigned int num_sometimes = num_possible - num_disabled;
264 
265  RCLCPP_INFO_STREAM(getLogger(), "Total Links : " + std::to_string(num_links));
266  RCLCPP_INFO_STREAM(getLogger(), "Total possible collisions : " + std::to_string(num_possible));
267  RCLCPP_INFO_STREAM(getLogger(), "Always in collision : " + std::to_string(num_always));
268  RCLCPP_INFO_STREAM(getLogger(), "Never in collision : " + std::to_string(num_never));
269  RCLCPP_INFO_STREAM(getLogger(), "Default in collision : " + std::to_string(num_default));
270  RCLCPP_INFO_STREAM(getLogger(), "Adjacent links disabled : " + std::to_string(num_adjacent));
271  RCLCPP_INFO_STREAM(getLogger(), "Sometimes in collision : " + std::to_string(num_sometimes));
272  RCLCPP_INFO_STREAM(getLogger(), "TOTAL DISABLED : " + std::to_string(num_disabled));
273  }
274 
275  *progress = 100; // end the status bar
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 // ******************************************************************************************
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  // Recursively build adj list of link connections
345  computeConnectionGraphRec(start_link, link_graph);
346 
347  // Repeatedly 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 preceding 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 }
386 
387 // ******************************************************************************************
388 // Recursively build the adj list of link connections
389 // ******************************************************************************************
390 void computeConnectionGraphRec(const moveit::core::LinkModel* start_link, LinkGraph& link_graph)
391 {
392  if (start_link) // check that the link is a valid pointer
393  {
394  // Loop through every link attached to start_link
395  for (std::size_t i = 0; i < start_link->getChildJointModels().size(); ++i)
396  {
397  const moveit::core::LinkModel* next = start_link->getChildJointModels()[i]->getChildLinkModel();
398 
399  // Bi-directional connection
400  link_graph[next].insert(start_link);
401  link_graph[start_link].insert(next);
402 
403  // Iterate with subsequent link
404  computeConnectionGraphRec(next, link_graph);
405  }
406  }
407  else
408  {
409  RCLCPP_ERROR_STREAM(getLogger(), "Joint exists in URDF with no link!");
410  }
411 }
412 
413 // ******************************************************************************************
414 // Disable collision checking for adjacent links, or adjacent with no geometry links between them
415 // ******************************************************************************************
416 unsigned int disableAdjacentLinks(planning_scene::PlanningScene& scene, LinkGraph& link_graph, LinkPairMap& link_pairs)
417 {
418  int num_disabled = 0;
419  for (LinkGraph::const_iterator link_graph_it = link_graph.begin(); link_graph_it != link_graph.end(); ++link_graph_it)
420  {
421  // disable all connected links to current link by looping through them
422  for (std::set<const moveit::core::LinkModel*>::const_iterator adj_it = link_graph_it->second.begin();
423  adj_it != link_graph_it->second.end(); ++adj_it)
424  {
425  // Check if either of the links have no geometry. If so, do not add (are we sure?)
426  if (!link_graph_it->first->getShapes().empty() && !(*adj_it)->getShapes().empty()) // both links have geometry
427  {
428  num_disabled += setLinkPair(link_graph_it->first->getName(), (*adj_it)->getName(), ADJACENT, link_pairs);
429 
430  // disable link checking in the collision matrix
431  scene.getAllowedCollisionMatrixNonConst().setEntry(link_graph_it->first->getName(), (*adj_it)->getName(), true);
432  }
433  }
434  }
435 
436  return num_disabled;
437 }
438 
439 // ******************************************************************************************
440 // Disable all collision checks that occur when the robot is started in its default state
441 // ******************************************************************************************
442 unsigned int disableDefaultCollisions(planning_scene::PlanningScene& scene, LinkPairMap& link_pairs,
444 {
445  // Setup environment
447  scene.getCurrentStateNonConst().setToDefaultValues(); // set to default values of 0 OR half between low and high
448  // joint values
449  scene.checkSelfCollision(req, res);
450 
451  // For each collision in default state, always add to disabled links set
452  int num_disabled = 0;
453  for (collision_detection::CollisionResult::ContactMap::const_iterator it = res.contacts.begin();
454  it != res.contacts.end(); ++it)
455  {
456  num_disabled += setLinkPair(it->first.first, it->first.second, DEFAULT, link_pairs);
457 
458  // disable link checking in the collision matrix
459  scene.getAllowedCollisionMatrixNonConst().setEntry(it->first.first, it->first.second, true);
460  }
461 
462  return num_disabled;
463 }
464 
465 // ******************************************************************************************
466 // Compute the links that are always in collision
467 // ******************************************************************************************
468 unsigned int disableAlwaysInCollision(planning_scene::PlanningScene& scene, LinkPairMap& link_pairs,
469  collision_detection::CollisionRequest& req, StringPairSet& links_seen_colliding,
470  double min_collision_faction)
471 {
472  // Trial count variables
473  static const unsigned int SMALL_TRIAL_COUNT = 200;
474  static const unsigned int SMALL_TRIAL_LIMIT =
475  static_cast<unsigned int>(static_cast<double>(SMALL_TRIAL_COUNT) * min_collision_faction);
476 
477  bool done = false;
478  unsigned int num_disabled = 0;
479 
480  while (!done)
481  {
482  // DO 'SMALL_TRIAL_COUNT' COLLISION CHECKS AND RECORD STATISTICS ---------------------------------------
483  std::map<std::pair<std::string, std::string>, unsigned int> collision_count;
484 
485  // Do a large number of tests
486  for (unsigned int i = 0; i < SMALL_TRIAL_COUNT; ++i)
487  {
488  // Check for collisions
491  scene.checkSelfCollision(req, res);
492 
493  // Sum the number of collisions
494  unsigned int nc = 0;
495  for (collision_detection::CollisionResult::ContactMap::const_iterator it = res.contacts.begin();
496  it != res.contacts.end(); ++it)
497  {
498  collision_count[it->first]++;
499  links_seen_colliding.insert(it->first);
500  nc += it->second.size();
501  }
502 
503  // Check if the number of contacts is greater than the max count
504  if (nc >= req.max_contacts)
505  {
506  req.max_contacts *= 2; // double the max contacts that the CollisionRequest checks for
507  }
508  }
509 
510  // >= XX% OF TIME IN COLLISION DISABLE -----------------------------------------------------
511  // Disable collision checking for links that are >= XX% of the time in collision (XX% = 95% by default)
512  int found = 0;
513 
514  // Loop through every pair of link collisions and disable if it meets the threshold
515  for (std::map<std::pair<std::string, std::string>, unsigned int>::const_iterator it = collision_count.begin();
516  it != collision_count.end(); ++it)
517  {
518  // Disable these two links permanently
519  if (it->second > SMALL_TRIAL_LIMIT)
520  {
521  num_disabled += setLinkPair(it->first.first, it->first.second, ALWAYS, link_pairs);
522 
523  // disable link checking in the collision matrix
524  scene.getAllowedCollisionMatrixNonConst().setEntry(it->first.first, it->first.second, true);
525 
526  found++;
527  }
528  }
529 
530  // if no updates were made to the collision matrix, we stop
531  if (found == 0)
532  done = true;
533  }
534 
535  return num_disabled;
536 }
537 
538 // ******************************************************************************************
539 // Get the pairs of links that are never in collision
540 // ******************************************************************************************
541 unsigned int disableNeverInCollision(const unsigned int num_trials, planning_scene::PlanningScene& scene,
542  LinkPairMap& link_pairs, const collision_detection::CollisionRequest& req,
543  StringPairSet& links_seen_colliding, unsigned int* progress)
544 {
545  unsigned int num_disabled = 0;
546  std::vector<std::thread> bgroup;
547  std::mutex lock; // used for sharing the same data structures
548 
549  int num_threads = std::thread::hardware_concurrency(); // how many cores does this computer have?
550 
551  for (int i = 0; i < num_threads; ++i)
552  {
553  ThreadComputation tc(scene, req, i, num_trials / num_threads, &links_seen_colliding, &lock, progress);
554  bgroup.push_back(std::thread([tc] { return disableNeverInCollisionThread(tc); }));
555  }
556 
557  for (auto& thread : bgroup)
558  {
559  thread.join();
560  }
561 
562  // Loop through every possible link pair and check if it has ever been seen in collision
563  for (std::pair<const std::pair<std::string, std::string>, LinkPairData>& link_pair : link_pairs)
564  {
565  if (!link_pair.second.disable_check) // is not disabled yet
566  {
567  // Check if current pair has been seen colliding ever. If it has never been seen colliding, add it to disabled
568  // list
569  if (links_seen_colliding.find(link_pair.first) == links_seen_colliding.end())
570  {
571  // Add to disabled list using pair ordering
572  link_pair.second.reason = NEVER;
573  link_pair.second.disable_check = true;
574 
575  // Count it
576  ++num_disabled;
577  }
578  }
579  }
580 
581  return num_disabled;
582 }
583 
584 // ******************************************************************************************
585 // Thread for getting the pairs of links that are never in collision
586 // ******************************************************************************************
587 void disableNeverInCollisionThread(ThreadComputation tc)
588 {
589  // User feedback vars
590  const unsigned int progress_interval = tc.num_trials_ / 20; // show progress update every 5%
591 
592  // Create a new kinematic state for this thread to work on
593  moveit::core::RobotState robot_state(tc.scene_.getRobotModel());
594 
595  // Do a large number of tests
596  for (unsigned int i = 0; i < tc.num_trials_; ++i)
597  {
598  boost::this_thread::interruption_point();
599 
600  // Status update at intervals and only for 0 thread
601  if (i % progress_interval == 0 && tc.thread_id_ == 0)
602  {
603  (*tc.progress_) = i * 92 / tc.num_trials_ + 8; // 8 is the amount of progress already completed in prev steps
604  }
605 
607  robot_state.setToRandomPositions();
608  tc.scene_.checkSelfCollision(tc.req_, res, robot_state);
609 
610  // Check all contacts
611  for (collision_detection::CollisionResult::ContactMap::const_iterator it = res.contacts.begin();
612  it != res.contacts.end(); ++it)
613  {
614  // Check if this collision pair is unique before doing a thread lock
615  if (tc.links_seen_colliding_->find(it->first) == tc.links_seen_colliding_->end())
616  {
617  // Collision Matrix and links_seen_colliding is modified only if needed, based on above if statement
618 
619  std::scoped_lock slock(*tc.lock_);
620  tc.links_seen_colliding_->insert(it->first);
621 
622  tc.scene_.getAllowedCollisionMatrixNonConst().setEntry(it->first.first, it->first.second,
623  true); // disable link checking in the collision matrix
624  }
625  }
626  }
627 }
628 
629 // ******************************************************************************************
630 // Converts a reason for disabling a link pair into a string
631 // ******************************************************************************************
632 const std::string disabledReasonToString(DisabledReason reason)
633 {
634  return REASONS_TO_STRING.at(reason);
635 }
636 
637 // ******************************************************************************************
638 // Converts a string reason for disabling a link pair into a struct data type
639 // ******************************************************************************************
640 DisabledReason disabledReasonFromString(const std::string& reason)
641 {
642  DisabledReason r;
643  try
644  {
645  r = REASONS_FROM_STRING.at(reason);
646  }
647  catch (const std::out_of_range&)
648  {
649  r = USER;
650  }
651 
652  return r;
653 }
654 
655 } // namespace srdf_setup
656 } // namespace moveit_setup
void setEntry(const std::string &name1, const std::string &name2, bool allowed)
Set an entry corresponding to a pair of elements.
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
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
This class maintains the representation of the environment as seen by a planning instance....
collision_detection::AllowedCollisionMatrix & getAllowedCollisionMatrixNonConst()
Get the allowed collision matrix.
moveit::core::RobotState & getCurrentStateNonConst()
Get the state at which the robot is assumed to be.
const moveit::core::RobotModelConstPtr & getRobotModel() const
Get the kinematic model for which the planning scene is maintained.
void checkSelfCollision(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res)
Check whether the current state is in self collision.
void update(moveit::core::RobotState *self, bool force, std::string &category)
Definition: robot_state.cpp:47
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
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
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.
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_