00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <moveit/setup_assistant/tools/compute_default_collisions.h>
00038 #include <boost/math/special_functions/binomial.hpp>
00039 #include <boost/thread.hpp>
00040 #include <tinyxml.h>
00041 #include <boost/lexical_cast.hpp>
00042 #include <boost/unordered_map.hpp>
00043 #include <boost/assign.hpp>
00044 #include <ros/console.h>
00045
00046 namespace moveit_setup_assistant
00047 {
00048
00049
00050
00051
00052
00053 const boost::unordered_map<DisabledReason, std::string> reasonsToString = boost::assign::map_list_of(NEVER, "Never")(
00054 DEFAULT, "Default")(ADJACENT, "Adjacent")(ALWAYS, "Always")(USER, "User")(NOT_DISABLED, "Not Disabled");
00055
00056 const boost::unordered_map<std::string, DisabledReason> reasonsFromString = boost::assign::map_list_of("Never", NEVER)(
00057 "Default", DEFAULT)("Adjacent", ADJACENT)("Always", ALWAYS)("User", USER)("Not Disabled", NOT_DISABLED);
00058
00059
00060 typedef std::set<std::pair<std::string, std::string> > StringPairSet;
00061
00062
00063 struct ThreadComputation
00064 {
00065 ThreadComputation(planning_scene::PlanningScene& scene, const collision_detection::CollisionRequest& req,
00066 int thread_id, int num_trials, StringPairSet* links_seen_colliding, boost::mutex* lock,
00067 unsigned int* progress)
00068 : scene_(scene)
00069 , req_(req)
00070 , thread_id_(thread_id)
00071 , num_trials_(num_trials)
00072 , links_seen_colliding_(links_seen_colliding)
00073 , lock_(lock)
00074 , progress_(progress)
00075 {
00076 }
00077 planning_scene::PlanningScene& scene_;
00078 const collision_detection::CollisionRequest& req_;
00079 int thread_id_;
00080 unsigned int num_trials_;
00081 StringPairSet* links_seen_colliding_;
00082 boost::mutex* lock_;
00083 unsigned int* progress_;
00084 };
00085
00086
00087 typedef std::map<const robot_model::LinkModel*, std::set<const robot_model::LinkModel*> > LinkGraph;
00088
00089
00090
00091
00092
00101 static bool setLinkPair(const std::string& linkA, const std::string& linkB, const DisabledReason reason,
00102 LinkPairMap& link_pairs);
00103
00109 static void computeConnectionGraph(const robot_model::LinkModel* link, LinkGraph& link_graph);
00110
00116 static void computeConnectionGraphRec(const robot_model::LinkModel* link, LinkGraph& link_graph);
00117
00125 static unsigned int disableAdjacentLinks(planning_scene::PlanningScene& scene, LinkGraph& link_graph,
00126 LinkPairMap& link_pairs);
00127
00135 static unsigned int disableDefaultCollisions(planning_scene::PlanningScene& scene, LinkPairMap& link_pairs,
00136 collision_detection::CollisionRequest& req);
00137
00148 static unsigned int disableAlwaysInCollision(planning_scene::PlanningScene& scene, LinkPairMap& link_pairs,
00149 collision_detection::CollisionRequest& req,
00150 StringPairSet& links_seen_colliding, double min_collision_faction = 0.95);
00151
00160 static unsigned int disableNeverInCollision(const unsigned int num_trials, planning_scene::PlanningScene& scene,
00161 LinkPairMap& link_pairs, const collision_detection::CollisionRequest& req,
00162 StringPairSet& links_seen_colliding, unsigned int* progress);
00163
00168 static void disableNeverInCollisionThread(ThreadComputation tc);
00169
00170
00171
00172
00173 LinkPairMap computeDefaultCollisions(const planning_scene::PlanningSceneConstPtr& parent_scene, unsigned int* progress,
00174 const bool include_never_colliding, const unsigned int num_trials,
00175 const double min_collision_fraction, const bool verbose)
00176 {
00177
00178 planning_scene::PlanningScenePtr scene = parent_scene->diff();
00179
00180
00181 LinkPairMap link_pairs;
00182
00183
00184 StringPairSet links_seen_colliding;
00185
00186
00187 LinkGraph link_graph;
00188
00189
00190
00191
00192
00193
00194 computeLinkPairs(*scene, link_pairs);
00195 *progress = 1;
00196
00197
00198
00199
00200
00201
00202 computeConnectionGraph(scene->getRobotModel()->getRootLink(), link_graph);
00203 *progress = 2;
00204
00205
00206
00207 unsigned int num_adjacent = disableAdjacentLinks(*scene, link_graph, link_pairs);
00208 *progress = 4;
00209
00210
00211
00212 collision_detection::CollisionRequest req;
00213 req.contacts = true;
00214
00215 req.max_contacts = int(link_graph.size());
00216 req.max_contacts_per_pair = 1;
00217 req.verbose = false;
00218
00219
00220
00221 unsigned int num_default = disableDefaultCollisions(*scene, link_pairs, req);
00222 *progress = 6;
00223
00224
00225
00226 unsigned int num_always =
00227 disableAlwaysInCollision(*scene, link_pairs, req, links_seen_colliding, min_collision_fraction);
00228
00229 *progress = 8;
00230
00231
00232
00233 unsigned int num_never = 0;
00234 if (include_never_colliding)
00235 {
00236 num_never = disableNeverInCollision(num_trials, *scene, link_pairs, req, links_seen_colliding, progress);
00237 }
00238
00239
00240
00241 if (verbose)
00242 {
00243
00244 unsigned int num_disabled = 0;
00245 for (LinkPairMap::const_iterator pair_it = link_pairs.begin(); pair_it != link_pairs.end(); ++pair_it)
00246 {
00247 if (pair_it->second.disable_check)
00248 ++num_disabled;
00249 }
00250
00251 ROS_INFO("-------------------------------------------------------------------------------");
00252 ROS_INFO("Statistics:");
00253 unsigned int num_links = int(link_graph.size());
00254 double num_possible = boost::math::binomial_coefficient<double>(num_links, 2);
00255 unsigned int num_sometimes = num_possible - num_disabled;
00256
00257 ROS_INFO("%6d : %s", num_links, "Total Links");
00258 ROS_INFO("%6.0f : %s", num_possible, "Total possible collisions");
00259 ROS_INFO("%6d : %s", num_always, "Always in collision");
00260 ROS_INFO("%6d : %s", num_never, "Never in collision");
00261 ROS_INFO("%6d : %s", num_default, "Default in collision");
00262 ROS_INFO("%6d : %s", num_adjacent, "Adjacent links disabled");
00263 ROS_INFO("%6d : %s", num_sometimes, "Sometimes in collision");
00264 ROS_INFO("%6d : %s", num_disabled, "TOTAL DISABLED");
00265
00266
00267
00268
00269
00270
00271 }
00272
00273 *progress = 100;
00274
00275 return link_pairs;
00276 }
00277
00278
00279
00280
00281 bool setLinkPair(const std::string& linkA, const std::string& linkB, const DisabledReason reason,
00282 LinkPairMap& link_pairs)
00283 {
00284 bool isUnique = false;
00285
00286
00287 std::pair<std::string, std::string> link_pair;
00288
00289
00290 if (linkA < linkB)
00291 {
00292 link_pair = std::pair<std::string, std::string>(linkA, linkB);
00293 }
00294 else
00295 {
00296 link_pair = std::pair<std::string, std::string>(linkB, linkA);
00297 }
00298
00299
00300 LinkPairData* link_pair_ptr = &link_pairs[link_pair];
00301
00302
00303 if (link_pairs[link_pair].disable_check == false)
00304 {
00305 isUnique = true;
00306 link_pair_ptr->reason = reason;
00307 }
00308
00309
00310 link_pair_ptr->disable_check = (reason != NOT_DISABLED);
00311
00312 return isUnique;
00313 }
00314
00315
00316
00317
00318 void computeLinkPairs(const planning_scene::PlanningScene& scene, LinkPairMap& link_pairs)
00319 {
00320
00321 const std::vector<std::string>& names = scene.getRobotModel()->getLinkModelNamesWithCollisionGeometry();
00322
00323 std::pair<std::string, std::string> temp_pair;
00324
00325
00326 for (std::size_t i = 0; i < names.size(); ++i)
00327 {
00328 for (std::size_t j = i + 1; j < names.size(); ++j)
00329 {
00330
00331 setLinkPair(names[i], names[j], NOT_DISABLED, link_pairs);
00332 }
00333 }
00334 }
00335
00336
00337
00338 void computeConnectionGraph(const robot_model::LinkModel* start_link, LinkGraph& link_graph)
00339 {
00340 link_graph.clear();
00341
00342
00343 computeConnectionGraphRec(start_link, link_graph);
00344
00345
00346 bool update = true;
00347 while (update)
00348 {
00349 update = false;
00350
00351
00352 for (LinkGraph::const_iterator edge_it = link_graph.begin(); edge_it != link_graph.end(); ++edge_it)
00353 {
00354 if (edge_it->first->getShapes().empty())
00355 {
00356
00357 std::vector<const robot_model::LinkModel*> temp_list;
00358
00359
00360 for (std::set<const robot_model::LinkModel*>::const_iterator adj_it = edge_it->second.begin();
00361 adj_it != edge_it->second.end(); ++adj_it)
00362 {
00363 temp_list.push_back(*adj_it);
00364 }
00365
00366
00367
00368 for (std::size_t i = 0; i < temp_list.size(); ++i)
00369 {
00370 for (std::size_t j = i + 1; j < temp_list.size(); ++j)
00371 {
00372
00373
00374
00375 if (link_graph[temp_list[i]].insert(temp_list[j]).second)
00376 update = true;
00377 if (link_graph[temp_list[j]].insert(temp_list[i]).second)
00378 update = true;
00379 }
00380 }
00381 }
00382 }
00383 }
00384
00385 }
00386
00387
00388
00389
00390 void computeConnectionGraphRec(const robot_model::LinkModel* start_link, LinkGraph& link_graph)
00391 {
00392 if (start_link)
00393 {
00394
00395 for (std::size_t i = 0; i < start_link->getChildJointModels().size(); ++i)
00396 {
00397 const robot_model::LinkModel* next = start_link->getChildJointModels()[i]->getChildLinkModel();
00398
00399
00400 link_graph[next].insert(start_link);
00401 link_graph[start_link].insert(next);
00402
00403
00404 computeConnectionGraphRec(next, link_graph);
00405 }
00406 }
00407 else
00408 {
00409 ROS_ERROR("Joint exists in URDF with no link!");
00410 }
00411 }
00412
00413
00414
00415
00416 unsigned int disableAdjacentLinks(planning_scene::PlanningScene& scene, LinkGraph& link_graph, LinkPairMap& link_pairs)
00417 {
00418 int num_disabled = 0;
00419 for (LinkGraph::const_iterator link_graph_it = link_graph.begin(); link_graph_it != link_graph.end(); ++link_graph_it)
00420 {
00421
00422 for (std::set<const robot_model::LinkModel*>::const_iterator adj_it = link_graph_it->second.begin();
00423 adj_it != link_graph_it->second.end(); ++adj_it)
00424 {
00425
00426
00427
00428 if (!link_graph_it->first->getShapes().empty() && !(*adj_it)->getShapes().empty())
00429 {
00430 num_disabled += setLinkPair(link_graph_it->first->getName(), (*adj_it)->getName(), ADJACENT, link_pairs);
00431
00432
00433 scene.getAllowedCollisionMatrixNonConst().setEntry(link_graph_it->first->getName(), (*adj_it)->getName(), true);
00434 }
00435 }
00436 }
00437
00438
00439 return num_disabled;
00440 }
00441
00442
00443
00444
00445 unsigned int disableDefaultCollisions(planning_scene::PlanningScene& scene, LinkPairMap& link_pairs,
00446 collision_detection::CollisionRequest& req)
00447 {
00448
00449 collision_detection::CollisionResult res;
00450 scene.getCurrentStateNonConst().setToDefaultValues();
00451
00452 scene.checkSelfCollision(req, res);
00453
00454
00455 int num_disabled = 0;
00456 for (collision_detection::CollisionResult::ContactMap::const_iterator it = res.contacts.begin();
00457 it != res.contacts.end(); ++it)
00458 {
00459 num_disabled += setLinkPair(it->first.first, it->first.second, DEFAULT, link_pairs);
00460
00461
00462 scene.getAllowedCollisionMatrixNonConst().setEntry(it->first.first, it->first.second, true);
00463 }
00464
00465
00466
00467 return num_disabled;
00468 }
00469
00470
00471
00472
00473 unsigned int disableAlwaysInCollision(planning_scene::PlanningScene& scene, LinkPairMap& link_pairs,
00474 collision_detection::CollisionRequest& req, StringPairSet& links_seen_colliding,
00475 double min_collision_faction)
00476 {
00477
00478 static const unsigned int small_trial_count = 200;
00479 static const unsigned int small_trial_limit = (unsigned int)((double)small_trial_count * min_collision_faction);
00480
00481 bool done = false;
00482 unsigned int num_disabled = 0;
00483
00484 while (!done)
00485 {
00486
00487 std::map<std::pair<std::string, std::string>, unsigned int> collision_count;
00488
00489
00490 for (unsigned int i = 0; i < small_trial_count; ++i)
00491 {
00492
00493 collision_detection::CollisionResult res;
00494 scene.getCurrentStateNonConst().setToRandomPositions();
00495 scene.checkSelfCollision(req, res);
00496
00497
00498 unsigned int nc = 0;
00499 for (collision_detection::CollisionResult::ContactMap::const_iterator it = res.contacts.begin();
00500 it != res.contacts.end(); ++it)
00501 {
00502 collision_count[it->first]++;
00503 links_seen_colliding.insert(it->first);
00504 nc += it->second.size();
00505 }
00506
00507
00508 if (nc >= req.max_contacts)
00509 {
00510 req.max_contacts *= 2;
00511
00512 }
00513 }
00514
00515
00516
00517 int found = 0;
00518
00519
00520 for (std::map<std::pair<std::string, std::string>, unsigned int>::const_iterator it = collision_count.begin();
00521 it != collision_count.end(); ++it)
00522 {
00523
00524 if (it->second > small_trial_limit)
00525 {
00526 num_disabled += setLinkPair(it->first.first, it->first.second, ALWAYS, link_pairs);
00527
00528
00529 scene.getAllowedCollisionMatrixNonConst().setEntry(it->first.first, it->first.second, true);
00530
00531 found++;
00532 }
00533 }
00534
00535
00536 if (found == 0)
00537 done = true;
00538
00539
00540 }
00541
00542 return num_disabled;
00543 }
00544
00545
00546
00547
00548 unsigned int disableNeverInCollision(const unsigned int num_trials, planning_scene::PlanningScene& scene,
00549 LinkPairMap& link_pairs, const collision_detection::CollisionRequest& req,
00550 StringPairSet& links_seen_colliding, unsigned int* progress)
00551 {
00552 unsigned int num_disabled = 0;
00553
00554 boost::thread_group bgroup;
00555 boost::mutex lock;
00556
00557 int num_threads = boost::thread::hardware_concurrency();
00558
00559
00560
00561 for (int i = 0; i < num_threads; ++i)
00562 {
00563 ThreadComputation tc(scene, req, i, num_trials / num_threads, &links_seen_colliding, &lock, progress);
00564 bgroup.create_thread(boost::bind(&disableNeverInCollisionThread, tc));
00565 }
00566
00567 bgroup.join_all();
00568
00569
00570 for (LinkPairMap::iterator pair_it = link_pairs.begin(); pair_it != link_pairs.end(); ++pair_it)
00571 {
00572 if (!pair_it->second.disable_check)
00573 {
00574
00575
00576 if (links_seen_colliding.find(pair_it->first) == links_seen_colliding.end())
00577 {
00578
00579 pair_it->second.reason = NEVER;
00580 pair_it->second.disable_check = true;
00581
00582
00583 ++num_disabled;
00584 }
00585 }
00586 }
00587
00588
00589 return num_disabled;
00590 }
00591
00592
00593
00594
00595 void disableNeverInCollisionThread(ThreadComputation tc)
00596 {
00597
00598
00599
00600 const unsigned int progress_interval = tc.num_trials_ / 20;
00601
00602
00603 robot_state::RobotState kstate(tc.scene_.getRobotModel());
00604
00605
00606 for (unsigned int i = 0; i < tc.num_trials_; ++i)
00607 {
00608
00609 if (i % progress_interval == 0 && tc.thread_id_ == 0)
00610 {
00611
00612 (*tc.progress_) = i * 92 / tc.num_trials_ + 8;
00613 }
00614
00615 collision_detection::CollisionResult res;
00616 kstate.setToRandomPositions();
00617 tc.scene_.checkSelfCollision(tc.req_, res, kstate);
00618
00619
00620 for (collision_detection::CollisionResult::ContactMap::const_iterator it = res.contacts.begin();
00621 it != res.contacts.end(); ++it)
00622 {
00623
00624 if (tc.links_seen_colliding_->find(it->first) == tc.links_seen_colliding_->end())
00625 {
00626
00627
00628 boost::mutex::scoped_lock slock(*tc.lock_);
00629 tc.links_seen_colliding_->insert(it->first);
00630
00631 tc.scene_.getAllowedCollisionMatrixNonConst().setEntry(it->first.first, it->first.second,
00632 true);
00633 }
00634 }
00635 }
00636 }
00637
00638
00639
00640
00641 const std::string disabledReasonToString(DisabledReason reason)
00642 {
00643 return reasonsToString.at(reason);
00644 }
00645
00646
00647
00648
00649 DisabledReason disabledReasonFromString(const std::string& reason)
00650 {
00651 DisabledReason r;
00652 try
00653 {
00654 r = reasonsFromString.at(reason);
00655 }
00656 catch (std::out_of_range)
00657 {
00658 r = USER;
00659 }
00660
00661 return r;
00662 }
00663
00664 }