38 #include <boost/math/special_functions/binomial.hpp> 39 #include <boost/thread.hpp> 40 #include <boost/lexical_cast.hpp> 41 #include <boost/unordered_map.hpp> 42 #include <boost/assign.hpp> 52 const boost::unordered_map<DisabledReason, std::string>
reasonsToString = boost::assign::map_list_of(
NEVER,
"Never")(
55 const boost::unordered_map<std::string, DisabledReason>
reasonsFromString = boost::assign::map_list_of(
"Never",
NEVER)(
65 int thread_id,
int num_trials, StringPairSet* links_seen_colliding, boost::mutex* lock,
66 unsigned int* progress)
86 typedef std::map<const robot_model::LinkModel*, std::set<const robot_model::LinkModel*> >
LinkGraph;
149 StringPairSet& links_seen_colliding,
double min_collision_faction = 0.95);
161 StringPairSet& links_seen_colliding,
unsigned int* progress);
173 const bool include_never_colliding,
const unsigned int num_trials,
174 const double min_collision_fraction,
const bool verbose)
177 planning_scene::PlanningScenePtr scene = parent_scene->diff();
183 StringPairSet links_seen_colliding;
186 LinkGraph link_graph;
203 boost::this_thread::interruption_point();
209 boost::this_thread::interruption_point();
224 boost::this_thread::interruption_point();
228 unsigned int num_always =
232 boost::this_thread::interruption_point();
236 unsigned int num_never = 0;
237 if (include_never_colliding)
247 unsigned int num_disabled = 0;
248 for (LinkPairMap::const_iterator pair_it = link_pairs.begin(); pair_it != link_pairs.end(); ++pair_it)
250 if (pair_it->second.disable_check)
254 ROS_INFO(
"-------------------------------------------------------------------------------");
256 unsigned int num_links = int(link_graph.size());
257 double num_possible = boost::math::binomial_coefficient<double>(num_links, 2);
258 unsigned int num_sometimes = num_possible - num_disabled;
260 ROS_INFO(
"%6d : %s", num_links,
"Total Links");
261 ROS_INFO(
"%6.0f : %s", num_possible,
"Total possible collisions");
262 ROS_INFO(
"%6d : %s", num_always,
"Always in collision");
263 ROS_INFO(
"%6d : %s", num_never,
"Never in collision");
264 ROS_INFO(
"%6d : %s", num_default,
"Default in collision");
265 ROS_INFO(
"%6d : %s", num_adjacent,
"Adjacent links disabled");
266 ROS_INFO(
"%6d : %s", num_sometimes,
"Sometimes in collision");
267 ROS_INFO(
"%6d : %s", num_disabled,
"TOTAL DISABLED");
287 bool isUnique =
false;
290 std::pair<std::string, std::string> link_pair;
295 link_pair = std::pair<std::string, std::string>(linkA, linkB);
299 link_pair = std::pair<std::string, std::string>(linkB, linkA);
306 if (link_pairs[link_pair].disable_check ==
false)
309 link_pair_ptr->
reason = reason;
313 link_pair_ptr->disable_check = (reason !=
NOT_DISABLED);
324 const std::vector<std::string>& names = scene.
getRobotModel()->getLinkModelNamesWithCollisionGeometry();
326 std::pair<std::string, std::string> temp_pair;
329 for (std::size_t i = 0; i < names.size(); ++i)
331 for (std::size_t j = i + 1; j < names.size(); ++j)
355 for (LinkGraph::const_iterator edge_it = link_graph.begin(); edge_it != link_graph.end(); ++edge_it)
357 if (edge_it->first->getShapes().empty())
360 std::vector<const robot_model::LinkModel*> temp_list;
363 for (std::set<const robot_model::LinkModel*>::const_iterator adj_it = edge_it->second.begin();
364 adj_it != edge_it->second.end(); ++adj_it)
366 temp_list.push_back(*adj_it);
371 for (std::size_t i = 0; i < temp_list.size(); ++i)
373 for (std::size_t j = i + 1; j < temp_list.size(); ++j)
378 if (link_graph[temp_list[i]].insert(temp_list[j]).second)
380 if (link_graph[temp_list[j]].insert(temp_list[i]).second)
398 for (std::size_t i = 0; i < start_link->getChildJointModels().size(); ++i)
400 const robot_model::LinkModel* next = start_link->getChildJointModels()[i]->getChildLinkModel();
403 link_graph[next].insert(start_link);
404 link_graph[start_link].insert(next);
412 ROS_ERROR(
"Joint exists in URDF with no link!");
421 int num_disabled = 0;
422 for (LinkGraph::const_iterator link_graph_it = link_graph.begin(); link_graph_it != link_graph.end(); ++link_graph_it)
425 for (std::set<const robot_model::LinkModel*>::const_iterator adj_it = link_graph_it->second.begin();
426 adj_it != link_graph_it->second.end(); ++adj_it)
431 if (!link_graph_it->first->getShapes().empty() && !(*adj_it)->getShapes().empty())
433 num_disabled +=
setLinkPair(link_graph_it->first->getName(), (*adj_it)->getName(),
ADJACENT, link_pairs);
458 int num_disabled = 0;
459 for (collision_detection::CollisionResult::ContactMap::const_iterator it = res.
contacts.begin();
478 double min_collision_faction)
481 static const unsigned int small_trial_count = 200;
482 static const unsigned int small_trial_limit = (
unsigned int)((
double)small_trial_count * min_collision_faction);
485 unsigned int num_disabled = 0;
490 std::map<std::pair<std::string, std::string>,
unsigned int> collision_count;
493 for (
unsigned int i = 0; i < small_trial_count; ++i)
502 for (collision_detection::CollisionResult::ContactMap::const_iterator it = res.
contacts.begin();
505 collision_count[it->first]++;
506 links_seen_colliding.insert(it->first);
507 nc += it->second.size();
523 for (std::map<std::pair<std::string, std::string>,
unsigned int>::const_iterator it = collision_count.begin();
524 it != collision_count.end(); ++it)
527 if (it->second > small_trial_limit)
529 num_disabled +=
setLinkPair(it->first.first, it->first.second,
ALWAYS, link_pairs);
553 StringPairSet& links_seen_colliding,
unsigned int* progress)
555 unsigned int num_disabled = 0;
557 boost::thread_group bgroup;
560 int num_threads = boost::thread::hardware_concurrency();
564 for (
int i = 0; i < num_threads; ++i)
566 ThreadComputation tc(scene, req, i, num_trials / num_threads, &links_seen_colliding, &lock, progress);
574 catch (boost::thread_interrupted)
576 ROS_WARN(
"disableNeverInCollision interrupted");
577 bgroup.interrupt_all();
583 for (LinkPairMap::iterator pair_it = link_pairs.begin(); pair_it != link_pairs.end(); ++pair_it)
585 if (!pair_it->second.disable_check)
589 if (links_seen_colliding.find(pair_it->first) == links_seen_colliding.end())
592 pair_it->second.reason =
NEVER;
593 pair_it->second.disable_check =
true;
613 const unsigned int progress_interval = tc.
num_trials_ / 20;
621 boost::this_thread::interruption_point();
624 if (i % progress_interval == 0 && tc.
thread_id_ == 0)
630 kstate.setToRandomPositions();
634 for (collision_detection::CollisionResult::ContactMap::const_iterator it = res.
contacts.begin();
642 boost::mutex::scoped_lock slock(*tc.
lock_);
657 return reasonsToString.at(reason);
668 r = reasonsFromString.at(reason);
670 catch (std::out_of_range)
const boost::unordered_map< std::string, DisabledReason > reasonsFromString
robot_state::RobotState & getCurrentStateNonConst()
Store details on a pair of links.
static unsigned int disableDefaultCollisions(planning_scene::PlanningScene &scene, LinkPairMap &link_pairs, collision_detection::CollisionRequest &req)
Disable all collision checks that occur when the robot is started in its default state.
static unsigned int disableNeverInCollision(const unsigned int num_trials, planning_scene::PlanningScene &scene, LinkPairMap &link_pairs, const collision_detection::CollisionRequest &req, StringPairSet &links_seen_colliding, unsigned int *progress)
Get the pairs of links that are never in collision.
void checkSelfCollision(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res)
static unsigned int disableAlwaysInCollision(planning_scene::PlanningScene &scene, LinkPairMap &link_pairs, collision_detection::CollisionRequest &req, StringPairSet &links_seen_colliding, double min_collision_faction=0.95)
Compute the links that are always in collision.
const collision_detection::CollisionRequest & req_
static void computeConnectionGraph(const robot_model::LinkModel *link, LinkGraph &link_graph)
Build the robot links connection graph and then check for links with no geomotry. ...
ThreadComputation(planning_scene::PlanningScene &scene, const collision_detection::CollisionRequest &req, int thread_id, int num_trials, StringPairSet *links_seen_colliding, boost::mutex *lock, unsigned int *progress)
static bool setLinkPair(const std::string &linkA, const std::string &linkB, const DisabledReason reason, LinkPairMap &link_pairs)
Helper function for adding two links to the disabled links data structure.
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
planning_scene::PlanningScene & scene_
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. n choose 2 pairs.
std::map< const robot_model::LinkModel *, std::set< const robot_model::LinkModel * > > LinkGraph
const robot_model::RobotModelConstPtr & getRobotModel() const
const std::string disabledReasonToString(DisabledReason reason)
Converts a reason for disabling a link pair into a string.
static void computeConnectionGraphRec(const robot_model::LinkModel *link, LinkGraph &link_graph)
Recursively build the adj list of link connections.
StringPairSet * links_seen_colliding_
static unsigned int disableAdjacentLinks(planning_scene::PlanningScene &scene, LinkGraph &link_graph, LinkPairMap &link_pairs)
Disable collision checking for adjacent links, or adjacent with no geometry links between them...
collision_detection::AllowedCollisionMatrix & getAllowedCollisionMatrixNonConst()
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
std::size_t max_contacts_per_pair
void setEntry(const std::string &name1, const std::string &name2, bool allowed)
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...
static void disableNeverInCollisionThread(ThreadComputation tc)
Thread for getting the pairs of links that are never in collision.
const boost::unordered_map< DisabledReason, std::string > reasonsToString
DisabledReason disabledReasonFromString(const std::string &reason)
Converts a string reason for disabling a link pair into a struct data type.
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...