loop_closure.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2008, Willow Garage, Inc.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the Willow Garage nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  *********************************************************************/
00036 
00037 
00038 /*
00039  * Implement the loop-closure exploration algorithm, from Stachniss, et
00040  * al., IROS 2004.
00041  */
00042 
00043 #include <float.h>
00044 
00045 #include <ros/console.h>
00046 #include <explore_hrl/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                          boost::function<void (void) > continuation_callback) :
00061         curr_node_(NULL), 
00062         addition_dist_min_(addition_dist_min), 
00063         loop_dist_min_(loop_dist_min),
00064         loop_dist_max_(loop_dist_max),
00065         slam_entropy_max_(slam_entropy_max_),
00066         graph_update_frequency_(graph_update_frequency),
00067         move_base_client_(move_base_client),
00068         nh_(),
00069         marker_id_(0),
00070         costmap_(costmap),
00071         control_mutex_(control_mutex),
00072         continuation_callback_(continuation_callback),
00073         planner_(NULL),
00074         slam_entropy_(0.0)
00075 {
00076   marker_publisher_ = nh_.advertise<visualization_msgs::MarkerArray>("visualization_marker_array",1);
00077   entropy_subscriber_ = nh_.subscribe("slam_entropy", 1, &LoopClosure::entropyCallback, this);
00078   planner_ = new navfn::NavfnROS(std::string("loop_closure_planner"), &costmap_);
00079 }
00080 
00081 LoopClosure::~LoopClosure()
00082 {
00083 
00084   // Same as visualizeGraph -- Just DELETE instead of add.
00085   visualization_msgs::MarkerArray markers;
00086   marker_id_ = 0;
00087   //first we'll go through each node in the graph and  add a marker for it
00088   for(unsigned int i = 0; i < nodes_.size(); ++i){
00089     visualizeNode(nodes_[i]->pose_, markers);
00090   }
00091 
00092   //we'll also add all the edges in the graph... there may be duplicates here, but that should be ok
00093   for(unsigned int i = 0; i < graph_.size(); ++i){
00094     for(unsigned int j = 0; j < graph_[i].size(); ++j){
00095       visualizeEdge(nodes_[i]->pose_, nodes_[graph_[i][j]]->pose_, markers);
00096     }
00097   }
00098 
00099   for ( unsigned int i = 0; i < markers.markers.size(); i++)
00100     markers.markers[i].action = visualization_msgs::Marker::DELETE;
00101 
00102   marker_publisher_.publish(markers);
00103 
00104   delete planner_;
00105 }
00106 
00107 void
00108 LoopClosure::entropyCallback(const std_msgs::Float64::ConstPtr& entropy)
00109 {
00110   slam_entropy_ = entropy->data;
00111 }
00112 
00113 void 
00114 LoopClosure::updateGraph(const tf::Pose& pose)
00115 {
00116   // Try to add a node
00117   addNode(pose);
00118   // Look for an opportunity to close a loop
00119   if(slam_entropy_ > 0.0 && slam_entropy_ > slam_entropy_max_)
00120   {
00121     ROS_DEBUG("Entropy is high enough (%.3f > %.3f); checking for loop closure opportunities",
00122               slam_entropy_, slam_entropy_max_);
00123     std::vector<GraphNode*> candidates;
00124     if(checkLoopClosure(pose, candidates))
00125     {
00126       // We found some. Time to control the robot
00127       control_mutex_.lock();
00128       // Control the robot
00129       ROS_INFO("Taking control of the robot for loop closure goals.");
00130 
00131       double min_path_length = DBL_MAX;
00132       GraphNode* entry_point = candidates[0];
00133 
00134       // Take the candidate node that is closest to our current position as the entry point
00135       for(unsigned int i = 0; i < candidates.size(); ++i){
00136         if(candidates[i]->path_length_ < min_path_length){
00137           entry_point = candidates[i];
00138           min_path_length = candidates[i]->path_length_;
00139         }
00140       }
00141       
00142       // We may end up going to several nodes; the first one is the entry
00143       // point.
00144       GraphNode* curr_target = entry_point;
00145 
00146       //the node that we'll connect to the target
00147       GraphNode* connect_node = curr_node_;
00148       
00149       move_base_msgs::MoveBaseGoal goal;
00150       goal.target_pose.header.frame_id = "map";
00151       goal.target_pose.header.stamp = ros::Time::now();
00152       // We retrace our steps as long as entropy is higher than what it was
00153       // last time we were here.
00154       do
00155       {
00156         ROS_INFO("Loop closure: Sending the robot to %.3f %.3f (%d)",
00157                  curr_target->pose_.getOrigin().x(),
00158                  curr_target->pose_.getOrigin().y(),
00159                  curr_target->id_);
00160         // TODO: pick a better orientation on the goal pose
00161         tf::poseTFToMsg(curr_target->pose_, goal.target_pose.pose);
00162         move_base_client_.sendGoal(goal);
00163         ros::Rate r(graph_update_frequency_);
00164 
00165 
00166         while(!move_base_client_.getState().isDone()){
00167           //get the current pose of the robot and check if
00168           tf::Stamped<tf::Pose> robot_pose;
00169           costmap_.getRobotPose(robot_pose);
00170 
00171           addNode(robot_pose);
00172 
00173           // Compute shortest distances from current node to all nodes.  Distances
00174           // are stored in nodes themselves.
00175           dijkstra(curr_node_->id_);
00176 
00177           //now we'll check if we are still far enough topologically from the loop closure target
00178           //if we are, we'll update the node that we'll connect with the loop closure
00179           if(curr_target->dijkstra_d_ > loop_dist_max_){
00180             connect_node = curr_node_;
00181           }
00182 
00183           visualizeGraph();
00184           r.sleep();
00185         }
00186         // TODO: inspect the result
00187 
00188         // Now go to the node that we went to last time we were here
00189         curr_target = curr_target->next_;
00190       } while((curr_target != NULL) && (slam_entropy_ > entry_point->slam_entropy_));
00191 
00192       // We need to connect the last node we added to the entry point in order to log that we've closed the loop
00193       if(connect_node){
00194         graph_[connect_node->id_].push_back(entry_point->id_);
00195         graph_[entry_point->id_].push_back(connect_node->id_);
00196         ROS_INFO("Adding edge from connector node to entry point");
00197       }
00198 
00199       control_mutex_.unlock();
00200       ROS_INFO("Entropy threshold satisfied (%.3f <= %.3f); loop closure terminated",
00201                slam_entropy_, entry_point->slam_entropy_);
00202       // Wake up frontier-based exploration.
00203       continuation_callback_();
00204     }
00205   }
00206 
00207   //actually display the graph in rviz
00208   visualizeGraph();
00209 }
00210 
00211 void 
00212 LoopClosure::addNode(const tf::Pose& pose)
00213 {
00214   bool add = false;
00215   // If there are no nodes yet, add one now
00216   if(curr_node_ == NULL)
00217     add = true;
00218   else
00219   {
00220     geometry_msgs::PoseStamped planner_start;
00221     geometry_msgs::Pose temp_pose;
00222     tf::poseTFToMsg(pose, temp_pose);
00223     planner_start.header.stamp = ros::Time::now();
00224     planner_start.header.frame_id = costmap_.getGlobalFrameID();
00225     planner_start.pose = temp_pose;
00226 
00227     //we'll only compute the potential once from our position
00228     planner_->computePotential(planner_start.pose.position);
00229 
00230     add = true;
00231     
00232     // How far are we from the closest node?
00233     double mind = DBL_MAX;
00234     GraphNode* closest_node = NULL;
00235     for(int i = nodes_.size() - 1; i >= 0; --i)
00236     {
00237       GraphNode* index_node = nodes_[i];
00238 
00239       //we need to convert from tf to message types for the planner
00240       geometry_msgs::PoseStamped planner_end;
00241 
00242       tf::poseTFToMsg(index_node->pose_, temp_pose);
00243       planner_end.header.stamp = ros::Time::now();
00244       planner_end.header.frame_id = costmap_.getGlobalFrameID();
00245       planner_end.pose = temp_pose;
00246 
00247       //now we'll make a plan from one point to the other
00248       std::vector<geometry_msgs::PoseStamped> plan;
00249       bool valid_plan = planner_->getPlanFromPotential(planner_end, plan) && !plan.empty();
00250 
00251       // Graph distance check satisfied; compute map distance
00252       if(valid_plan){
00253         double path_length = 0.0;
00254 
00255         //compute the path length
00256         if(plan.size() > 1){
00257           //double dist = distance(plan[0], plan[1]);
00258           //path_length = dist * (plan.size() - 1);
00259 
00260           for(unsigned int j = 0; j < plan.size() - 1; ++j){
00261             double dist = distance(plan[j], plan[j + 1]);
00262             path_length += dist;
00263           }
00264 
00265           if(path_length < mind){
00266             mind = path_length;
00267             closest_node = index_node;
00268 
00269             //we'll also update our current node here because we always want to add ourselves as a node to the 
00270             //closest node
00271             curr_node_ = closest_node;
00272           }
00273         }
00274 
00275       }
00276     }
00277     if(mind < addition_dist_min_)
00278     {
00279       // We found a close-enough node, so we won't add one, unless we lost visibility
00280       add = false;
00281 
00282       /*
00283       for(int i = nodes_.size() - 1; i >= 0; --i)
00284       {
00285         GraphNode* index_node = nodes_[i];
00286 
00287         //we also need to check if we have visibility from our current node to the previous node
00288         bool is_visible = true;
00289         VisibilityChecker checker(visibility_map.getCharMap(), is_visible);
00290 
00291         //get map coordinates
00292         bool in_bounds = true;
00293         unsigned int x0, y0;
00294         if(!visibility_map.worldToMap(pose.getOrigin().x(), pose.getOrigin().y(), x0, y0)){
00295           ROS_WARN("Attempting to check visibility from a point off the map... this should never happen");
00296           in_bounds = false;
00297         }
00298 
00299         unsigned int x1, y1;
00300         if(!visibility_map.worldToMap(index_node->pose_.getOrigin().x(), index_node->pose_.getOrigin().y(), x1, y1)){
00301           ROS_WARN("Attempting to check visibility to a point off the map... this should never happen");
00302           in_bounds = false;
00303         }
00304 
00305         if(in_bounds){
00306           //raytrace a line with our visibility checker
00307           raytraceLine(checker, x0, y0, x1, y1, visibility_map.getSizeInCellsX());
00308 
00309           //check if we have visibility to the node
00310           if(is_visible){
00311             add = false;
00312             break;
00313           }
00314         }
00315       }
00316       */
00317     
00318       
00319       // Update current node to be this one.
00320       curr_node_ = closest_node;
00321 
00322       // Store the current slam entropy; we compare to it later to decide
00323       // to terminate loop closure.
00324       if(slam_entropy_ > 0.0)
00325         curr_node_->slam_entropy_ = slam_entropy_;
00326     }
00327   }
00328 
00329   if(add)
00330   {
00331     ROS_INFO("Adding node at %.3f, %.3f", pose.getOrigin().x(), pose.getOrigin().y());
00332     GraphNode* n = new GraphNode(nodes_.size(), pose);
00333     nodes_.push_back(n);
00334     // Add an empty adjacency list for the new node
00335     std::vector<int> edges;
00336     graph_.push_back(edges);
00337 
00338     if(curr_node_)
00339     {
00340       // Update both adjacency lists
00341       graph_[curr_node_->id_].push_back(n->id_);
00342       graph_[n->id_].push_back(curr_node_->id_);
00343       curr_node_->next_ = n;
00344     }
00345     curr_node_ = n;
00346 
00347     // Store the current slam entropy; we compare to it later to decide
00348     // to terminate loop closure.
00349     if(slam_entropy_ > 0.0)
00350       curr_node_->slam_entropy_ = slam_entropy_;
00351   }
00352 }
00353 
00354 bool
00355 LoopClosure::checkLoopClosure(const tf::Pose& pose, std::vector<GraphNode*>& candidates)
00356 {
00357   bool ret = false;
00358 
00359   if(curr_node_ == NULL || nodes_.size() < 2)
00360     return ret;
00361 
00362   // Compute shortest distances from current node to all nodes.  Distances
00363   // are stored in nodes themselves.
00364   dijkstra(curr_node_->id_);
00365 
00366   //we'll only compute the potential once
00367   geometry_msgs::Pose temp_pose;
00368   geometry_msgs::PoseStamped planner_start;
00369 
00370   tf::poseTFToMsg(pose, temp_pose);
00371   planner_start.header.stamp = ros::Time::now();
00372   planner_start.header.frame_id = costmap_.getGlobalFrameID();
00373   planner_start.pose = temp_pose;
00374 
00375   planner_->computePotential(planner_start.pose.position);
00376 
00377   //get a copy of the costmap that we can do raytracing on
00378   costmap_2d::Costmap2D visibility_map;
00379   costmap_.getCostmapCopy(visibility_map);
00380 
00381   for(std::vector<GraphNode*>::iterator it = nodes_.begin();
00382       it != nodes_.end();
00383       ++it)
00384   {
00385 
00386     ROS_DEBUG("Checking %d (%.3f, %.3f)", (*it)->id_, (*it)->pose_.getOrigin().x(), (*it)->pose_.getOrigin().y());
00387     ROS_DEBUG("Graph distance is %.3f (threshold is %.3f)", (*it)->dijkstra_d_, loop_dist_max_);
00388 
00389     if((*it)->dijkstra_d_ > loop_dist_max_)
00390     {
00391       ROS_DEBUG("graph dist check satisfied");
00392       //we need to convert from tf to message types for the planner
00393       geometry_msgs::PoseStamped planner_end;
00394 
00395       tf::poseTFToMsg((*it)->pose_, temp_pose);
00396       planner_end.header.stamp = ros::Time::now();
00397       planner_end.header.frame_id = costmap_.getGlobalFrameID();
00398       planner_end.pose = temp_pose;
00399 
00400       //now we'll make a plan from one point to the other
00401       std::vector<geometry_msgs::PoseStamped> plan;
00402       bool valid_plan = planner_->getPlanFromPotential(planner_end, plan) && !plan.empty();
00403 
00404       // Graph distance check satisfied; compute map distance
00405       if(valid_plan){
00406         double path_length = 0.0;
00407 
00408         //compute the path length
00409         if(plan.size() > 1){
00410           //double dist = distance(plan[0], plan[1]);
00411           //path_length = dist * (plan.size() - 1);
00412 
00413           for(unsigned int j = 0; j < plan.size() - 1; ++j){
00414             double dist = distance(plan[j], plan[j + 1]);
00415             path_length += dist;
00416           }
00417 
00418           ROS_DEBUG("path_length: %.3f (threshold is %.3f)", path_length, loop_dist_min_);
00419           if(path_length < loop_dist_min_)
00420           {
00421             //also check that there is visibility from one node to the other
00422             bool is_visible = true;
00423             VisibilityChecker checker(visibility_map.getCharMap(), is_visible);
00424 
00425             //get map coordinates
00426             bool in_bounds = true;
00427             unsigned int x0, y0;
00428             if(!visibility_map.worldToMap(pose.getOrigin().x(), pose.getOrigin().y(), x0, y0)){
00429               ROS_WARN("Attempting to check visibility from a point off the map... this should never happen");
00430               in_bounds = false;
00431             }
00432 
00433             unsigned int x1, y1;
00434             if(!visibility_map.worldToMap((*it)->pose_.getOrigin().x(), (*it)->pose_.getOrigin().y(), x1, y1)){
00435               ROS_WARN("Attempting to check visibility to a point off the map... this should never happen");
00436               in_bounds = false;
00437             }
00438 
00439             if(in_bounds){
00440               //raytrace a line with our visibility checker
00441               raytraceLine(checker, x0, y0, x1, y1, visibility_map.getSizeInCellsX());
00442 
00443               //check if we have visibility to the node
00444               if(is_visible){
00445                 //update the path distance on the node we're about to push back
00446                 (*it)->path_length_ = path_length;
00447                 // Both checks satisfied
00448                 candidates.push_back(*it);
00449                 ROS_INFO("added loop closure candidate %d (%.3f, %.3f)", 
00450                     (*it)->id_, (*it)->pose_.getOrigin().x(), (*it)->pose_.getOrigin().y());
00451                 ret = true;
00452               }
00453             }
00454           }
00455         }
00456       }
00457     }
00458   }
00459 
00460   return ret;
00461 }
00462 
00463 // Poor-man's (inefficient) dijkstra implementation.
00464 void
00465 LoopClosure::dijkstra(int source)
00466 {
00467   std::list<GraphNode*> Q;
00468   for(std::vector<GraphNode*>::iterator it = nodes_.begin();
00469       it != nodes_.end();
00470       ++it)
00471   {
00472     if((*it)->id_ == source)
00473       (*it)->dijkstra_d_ = 0.0;
00474     else
00475       (*it)->dijkstra_d_ = DBL_MAX;
00476     Q.push_back(*it);
00477   }
00478   while(!Q.empty())
00479   {
00480     std::list<GraphNode*>::iterator it = Q.end();
00481     for(std::list<GraphNode*>::iterator iit = Q.begin();
00482         iit != Q.end();
00483         ++iit)
00484     {
00485       if((it == Q.end()) || ((*iit)->dijkstra_d_ < (*it)->dijkstra_d_))
00486       {
00487         it = iit;
00488       }
00489     }
00490     GraphNode* n = *it;
00491     if(n->dijkstra_d_ == DBL_MAX)
00492       break;
00493     Q.erase(it);
00494 
00495     for(std::vector<int>::iterator git = graph_[n->id_].begin();
00496         git != graph_[n->id_].end();
00497         ++git)
00498     {
00499       GraphNode* nn = nodes_[*git];
00500       double d = (n->pose_.getOrigin() - nn->pose_.getOrigin()).length();
00501       double alt = n->dijkstra_d_ + d;
00502       if(alt < nn->dijkstra_d_)
00503       {
00504         nn->dijkstra_d_ = alt;
00505       }
00506     }
00507   }
00508 }
00509 
00510 void LoopClosure::visualizeNode(const tf::Pose& pose, visualization_msgs::MarkerArray& markers)
00511 {
00512   visualization_msgs::Marker marker;
00513   marker.header.frame_id = "map";
00514   marker.header.stamp = ros::Time::now();
00515   marker.action = visualization_msgs::Marker::ADD;
00516   marker.ns = "loop_closure";
00517   marker.id = marker_id_++;
00518   marker.type = visualization_msgs::Marker::SPHERE;
00519   marker.pose.position.x = pose.getOrigin().x();
00520   marker.pose.position.y = pose.getOrigin().y();
00521   marker.scale.x = 0.5;
00522   marker.scale.y = 0.5;
00523   marker.scale.z = 0.5;
00524   marker.color.a = 1.0;
00525   marker.color.r = 1.0;
00526   marker.color.g = 0.0;
00527   marker.color.b = 0.0;
00528   //marker.lifetime = ros::Duration(5);
00529   markers.markers.push_back(marker);
00530   //marker_publisher_.publish(marker);
00531 }
00532 
00533 void LoopClosure::visualizeEdge(const tf::Pose& pose1, const tf::Pose& pose2, visualization_msgs::MarkerArray& markers)
00534 {
00535   visualization_msgs::Marker marker;
00536   marker.header.frame_id = "map";
00537   marker.header.stamp = ros::Time::now();
00538   marker.action = visualization_msgs::Marker::ADD;
00539   marker.ns = "loop_closure";
00540   marker.id = marker_id_++;
00541   marker.type = visualization_msgs::Marker::LINE_STRIP;
00542   geometry_msgs::Point p;
00543   p.x = pose1.getOrigin().x();
00544   p.y = pose1.getOrigin().y();
00545   marker.points.push_back(p);
00546   p.x = pose2.getOrigin().x();
00547   p.y = pose2.getOrigin().y();
00548   marker.points.push_back(p);
00549   marker.scale.x = 0.25;
00550   marker.scale.y = 0.25;
00551   marker.scale.z = 0.25;
00552   marker.color.a = 1.0;
00553   marker.color.r = 1.0;
00554   marker.color.g = 0.0;
00555   marker.color.b = 0.0;
00556   //marker.lifetime = ros::Duration(5);
00557   markers.markers.push_back(marker);
00558   //marker_publisher_.publish(marker);
00559 }
00560 
00561 void LoopClosure::visualizeGraph()
00562 {
00563   visualization_msgs::MarkerArray markers;
00564   marker_id_ = 0;
00565   //first we'll go through each node in the graph and  add a marker for it
00566   for(unsigned int i = 0; i < nodes_.size(); ++i){
00567     visualizeNode(nodes_[i]->pose_, markers);
00568   }
00569 
00570   //we'll also add all the edges in the graph... there may be duplicates here, but that should be ok
00571   for(unsigned int i = 0; i < graph_.size(); ++i){
00572     for(unsigned int j = 0; j < graph_[i].size(); ++j){
00573       visualizeEdge(nodes_[i]->pose_, nodes_[graph_[i][j]]->pose_, markers);
00574     }
00575   }
00576 
00577   marker_publisher_.publish(markers);
00578 }
00579 
00580 


explore_hrl
Author(s): Travis Deyle
autogenerated on Wed Nov 27 2013 11:48:01