39 #include <boost/math/special_functions/binomial.hpp>
40 #include <boost/thread.hpp>
41 #include <boost/assign.hpp>
42 #include <unordered_map>
53 const std::unordered_map<DisabledReason, std::string>
REASONS_TO_STRING = boost::assign::map_list_of(
NEVER,
"Never")(
60 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"collision_updater");
69 int thread_id,
int num_trials,
StringPairSet* links_seen_colliding, std::mutex* lock,
70 unsigned int* progress)
90 typedef std::map<const moveit::core::LinkModel*, std::set<const moveit::core::LinkModel*> >
LinkGraph;
104 static bool setLinkPair(
const std::string& linkA,
const std::string& linkB,
const DisabledReason reason,
153 StringPairSet& links_seen_colliding,
double min_collision_faction = 0.95);
165 StringPairSet& links_seen_colliding,
unsigned int* progress);
177 const bool include_never_colliding,
const unsigned int num_trials,
178 const double min_collision_fraction,
const bool verbose)
181 planning_scene::PlanningScenePtr
scene = parent_scene->diff();
205 computeConnectionGraph(
scene->getRobotModel()->getRootLink(), link_graph);
207 boost::this_thread::interruption_point();
211 unsigned int num_adjacent = disableAdjacentLinks(*
scene, link_graph, link_pairs);
213 boost::this_thread::interruption_point();
226 unsigned int num_default = disableDefaultCollisions(*
scene, link_pairs, req);
228 boost::this_thread::interruption_point();
232 unsigned int num_always =
233 disableAlwaysInCollision(*
scene, link_pairs, req, links_seen_colliding, min_collision_fraction);
236 boost::this_thread::interruption_point();
240 unsigned int num_never = 0;
241 if (include_never_colliding)
243 num_never = disableNeverInCollision(num_trials, *
scene, link_pairs, req, links_seen_colliding, progress);
251 unsigned int num_disabled = 0;
252 for (LinkPairMap::const_iterator pair_it = link_pairs.begin(); pair_it != link_pairs.end(); ++pair_it)
254 if (pair_it->second.disable_check)
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);
262 unsigned int num_sometimes = num_possible - num_disabled;
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));
288 bool setLinkPair(
const std::string& linkA,
const std::string& linkB,
const DisabledReason reason,
291 bool is_unique =
false;
294 std::pair<std::string, std::string> link_pair;
299 link_pair = std::pair<std::string, std::string>(linkA, linkB);
303 link_pair = std::pair<std::string, std::string>(linkB, linkA);
307 LinkPairData* link_pair_ptr = &link_pairs[link_pair];
310 if (!link_pairs[link_pair].disable_check)
313 link_pair_ptr->reason = reason;
317 link_pair_ptr->disable_check = (reason !=
NOT_DISABLED);
328 const std::vector<std::string>& names =
scene.getRobotModel()->getLinkModelNamesWithCollisionGeometry();
330 std::pair<std::string, std::string> temp_pair;
333 for (std::size_t i = 0; i < names.size(); ++i)
335 for (std::size_t j = i + 1; j < names.size(); ++j)
338 setLinkPair(names[i], names[j],
NOT_DISABLED, link_pairs);
350 computeConnectionGraphRec(start_link, link_graph);
359 for (LinkGraph::const_iterator edge_it = link_graph.begin(); edge_it != link_graph.end(); ++edge_it)
361 if (edge_it->first->getShapes().empty())
364 std::vector<const moveit::core::LinkModel*> temp_list;
369 temp_list.push_back(adj_it);
374 for (std::size_t i = 0; i < temp_list.size(); ++i)
376 for (std::size_t j = i + 1; j < temp_list.size(); ++j)
381 if (link_graph[temp_list[i]].insert(temp_list[j]).second)
383 if (link_graph[temp_list[j]].insert(temp_list[i]).second)
406 link_graph[next].insert(start_link);
407 link_graph[start_link].insert(next);
410 computeConnectionGraphRec(next, link_graph);
415 RCLCPP_ERROR_STREAM(LOGGER,
"Joint exists in URDF with no link!");
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)
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)
434 if (!link_graph_it->first->getShapes().empty() && !(*adj_it)->getShapes().empty())
436 num_disabled += setLinkPair(link_graph_it->first->getName(), (*adj_it)->getName(),
ADJACENT, link_pairs);
439 scene.getAllowedCollisionMatrixNonConst().setEntry(link_graph_it->first->getName(), (*adj_it)->getName(),
true);
456 scene.getCurrentStateNonConst().setToDefaultValues();
458 scene.checkSelfCollision(req, res);
461 int num_disabled = 0;
462 for (collision_detection::CollisionResult::ContactMap::const_iterator it = res.
contacts.begin();
465 num_disabled += setLinkPair(it->first.first, it->first.second,
DEFAULT, link_pairs);
468 scene.getAllowedCollisionMatrixNonConst().setEntry(it->first.first, it->first.second,
true);
481 double min_collision_faction)
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);
488 unsigned int num_disabled = 0;
493 std::map<std::pair<std::string, std::string>,
unsigned int> collision_count;
496 for (
unsigned int i = 0; i < SMALL_TRIAL_COUNT; ++i)
500 scene.getCurrentStateNonConst().setToRandomPositions();
501 scene.checkSelfCollision(req, res);
505 for (collision_detection::CollisionResult::ContactMap::const_iterator it = res.
contacts.begin();
508 collision_count[it->first]++;
509 links_seen_colliding.insert(it->first);
510 nc += it->second.size();
526 for (std::map<std::pair<std::string, std::string>,
unsigned int>::const_iterator it = collision_count.begin();
527 it != collision_count.end(); ++it)
530 if (it->second > SMALL_TRIAL_LIMIT)
532 num_disabled += setLinkPair(it->first.first, it->first.second,
ALWAYS, link_pairs);
535 scene.getAllowedCollisionMatrixNonConst().setEntry(it->first.first, it->first.second,
true);
558 unsigned int num_disabled = 0;
559 std::vector<std::thread> bgroup;
562 int num_threads = std::thread::hardware_concurrency();
566 for (
int i = 0; i < num_threads; ++i)
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); }));
572 for (
auto& thread : bgroup)
578 for (std::pair<
const std::pair<std::string, std::string>, LinkPairData>& link_pair : link_pairs)
580 if (!link_pair.second.disable_check)
584 if (links_seen_colliding.find(link_pair.first) == links_seen_colliding.end())
587 link_pair.second.reason =
NEVER;
588 link_pair.second.disable_check =
true;
603 void disableNeverInCollisionThread(ThreadComputation tc)
608 const unsigned int progress_interval = tc.num_trials_ / 20;
614 for (
unsigned int i = 0; i < tc.num_trials_; ++i)
616 boost::this_thread::interruption_point();
619 if (i % progress_interval == 0 && tc.thread_id_ == 0)
621 (*tc.progress_) = i * 92 / tc.num_trials_ + 8;
625 robot_state.setToRandomPositions();
626 tc.scene_.checkSelfCollision(tc.req_, res, robot_state);
629 for (collision_detection::CollisionResult::ContactMap::const_iterator it = res.
contacts.begin();
633 if (tc.links_seen_colliding_->find(it->first) == tc.links_seen_colliding_->end())
637 std::scoped_lock slock(*tc.lock_);
638 tc.links_seen_colliding_->insert(it->first);
640 tc.scene_.getAllowedCollisionMatrixNonConst().setEntry(it->first.first, it->first.second,
665 catch (
const std::out_of_range&)
A link from the robot. Contains the constant transform applied to the link and its geometry.
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...
Representation of a robot's state. This includes position, velocity, acceleration and effort.
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
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_
StringPairSet * links_seen_colliding_
planning_scene::PlanningScene & scene_