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
00038
00039
00040
00041
00042
00043 #include <float.h>
00044
00045 #include <ros/console.h>
00046 #include <explore/loop_closure.h>
00047 #include <visualization_msgs/Marker.h>
00048 #include <geometry_msgs/Point.h>
00049
00050 using namespace explore;
00051
00052 LoopClosure::LoopClosure(double addition_dist_min,
00053 double loop_dist_min,
00054 double loop_dist_max,
00055 double slam_entropy_max_,
00056 double graph_update_frequency,
00057 actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction>& move_base_client,
00058 costmap_2d::Costmap2DROS& costmap,
00059 boost::mutex& control_mutex) :
00060 curr_node_(NULL),
00061 addition_dist_min_(addition_dist_min),
00062 loop_dist_min_(loop_dist_min),
00063 loop_dist_max_(loop_dist_max),
00064 slam_entropy_max_(slam_entropy_max_),
00065 graph_update_frequency_(graph_update_frequency),
00066 move_base_client_(move_base_client),
00067 nh_(),
00068 marker_id_(0),
00069 costmap_(costmap),
00070 control_mutex_(control_mutex),
00071 planner_(NULL),
00072 slam_entropy_(0.0),
00073 slam_entropy_time_(ros::Time::now().toSec())
00074 {
00075 marker_publisher_ = nh_.advertise<visualization_msgs::MarkerArray>("visualization_marker_array",1);
00076 entropy_subscriber_ = nh_.subscribe("slam_entropy", 1, &LoopClosure::entropyCallback, this);
00077 planner_ = new navfn::NavfnROS(std::string("loop_closure_planner"), &costmap_);
00078 }
00079
00080 LoopClosure::~LoopClosure()
00081 {
00082 delete planner_;
00083 }
00084
00085 void
00086 LoopClosure::entropyCallback(const std_msgs::Float64::ConstPtr& entropy)
00087 {
00088 slam_entropy_ = entropy->data;
00089 slam_entropy_time_ = ros::Time::now().toSec();
00090 ROS_DEBUG("Entropy is: %f (%f)", slam_entropy_, slam_entropy_max_);
00091 }
00092
00093 void
00094 LoopClosure::updateGraph(const tf::Pose& pose)
00095 {
00096
00097 addNode(pose);
00098
00099 double time = ros::Time::now().toSec();
00100 if ((time - slam_entropy_time_) > 5.0f) {
00101 ROS_WARN("Entropy has not been updated. Loop closure opportunities may be ignored.");
00102 slam_entropy_time_ = time;
00103 }
00104
00105
00106 if(slam_entropy_ > 0.0 && slam_entropy_ > slam_entropy_max_)
00107 {
00108 ROS_DEBUG("Entropy is high enough (%.3f > %.3f); checking for loop closure opportunities",
00109 slam_entropy_, slam_entropy_max_);
00110 std::vector<GraphNode*> candidates;
00111 if(checkLoopClosure(pose, candidates))
00112 {
00113
00114 control_mutex_.lock();
00115
00116 ROS_INFO("Taking control of the robot for loop closure goals.");
00117
00118 double min_path_length = DBL_MAX;
00119 GraphNode* entry_point = candidates[0];
00120
00121
00122 for(unsigned int i = 0; i < candidates.size(); ++i){
00123 if(candidates[i]->path_length_ < min_path_length){
00124 entry_point = candidates[i];
00125 min_path_length = candidates[i]->path_length_;
00126 }
00127 }
00128
00129
00130
00131 GraphNode* curr_target = entry_point;
00132
00133
00134 GraphNode* connect_node = curr_node_;
00135
00136 move_base_msgs::MoveBaseGoal goal;
00137 goal.target_pose.header.frame_id = "map";
00138 goal.target_pose.header.stamp = ros::Time::now();
00139
00140
00141 do
00142 {
00143 ROS_INFO("Loop closure: Sending the robot to %.3f %.3f (%d)",
00144 curr_target->pose_.getOrigin().x(),
00145 curr_target->pose_.getOrigin().y(),
00146 curr_target->id_);
00147
00148 tf::poseTFToMsg(curr_target->pose_, goal.target_pose.pose);
00149 move_base_client_.sendGoal(goal);
00150 ros::Rate r(graph_update_frequency_);
00151
00152
00153 while(!move_base_client_.getState().isDone()){
00154
00155 tf::Stamped<tf::Pose> robot_pose;
00156 costmap_.getRobotPose(robot_pose);
00157
00158 addNode(robot_pose);
00159
00160
00161
00162 dijkstra(curr_node_->id_);
00163
00164
00165
00166 if(curr_target->dijkstra_d_ > loop_dist_max_){
00167 connect_node = curr_node_;
00168 }
00169
00170 visualizeGraph();
00171 r.sleep();
00172 }
00173
00174
00175
00176 curr_target = curr_target->next_;
00177 } while((curr_target != NULL) && (slam_entropy_ > entry_point->slam_entropy_));
00178
00179
00180 if(connect_node){
00181 graph_[connect_node->id_].push_back(entry_point->id_);
00182 graph_[entry_point->id_].push_back(connect_node->id_);
00183 ROS_INFO("Adding edge from connector node to entry point");
00184 }
00185
00186 control_mutex_.unlock();
00187 ROS_INFO("Entropy threshold satisfied (%.3f <= %.3f); loop closure terminated",
00188 slam_entropy_, entry_point->slam_entropy_);
00189 }
00190 }
00191
00192
00193 visualizeGraph();
00194 }
00195
00196 void
00197 LoopClosure::addNode(const tf::Pose& pose)
00198 {
00199 bool add = false;
00200
00201 if(curr_node_ == NULL)
00202 add = true;
00203 else
00204 {
00205 geometry_msgs::PoseStamped planner_start;
00206 geometry_msgs::Pose temp_pose;
00207 tf::poseTFToMsg(pose, temp_pose);
00208 planner_start.header.stamp = ros::Time::now();
00209 planner_start.header.frame_id = costmap_.getGlobalFrameID();
00210 planner_start.pose = temp_pose;
00211
00212
00213 planner_->computePotential(planner_start.pose.position);
00214
00215 add = true;
00216
00217
00218 double mind = DBL_MAX;
00219 GraphNode* closest_node = NULL;
00220 for(int i = nodes_.size() - 1; i >= 0; --i)
00221 {
00222 GraphNode* index_node = nodes_[i];
00223
00224
00225 geometry_msgs::PoseStamped planner_end;
00226
00227 tf::poseTFToMsg(index_node->pose_, temp_pose);
00228 planner_end.header.stamp = ros::Time::now();
00229 planner_end.header.frame_id = costmap_.getGlobalFrameID();
00230 planner_end.pose = temp_pose;
00231
00232
00233 std::vector<geometry_msgs::PoseStamped> plan;
00234 bool valid_plan = planner_->getPlanFromPotential(planner_end, plan) && !plan.empty();
00235
00236
00237 if(valid_plan){
00238 double path_length = 0.0;
00239
00240
00241 if(plan.size() > 1){
00242
00243
00244
00245 for(unsigned int j = 0; j < plan.size() - 1; ++j){
00246 double dist = distance(plan[j], plan[j + 1]);
00247 path_length += dist;
00248 }
00249
00250 if(path_length < mind){
00251 mind = path_length;
00252 closest_node = index_node;
00253
00254
00255
00256 curr_node_ = closest_node;
00257 }
00258 }
00259
00260 }
00261 }
00262 if(mind < addition_dist_min_)
00263 {
00264
00265 add = false;
00266
00267
00268
00269
00270
00271
00272
00273
00274
00275
00276
00277
00278
00279
00280
00281
00282
00283
00284
00285
00286
00287
00288
00289
00290
00291
00292
00293
00294
00295
00296
00297
00298
00299
00300
00301
00302
00303
00304
00305 curr_node_ = closest_node;
00306
00307
00308
00309 if(slam_entropy_ > 0.0)
00310 curr_node_->slam_entropy_ = slam_entropy_;
00311 }
00312 }
00313
00314 if(add)
00315 {
00316 ROS_INFO("Adding node at %.3f, %.3f", pose.getOrigin().x(), pose.getOrigin().y());
00317 GraphNode* n = new GraphNode(nodes_.size(), pose);
00318 nodes_.push_back(n);
00319
00320 std::vector<int> edges;
00321 graph_.push_back(edges);
00322
00323 if(curr_node_)
00324 {
00325
00326 graph_[curr_node_->id_].push_back(n->id_);
00327 graph_[n->id_].push_back(curr_node_->id_);
00328 curr_node_->next_ = n;
00329 }
00330 curr_node_ = n;
00331
00332
00333
00334 if(slam_entropy_ > 0.0)
00335 curr_node_->slam_entropy_ = slam_entropy_;
00336 }
00337 }
00338
00339 bool
00340 LoopClosure::checkLoopClosure(const tf::Pose& pose, std::vector<GraphNode*>& candidates)
00341 {
00342 bool ret = false;
00343
00344 if(curr_node_ == NULL || nodes_.size() < 2)
00345 return ret;
00346
00347
00348
00349 dijkstra(curr_node_->id_);
00350
00351
00352 geometry_msgs::Pose temp_pose;
00353 geometry_msgs::PoseStamped planner_start;
00354
00355 tf::poseTFToMsg(pose, temp_pose);
00356 planner_start.header.stamp = ros::Time::now();
00357 planner_start.header.frame_id = costmap_.getGlobalFrameID();
00358 planner_start.pose = temp_pose;
00359
00360 planner_->computePotential(planner_start.pose.position);
00361
00362
00363 costmap_2d::Costmap2D visibility_map;
00364 costmap_.getCostmapCopy(visibility_map);
00365
00366 for(std::vector<GraphNode*>::iterator it = nodes_.begin();
00367 it != nodes_.end();
00368 ++it)
00369 {
00370
00371 ROS_DEBUG("Checking %d (%.3f, %.3f)", (*it)->id_, (*it)->pose_.getOrigin().x(), (*it)->pose_.getOrigin().y());
00372 ROS_DEBUG("Graph distance is %.3f (threshold is %.3f)", (*it)->dijkstra_d_, loop_dist_max_);
00373
00374 if((*it)->dijkstra_d_ > loop_dist_max_)
00375 {
00376 ROS_DEBUG("graph dist check satisfied");
00377
00378 geometry_msgs::PoseStamped planner_end;
00379
00380 tf::poseTFToMsg((*it)->pose_, temp_pose);
00381 planner_end.header.stamp = ros::Time::now();
00382 planner_end.header.frame_id = costmap_.getGlobalFrameID();
00383 planner_end.pose = temp_pose;
00384
00385
00386 std::vector<geometry_msgs::PoseStamped> plan;
00387 bool valid_plan = planner_->getPlanFromPotential(planner_end, plan) && !plan.empty();
00388
00389
00390 if(valid_plan){
00391 double path_length = 0.0;
00392
00393
00394 if(plan.size() > 1){
00395
00396
00397
00398 for(unsigned int j = 0; j < plan.size() - 1; ++j){
00399 double dist = distance(plan[j], plan[j + 1]);
00400 path_length += dist;
00401 }
00402
00403 ROS_DEBUG("path_length: %.3f (threshold is %.3f)", path_length, loop_dist_min_);
00404 if(path_length < loop_dist_min_)
00405 {
00406
00407 bool is_visible = true;
00408 VisibilityChecker checker(visibility_map.getCharMap(), is_visible);
00409
00410
00411 bool in_bounds = true;
00412 unsigned int x0, y0;
00413 if(!visibility_map.worldToMap(pose.getOrigin().x(), pose.getOrigin().y(), x0, y0)){
00414 ROS_WARN("Attempting to check visibility from a point off the map... this should never happen");
00415 in_bounds = false;
00416 }
00417
00418 unsigned int x1, y1;
00419 if(!visibility_map.worldToMap((*it)->pose_.getOrigin().x(), (*it)->pose_.getOrigin().y(), x1, y1)){
00420 ROS_WARN("Attempting to check visibility to a point off the map... this should never happen");
00421 in_bounds = false;
00422 }
00423
00424 if(in_bounds){
00425
00426 raytraceLine(checker, x0, y0, x1, y1, visibility_map.getSizeInCellsX());
00427
00428
00429 if(is_visible){
00430
00431 (*it)->path_length_ = path_length;
00432
00433 candidates.push_back(*it);
00434 ROS_INFO("added loop closure candidate %d (%.3f, %.3f)",
00435 (*it)->id_, (*it)->pose_.getOrigin().x(), (*it)->pose_.getOrigin().y());
00436 ret = true;
00437 }
00438 }
00439 }
00440 }
00441 }
00442 }
00443 }
00444
00445 return ret;
00446 }
00447
00448
00449 void
00450 LoopClosure::dijkstra(int source)
00451 {
00452 std::list<GraphNode*> Q;
00453 for(std::vector<GraphNode*>::iterator it = nodes_.begin();
00454 it != nodes_.end();
00455 ++it)
00456 {
00457 if((*it)->id_ == source)
00458 (*it)->dijkstra_d_ = 0.0;
00459 else
00460 (*it)->dijkstra_d_ = DBL_MAX;
00461 Q.push_back(*it);
00462 }
00463 while(!Q.empty())
00464 {
00465 std::list<GraphNode*>::iterator it = Q.end();
00466 for(std::list<GraphNode*>::iterator iit = Q.begin();
00467 iit != Q.end();
00468 ++iit)
00469 {
00470 if((it == Q.end()) || ((*iit)->dijkstra_d_ < (*it)->dijkstra_d_))
00471 {
00472 it = iit;
00473 }
00474 }
00475 GraphNode* n = *it;
00476 if(n->dijkstra_d_ == DBL_MAX)
00477 break;
00478 Q.erase(it);
00479
00480 for(std::vector<int>::iterator git = graph_[n->id_].begin();
00481 git != graph_[n->id_].end();
00482 ++git)
00483 {
00484 GraphNode* nn = nodes_[*git];
00485 double d = (n->pose_.getOrigin() - nn->pose_.getOrigin()).length();
00486 double alt = n->dijkstra_d_ + d;
00487 if(alt < nn->dijkstra_d_)
00488 {
00489 nn->dijkstra_d_ = alt;
00490 }
00491 }
00492 }
00493 }
00494
00495 void LoopClosure::visualizeNode(const tf::Pose& pose, visualization_msgs::MarkerArray& markers)
00496 {
00497 visualization_msgs::Marker marker;
00498 marker.header.frame_id = "map";
00499 marker.header.stamp = ros::Time::now();
00500 marker.action = visualization_msgs::Marker::ADD;
00501 marker.ns = "loop_closure";
00502 marker.id = marker_id_++;
00503 marker.type = visualization_msgs::Marker::SPHERE;
00504 marker.pose.position.x = pose.getOrigin().x();
00505 marker.pose.position.y = pose.getOrigin().y();
00506 marker.scale.x = 0.5;
00507 marker.scale.y = 0.5;
00508 marker.scale.z = 0.5;
00509 marker.color.a = 1.0;
00510 marker.color.r = 1.0;
00511 marker.color.g = 0.0;
00512 marker.color.b = 0.0;
00513
00514 markers.markers.push_back(marker);
00515
00516 }
00517
00518 void LoopClosure::visualizeEdge(const tf::Pose& pose1, const tf::Pose& pose2, visualization_msgs::MarkerArray& markers)
00519 {
00520 visualization_msgs::Marker marker;
00521 marker.header.frame_id = "map";
00522 marker.header.stamp = ros::Time::now();
00523 marker.action = visualization_msgs::Marker::ADD;
00524 marker.ns = "loop_closure";
00525 marker.id = marker_id_++;
00526 marker.type = visualization_msgs::Marker::LINE_STRIP;
00527 geometry_msgs::Point p;
00528 p.x = pose1.getOrigin().x();
00529 p.y = pose1.getOrigin().y();
00530 marker.points.push_back(p);
00531 p.x = pose2.getOrigin().x();
00532 p.y = pose2.getOrigin().y();
00533 marker.points.push_back(p);
00534 marker.scale.x = 0.25;
00535 marker.scale.y = 0.25;
00536 marker.scale.z = 0.25;
00537 marker.color.a = 1.0;
00538 marker.color.r = 1.0;
00539 marker.color.g = 0.0;
00540 marker.color.b = 0.0;
00541
00542 markers.markers.push_back(marker);
00543
00544 }
00545
00546 void LoopClosure::visualizeGraph()
00547 {
00548 visualization_msgs::MarkerArray markers;
00549 marker_id_ = 0;
00550
00551 for(unsigned int i = 0; i < nodes_.size(); ++i){
00552 visualizeNode(nodes_[i]->pose_, markers);
00553 }
00554
00555
00556 for(unsigned int i = 0; i < graph_.size(); ++i){
00557 for(unsigned int j = 0; j < graph_[i].size(); ++j){
00558 visualizeEdge(nodes_[i]->pose_, nodes_[graph_[i][j]]->pose_, markers);
00559 }
00560 }
00561
00562 marker_publisher_.publish(markers);
00563 }
00564
00565