compute_default_collisions.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2012, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Dave Coleman */
00036 
00037 #include <moveit/setup_assistant/tools/compute_default_collisions.h>
00038 #include <boost/math/special_functions/binomial.hpp>  // for statistics at end
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 // Custom Types, Enums and Structs
00050 // ******************************************************************************************
00051 
00052 // Boost mapping of reasons for disabling a link pair to strings
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 // Unique set of pairs of links in string-based form
00060 typedef std::set<std::pair<std::string, std::string> > StringPairSet;
00061 
00062 // Struct for passing parameters to threads, for cleaner code
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_;  // only to be updated by thread 0
00084 };
00085 
00086 // LinkGraph defines a Link's model and a set of unique links it connects
00087 typedef std::map<const robot_model::LinkModel*, std::set<const robot_model::LinkModel*> > LinkGraph;
00088 
00089 // ******************************************************************************************
00090 // Static Prototypes
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 // Generates an adjacency list of links that are always and never in collision, to speed up collision detection
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   // Create new instance of planning scene using pointer
00178   planning_scene::PlanningScenePtr scene = parent_scene->diff();
00179 
00180   // Map of disabled collisions that contains a link as a key and an ordered list of links that are connected.
00181   LinkPairMap link_pairs;
00182 
00183   // Track unique edges that have been found to be in collision in some state
00184   StringPairSet links_seen_colliding;
00185 
00186   // LinkGraph is a custom type of a map with a LinkModel as key and a set of LinkModels as second
00187   LinkGraph link_graph;
00188 
00189   // ROS_INFO_STREAM("Initial allowed Collision Matrix Size = " << scene.getAllowedCollisions().getSize() );
00190 
00191   // 0. GENERATE ALL POSSIBLE LINK PAIRS -------------------------------------------------------------
00192   // Generate a list of unique link pairs for all links with geometry. Order pairs alphabetically.
00193   // There should be n choose 2 pairs
00194   computeLinkPairs(*scene, link_pairs);
00195   *progress = 1;
00196 
00197   // 1. FIND CONNECTING LINKS ------------------------------------------------------------------------
00198   // For each link, compute the set of other links it connects to via a single joint (adjacent links)
00199   // or via a chain of joints with intermediate links with no geometry (like a socket joint)
00200 
00201   // Create Connection Graph
00202   computeConnectionGraph(scene->getRobotModel()->getRootLink(), link_graph);
00203   *progress = 2;  // Progress bar feedback
00204 
00205   // 2. DISABLE ALL ADJACENT LINK COLLISIONS ---------------------------------------------------------
00206   // if 2 links are adjacent, or adjacent with a zero-shape between them, disable collision checking for them
00207   unsigned int num_adjacent = disableAdjacentLinks(*scene, link_graph, link_pairs);
00208   *progress = 4;  // Progress bar feedback
00209 
00210   // 3. INITIAL CONTACTS TO CONSIDER GUESS -----------------------------------------------------------
00211   // Create collision detection request object
00212   collision_detection::CollisionRequest req;
00213   req.contacts = true;
00214   // max number of contacts to compute. initial guess is number of links on robot
00215   req.max_contacts = int(link_graph.size());
00216   req.max_contacts_per_pair = 1;
00217   req.verbose = false;
00218 
00219   // 4. DISABLE "DEFAULT" COLLISIONS --------------------------------------------------------
00220   // Disable all collision checks that occur when the robot is started in its default state
00221   unsigned int num_default = disableDefaultCollisions(*scene, link_pairs, req);
00222   *progress = 6;  // Progress bar feedback
00223 
00224   // 5. ALWAYS IN COLLISION --------------------------------------------------------------------
00225   // Compute the links that are always in collision
00226   unsigned int num_always =
00227       disableAlwaysInCollision(*scene, link_pairs, req, links_seen_colliding, min_collision_fraction);
00228   // ROS_INFO("Links seen colliding total = %d", int(links_seen_colliding.size()));
00229   *progress = 8;  // Progress bar feedback
00230 
00231   // 6. NEVER IN COLLISION -------------------------------------------------------------------
00232   // Get the pairs of links that are never in collision
00233   unsigned int num_never = 0;
00234   if (include_never_colliding)  // option of function
00235   {
00236     num_never = disableNeverInCollision(num_trials, *scene, link_pairs, req, links_seen_colliding, progress);
00237   }
00238 
00239   // ROS_INFO("Link pairs seen colliding ever: %d", int(links_seen_colliding.size()));
00240 
00241   if (verbose)
00242   {
00243     // Calculate number of disabled links:
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)  // has a reason to be disabled
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);  // n choose 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     /*ROS_INFO("Copy to Spreadsheet:");
00267     ROS_INFO_STREAM(num_links << "\t" << num_possible << "\t" << num_always << "\t" << num_never
00268                     << "\t" << num_default << "\t" << num_adjacent << "\t" << num_sometimes
00269                     << "\t" << num_disabled);
00270     */
00271   }
00272 
00273   *progress = 100;  // end the status bar
00274 
00275   return link_pairs;
00276 }
00277 
00278 // ******************************************************************************************
00279 // Helper function for adding two links to the disabled links data structure
00280 // ******************************************************************************************
00281 bool setLinkPair(const std::string& linkA, const std::string& linkB, const DisabledReason reason,
00282                  LinkPairMap& link_pairs)
00283 {
00284   bool isUnique = false;  // determine if this link pair had already existsed in the link_pairs datastructure
00285 
00286   // Determine order of the 2 links in the pair
00287   std::pair<std::string, std::string> link_pair;
00288 
00289   // compare the string names of the two links and add the lesser alphabetically, s.t. the pair is only added once
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   // Update properties of this link pair using only 1 search
00300   LinkPairData* link_pair_ptr = &link_pairs[link_pair];
00301 
00302   // Check if link pair was already disabled. It also creates the entry if none existed
00303   if (link_pairs[link_pair].disable_check == false)  // it was not previously disabled
00304   {
00305     isUnique = true;
00306     link_pair_ptr->reason = reason;  // only change the reason if the pair was previously enabled
00307   }
00308 
00309   // Only disable collision checking if there is a reason to disable it. This func is also used for initializing pairs
00310   link_pair_ptr->disable_check = (reason != NOT_DISABLED);
00311 
00312   return isUnique;
00313 }
00314 
00315 // ******************************************************************************************
00316 // Generate a list of unique link pairs for all links with geometry. Order pairs alphabetically. n choose 2 pairs
00317 // ******************************************************************************************
00318 void computeLinkPairs(const planning_scene::PlanningScene& scene, LinkPairMap& link_pairs)
00319 {
00320   // Get the names of the link models that have some collision geometry associated to themselves
00321   const std::vector<std::string>& names = scene.getRobotModel()->getLinkModelNamesWithCollisionGeometry();
00322 
00323   std::pair<std::string, std::string> temp_pair;
00324 
00325   // Loop through every combination of name pairs, AB and BA, n^2
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       // Add to link pairs list
00331       setLinkPair(names[i], names[j], NOT_DISABLED, link_pairs);
00332     }
00333   }
00334 }
00335 // ******************************************************************************************
00336 // Build the robot links connection graph and then check for links with no geomotry
00337 // ******************************************************************************************
00338 void computeConnectionGraph(const robot_model::LinkModel* start_link, LinkGraph& link_graph)
00339 {
00340   link_graph.clear();  // make sure the edges structure is clear
00341 
00342   // Recurively build adj list of link connections
00343   computeConnectionGraphRec(start_link, link_graph);
00344 
00345   // Repeatidly check for links with no geometry and remove them, then re-check until no more removals are detected
00346   bool update = true;  // track if a no geometry link was found
00347   while (update)
00348   {
00349     update = false;  // default
00350 
00351     // Check if each edge has a shape
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())  // link in adjList "link_graph" does not have shape, remove!
00355       {
00356         // Temporary list for connected links
00357         std::vector<const robot_model::LinkModel*> temp_list;
00358 
00359         // Copy link's parent and child links to temp_list
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         // Make all preceeding and succeeding links to the no-shape link fully connected
00367         // so that they don't collision check with themselves
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             // for each LinkModel in temp_list, find its location in the link_graph structure and insert the rest
00373             // of the links into its unique set.
00374             // if the LinkModel is not already in the set, update is set to true so that we keep searching
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   // ROS_INFO("Generated connection graph with %d links", int(link_graph.size()));
00385 }
00386 
00387 // ******************************************************************************************
00388 // Recursively build the adj list of link connections
00389 // ******************************************************************************************
00390 void computeConnectionGraphRec(const robot_model::LinkModel* start_link, LinkGraph& link_graph)
00391 {
00392   if (start_link)  // check that the link is a valid pointer
00393   {
00394     // Loop through every link attached to start_link
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       // Bi-directional connection
00400       link_graph[next].insert(start_link);
00401       link_graph[start_link].insert(next);
00402 
00403       // Iterate with subsequent link
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 // Disable collision checking for adjacent links, or adjacent with no geometry links between them
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     // disable all connected links to current link by looping through them
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       // ROS_INFO("Disabled %s to %s", link_graph_it->first->getName().c_str(), (*adj_it)->getName().c_str() );
00426 
00427       // Check if either of the links have no geometry. If so, do not add (are we sure?)
00428       if (!link_graph_it->first->getShapes().empty() && !(*adj_it)->getShapes().empty())  // both links have geometry
00429       {
00430         num_disabled += setLinkPair(link_graph_it->first->getName(), (*adj_it)->getName(), ADJACENT, link_pairs);
00431 
00432         // disable link checking in the collision matrix
00433         scene.getAllowedCollisionMatrixNonConst().setEntry(link_graph_it->first->getName(), (*adj_it)->getName(), true);
00434       }
00435     }
00436   }
00437   // ROS_INFO("Disabled %d adjancent link pairs from collision checking", num_disabled);
00438 
00439   return num_disabled;
00440 }
00441 
00442 // ******************************************************************************************
00443 // Disable all collision checks that occur when the robot is started in its default state
00444 // ******************************************************************************************
00445 unsigned int disableDefaultCollisions(planning_scene::PlanningScene& scene, LinkPairMap& link_pairs,
00446                                       collision_detection::CollisionRequest& req)
00447 {
00448   // Setup environment
00449   collision_detection::CollisionResult res;
00450   scene.getCurrentStateNonConst().setToDefaultValues();  // set to default values of 0 OR half between low and high
00451                                                          // joint values
00452   scene.checkSelfCollision(req, res);
00453 
00454   // For each collision in default state, always add to disabled links set
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     // disable link checking in the collision matrix
00462     scene.getAllowedCollisionMatrixNonConst().setEntry(it->first.first, it->first.second, true);
00463   }
00464 
00465   // ROS_INFO("Disabled %d link pairs that are in collision in default state from collision checking", num_disabled);
00466 
00467   return num_disabled;
00468 }
00469 
00470 // ******************************************************************************************
00471 // Compute the links that are always in collision
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   // Trial count variables
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     // DO 'small_trial_count' COLLISION CHECKS AND RECORD STATISTICS ---------------------------------------
00487     std::map<std::pair<std::string, std::string>, unsigned int> collision_count;
00488 
00489     // Do a large number of tests
00490     for (unsigned int i = 0; i < small_trial_count; ++i)
00491     {
00492       // Check for collisions
00493       collision_detection::CollisionResult res;
00494       scene.getCurrentStateNonConst().setToRandomPositions();
00495       scene.checkSelfCollision(req, res);
00496 
00497       // Sum the number of collisions
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       // Check if the number of contacts is greater than the max count
00508       if (nc >= req.max_contacts)
00509       {
00510         req.max_contacts *= 2;  // double the max contacts that the CollisionRequest checks for
00511         // ROS_INFO("Doubling max_contacts to %d", int(req.max_contacts));
00512       }
00513     }
00514 
00515     // >= XX% OF TIME IN COLLISION DISABLE -----------------------------------------------------
00516     // Disable collision checking for links that are >= XX% of the time in collision (XX% = 95% by default)
00517     int found = 0;
00518 
00519     // Loop through every pair of link collisions and disable if it meets the threshold
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       // Disable these two links permanently
00524       if (it->second > small_trial_limit)
00525       {
00526         num_disabled += setLinkPair(it->first.first, it->first.second, ALWAYS, link_pairs);
00527 
00528         // disable link checking in the collision matrix
00529         scene.getAllowedCollisionMatrixNonConst().setEntry(it->first.first, it->first.second, true);
00530 
00531         found++;
00532       }
00533     }
00534 
00535     // if no updates were made to the collision matrix, we stop
00536     if (found == 0)
00537       done = true;
00538 
00539     // ROS_INFO("Disabled %u link pairs that are always in collision from collision checking", found);
00540   }
00541 
00542   return num_disabled;
00543 }
00544 
00545 // ******************************************************************************************
00546 // Get the pairs of links that are never in collision
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;  // create a group of threads
00555   boost::mutex lock;           // used for sharing the same data structures
00556 
00557   int num_threads = boost::thread::hardware_concurrency();  // how many cores does this computer have?
00558   // ROS_INFO_STREAM("Performing " << num_trials << " trials for 'always in collision' checking on " <<
00559   //   num_threads << " threads...");
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();  // wait for all threads to finish
00568 
00569   // Loop through every possible link pair and check if it has ever been seen in collision
00570   for (LinkPairMap::iterator pair_it = link_pairs.begin(); pair_it != link_pairs.end(); ++pair_it)
00571   {
00572     if (!pair_it->second.disable_check)  // is not disabled yet
00573     {
00574       // Check if current pair has been seen colliding ever. If it has never been seen colliding, add it to disabled
00575       // list
00576       if (links_seen_colliding.find(pair_it->first) == links_seen_colliding.end())
00577       {
00578         // Add to disabled list using pair ordering
00579         pair_it->second.reason = NEVER;
00580         pair_it->second.disable_check = true;
00581 
00582         // Count it
00583         ++num_disabled;
00584       }
00585     }
00586   }
00587   // ROS_INFO("Disabled %d link pairs that are never in collision", num_disabled);
00588 
00589   return num_disabled;
00590 }
00591 
00592 // ******************************************************************************************
00593 // Thread for getting the pairs of links that are never in collision
00594 // ******************************************************************************************
00595 void disableNeverInCollisionThread(ThreadComputation tc)
00596 {
00597   // ROS_INFO_STREAM("Thread " << tc.thread_id_ << " running " << tc.num_trials_ << " trials");
00598 
00599   // User feedback vars
00600   const unsigned int progress_interval = tc.num_trials_ / 20;  // show progress update every 5%
00601 
00602   // Create a new kinematic state for this thread to work on
00603   robot_state::RobotState kstate(tc.scene_.getRobotModel());
00604 
00605   // Do a large number of tests
00606   for (unsigned int i = 0; i < tc.num_trials_; ++i)
00607   {
00608     // Status update at intervals and only for 0 thread
00609     if (i % progress_interval == 0 && tc.thread_id_ == 0)
00610     {
00611       // ROS_INFO("Collision checking %d%% complete", int(i * 100 / tc.num_trials_ ));
00612       (*tc.progress_) = i * 92 / tc.num_trials_ + 8;  // 8 is the amount of progress already completed in prev steps
00613     }
00614 
00615     collision_detection::CollisionResult res;
00616     kstate.setToRandomPositions();
00617     tc.scene_.checkSelfCollision(tc.req_, res, kstate);
00618 
00619     // Check all contacts
00620     for (collision_detection::CollisionResult::ContactMap::const_iterator it = res.contacts.begin();
00621          it != res.contacts.end(); ++it)
00622     {
00623       // Check if this collision pair is unique before doing a thread lock
00624       if (tc.links_seen_colliding_->find(it->first) == tc.links_seen_colliding_->end())
00625       {
00626         // Collision Matrix and links_seen_colliding is modified only if needed, based on above if statement
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);  // disable link checking in the collision matrix
00633       }
00634     }
00635   }
00636 }
00637 
00638 // ******************************************************************************************
00639 // Converts a reason for disabling a link pair into a string
00640 // ******************************************************************************************
00641 const std::string disabledReasonToString(DisabledReason reason)
00642 {
00643   return reasonsToString.at(reason);
00644 }
00645 
00646 // ******************************************************************************************
00647 // Converts a string reason for disabling a link pair into a struct data type
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 }  // namespace


moveit_setup_assistant
Author(s): Dave Coleman
autogenerated on Mon Jul 24 2017 02:22:29