39 #include <boost/math/special_functions/binomial.hpp>
40 #include <boost/thread.hpp>
41 #include <boost/assign.hpp>
42 #include <unordered_map>
61 const std::unordered_map<DisabledReason, std::string>
REASONS_TO_STRING = boost::assign::map_list_of(
NEVER,
"Never")(
74 int thread_id,
int num_trials,
StringPairSet* links_seen_colliding, std::mutex* lock,
75 unsigned int* progress)
95 typedef std::map<const moveit::core::LinkModel*, std::set<const moveit::core::LinkModel*> >
LinkGraph;
109 static bool setLinkPair(
const std::string& linkA,
const std::string& linkB,
const DisabledReason reason,
158 StringPairSet& links_seen_colliding,
double min_collision_faction = 0.95);
170 StringPairSet& links_seen_colliding,
unsigned int* progress);
182 const bool include_never_colliding,
const unsigned int num_trials,
183 const double min_collision_fraction,
const bool verbose)
186 planning_scene::PlanningScenePtr scene = parent_scene->diff();
208 computeConnectionGraph(scene->getRobotModel()->getRootLink(), link_graph);
210 boost::this_thread::interruption_point();
214 unsigned int num_adjacent = disableAdjacentLinks(*scene, link_graph, link_pairs);
216 boost::this_thread::interruption_point();
229 unsigned int num_default = disableDefaultCollisions(*scene, link_pairs, req);
231 boost::this_thread::interruption_point();
235 unsigned int num_always =
236 disableAlwaysInCollision(*scene, link_pairs, req, links_seen_colliding, min_collision_fraction);
239 boost::this_thread::interruption_point();
243 unsigned int num_never = 0;
244 if (include_never_colliding)
246 num_never = disableNeverInCollision(num_trials, *scene, link_pairs, req, links_seen_colliding, progress);
252 unsigned int num_disabled = 0;
253 for (LinkPairMap::const_iterator pair_it = link_pairs.begin(); pair_it != link_pairs.end(); ++pair_it)
255 if (pair_it->second.disable_check)
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);
263 unsigned int num_sometimes = num_possible - num_disabled;
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));
283 bool setLinkPair(
const std::string& linkA,
const std::string& linkB,
const DisabledReason reason,
286 bool is_unique =
false;
289 std::pair<std::string, std::string> link_pair;
294 link_pair = std::pair<std::string, std::string>(linkA, linkB);
298 link_pair = std::pair<std::string, std::string>(linkB, linkA);
302 LinkPairData* link_pair_ptr = &link_pairs[link_pair];
305 if (!link_pairs[link_pair].disable_check)
308 link_pair_ptr->reason = reason;
312 link_pair_ptr->disable_check = (reason !=
NOT_DISABLED);
323 const std::vector<std::string>& names = scene.
getRobotModel()->getLinkModelNamesWithCollisionGeometry();
325 std::pair<std::string, std::string> temp_pair;
328 for (std::size_t i = 0; i < names.size(); ++i)
330 for (std::size_t j = i + 1; j < names.size(); ++j)
333 setLinkPair(names[i], names[j],
NOT_DISABLED, link_pairs);
345 computeConnectionGraphRec(start_link, link_graph);
354 for (LinkGraph::const_iterator edge_it = link_graph.begin(); edge_it != link_graph.end(); ++edge_it)
356 if (edge_it->first->getShapes().empty())
359 std::vector<const moveit::core::LinkModel*> temp_list;
364 temp_list.push_back(adj_it);
369 for (std::size_t i = 0; i < temp_list.size(); ++i)
371 for (std::size_t j = i + 1; j < temp_list.size(); ++j)
376 if (link_graph[temp_list[i]].insert(temp_list[j]).second)
378 if (link_graph[temp_list[j]].insert(temp_list[i]).second)
400 link_graph[next].insert(start_link);
401 link_graph[start_link].insert(next);
404 computeConnectionGraphRec(next, link_graph);
409 RCLCPP_ERROR_STREAM(
getLogger(),
"Joint exists in URDF with no link!");
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)
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)
426 if (!link_graph_it->first->getShapes().empty() && !(*adj_it)->getShapes().empty())
428 num_disabled += setLinkPair(link_graph_it->first->getName(), (*adj_it)->getName(),
ADJACENT, link_pairs);
452 int num_disabled = 0;
453 for (collision_detection::CollisionResult::ContactMap::const_iterator it = res.
contacts.begin();
456 num_disabled += setLinkPair(it->first.first, it->first.second,
DEFAULT, link_pairs);
470 double min_collision_faction)
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);
478 unsigned int num_disabled = 0;
483 std::map<std::pair<std::string, std::string>,
unsigned int> collision_count;
486 for (
unsigned int i = 0; i < SMALL_TRIAL_COUNT; ++i)
495 for (collision_detection::CollisionResult::ContactMap::const_iterator it = res.
contacts.begin();
498 collision_count[it->first]++;
499 links_seen_colliding.insert(it->first);
500 nc += it->second.size();
515 for (std::map<std::pair<std::string, std::string>,
unsigned int>::const_iterator it = collision_count.begin();
516 it != collision_count.end(); ++it)
519 if (it->second > SMALL_TRIAL_LIMIT)
521 num_disabled += setLinkPair(it->first.first, it->first.second,
ALWAYS, link_pairs);
545 unsigned int num_disabled = 0;
546 std::vector<std::thread> bgroup;
549 int num_threads = std::thread::hardware_concurrency();
551 for (
int i = 0; i < num_threads; ++i)
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); }));
557 for (
auto& thread : bgroup)
563 for (std::pair<
const std::pair<std::string, std::string>, LinkPairData>& link_pair : link_pairs)
565 if (!link_pair.second.disable_check)
569 if (links_seen_colliding.find(link_pair.first) == links_seen_colliding.end())
572 link_pair.second.reason =
NEVER;
573 link_pair.second.disable_check =
true;
587 void disableNeverInCollisionThread(ThreadComputation tc)
590 const unsigned int progress_interval = tc.num_trials_ / 20;
596 for (
unsigned int i = 0; i < tc.num_trials_; ++i)
598 boost::this_thread::interruption_point();
601 if (i % progress_interval == 0 && tc.thread_id_ == 0)
603 (*tc.progress_) = i * 92 / tc.num_trials_ + 8;
607 robot_state.setToRandomPositions();
608 tc.scene_.checkSelfCollision(tc.req_, res, robot_state);
611 for (collision_detection::CollisionResult::ContactMap::const_iterator it = res.
contacts.begin();
615 if (tc.links_seen_colliding_->find(it->first) == tc.links_seen_colliding_->end())
619 std::scoped_lock slock(*tc.lock_);
620 tc.links_seen_colliding_->insert(it->first);
622 tc.scene_.getAllowedCollisionMatrixNonConst().setEntry(it->first.first, it->first.second,
647 catch (
const std::out_of_range&)
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.
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.
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.
rclcpp::Logger getLogger()
void update(moveit::core::RobotState *self, bool force, std::string &category)
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.
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_