navfn_ros.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 * Author: Eitan Marder-Eppstein
00036 *********************************************************************/
00037 
00038 /* I have been using modified version of navfn for a long time here.
00039 Unfornutely my changes are affecting ABI of the component, so the can't be
00040 accepted for ROS Jade or below. I expect them be accepted for ROS Karmic. Then
00041 this should be moved back to using standard ROS navfn `<navfn/navfn_ros.h>`.
00042 For the meanwhile, to allow seamless building, I will be using internal
00043 version included from ROS. */
00044 
00045 #include <explore/navfn_ros.h>
00046 
00047 #include <tf/transform_listener.h>
00048 #include <costmap_2d/cost_values.h>
00049 #include <costmap_2d/costmap_2d.h>
00050 
00051 #include <pcl_conversions/pcl_conversions.h>
00052 
00053 namespace navfn {
00054 
00055   NavfnROS::NavfnROS() 
00056     : costmap_(NULL),  planner_(), initialized_(false), allow_unknown_(true) {}
00057 
00058   NavfnROS::NavfnROS(std::string name, costmap_2d::Costmap2DROS* costmap_ros)
00059     : costmap_(NULL),  planner_(), initialized_(false), allow_unknown_(true) {
00060       //initialize the planner
00061       initialize(name, costmap_ros);
00062   }
00063 
00064   NavfnROS::NavfnROS(std::string name, costmap_2d::Costmap2D* costmap, std::string global_frame)
00065     : costmap_(NULL),  planner_(), initialized_(false), allow_unknown_(true) {
00066       //initialize the planner
00067       initialize(name, costmap, global_frame);
00068   }
00069 
00070   void NavfnROS::initialize(std::string name, costmap_2d::Costmap2D* costmap, std::string global_frame){
00071     if(!initialized_){
00072       costmap_ = costmap;
00073       global_frame_ = global_frame;
00074       planner_ = boost::shared_ptr<NavFn>(new NavFn(costmap_->getSizeInCellsX(), costmap_->getSizeInCellsY()));
00075 
00076       ros::NodeHandle private_nh("~/" + name);
00077 
00078       plan_pub_ = private_nh.advertise<nav_msgs::Path>("plan", 1);
00079 
00080       private_nh.param("visualize_potential", visualize_potential_, false);
00081 
00082       //if we're going to visualize the potential array we need to advertise
00083       if(visualize_potential_)
00084         potarr_pub_.advertise(private_nh, "potential", 1);
00085 
00086       private_nh.param("allow_unknown", allow_unknown_, true);
00087       private_nh.param("planner_window_x", planner_window_x_, 0.0);
00088       private_nh.param("planner_window_y", planner_window_y_, 0.0);
00089       private_nh.param("default_tolerance", default_tolerance_, 0.0);
00090 
00091       //get the tf prefix
00092       ros::NodeHandle prefix_nh;
00093       tf_prefix_ = tf::getPrefixParam(prefix_nh);
00094 
00095       make_plan_srv_ =  private_nh.advertiseService("make_plan", &NavfnROS::makePlanService, this);
00096 
00097       initialized_ = true;
00098     }
00099     else
00100       ROS_WARN("This planner has already been initialized, you can't call it twice, doing nothing");
00101   }
00102 
00103   void NavfnROS::initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros){
00104     initialize(name, costmap_ros->getCostmap(), costmap_ros->getGlobalFrameID());
00105   }
00106 
00107   bool NavfnROS::validPointPotential(const geometry_msgs::Point& world_point){
00108     return validPointPotential(world_point, default_tolerance_);
00109   }
00110 
00111   bool NavfnROS::validPointPotential(const geometry_msgs::Point& world_point, double tolerance){
00112     if(!initialized_){
00113       ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use");
00114       return false;
00115     }
00116 
00117     double resolution = costmap_->getResolution();
00118     geometry_msgs::Point p;
00119     p = world_point;
00120 
00121     p.y = world_point.y - tolerance;
00122 
00123     while(p.y <= world_point.y + tolerance){
00124       p.x = world_point.x - tolerance;
00125       while(p.x <= world_point.x + tolerance){
00126         double potential = getPointPotential(p);
00127         if(potential < POT_HIGH){
00128           return true;
00129         }
00130         p.x += resolution;
00131       }
00132       p.y += resolution;
00133     }
00134 
00135     return false;
00136   }
00137 
00138   double NavfnROS::getPointPotential(const geometry_msgs::Point& world_point){
00139     if(!initialized_){
00140       ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use");
00141       return -1.0;
00142     }
00143 
00144     unsigned int mx, my;
00145     if(!costmap_->worldToMap(world_point.x, world_point.y, mx, my))
00146       return DBL_MAX;
00147 
00148     unsigned int index = my * planner_->nx + mx;
00149     return planner_->potarr[index];
00150   }
00151 
00152   bool NavfnROS::computePotential(const geometry_msgs::Point& world_point){
00153     if(!initialized_){
00154       ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use");
00155       return false;
00156     }
00157 
00158     //make sure to resize the underlying array that Navfn uses
00159     planner_->setNavArr(costmap_->getSizeInCellsX(), costmap_->getSizeInCellsY());
00160     planner_->setCostmap(costmap_->getCharMap(), true, allow_unknown_);
00161 
00162     unsigned int mx, my;
00163     if(!costmap_->worldToMap(world_point.x, world_point.y, mx, my))
00164       return false;
00165 
00166     int map_start[2];
00167     map_start[0] = 0;
00168     map_start[1] = 0;
00169 
00170     int map_goal[2];
00171     map_goal[0] = mx;
00172     map_goal[1] = my;
00173 
00174     planner_->setStart(map_start);
00175     planner_->setGoal(map_goal);
00176 
00177     return planner_->calcNavFnDijkstra();
00178   }
00179 
00180   void NavfnROS::clearRobotCell(const tf::Stamped<tf::Pose>& global_pose, unsigned int mx, unsigned int my){
00181     if(!initialized_){
00182       ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use");
00183       return;
00184     }
00185 
00186     //set the associated costs in the cost map to be free
00187     costmap_->setCost(mx, my, costmap_2d::FREE_SPACE);
00188   }
00189 
00190   bool NavfnROS::makePlanService(nav_msgs::GetPlan::Request& req, nav_msgs::GetPlan::Response& resp){
00191     makePlan(req.start, req.goal, resp.plan.poses);
00192 
00193     resp.plan.header.stamp = ros::Time::now();
00194     resp.plan.header.frame_id = global_frame_;
00195 
00196     return true;
00197   } 
00198 
00199   void NavfnROS::mapToWorld(double mx, double my, double& wx, double& wy) {
00200     wx = costmap_->getOriginX() + mx * costmap_->getResolution();
00201     wy = costmap_->getOriginY() + my * costmap_->getResolution();
00202   }
00203 
00204   bool NavfnROS::makePlan(const geometry_msgs::PoseStamped& start, 
00205       const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan){
00206     return makePlan(start, goal, default_tolerance_, plan);
00207   }
00208 
00209   bool NavfnROS::makePlan(const geometry_msgs::PoseStamped& start, 
00210       const geometry_msgs::PoseStamped& goal, double tolerance, std::vector<geometry_msgs::PoseStamped>& plan){
00211     boost::mutex::scoped_lock lock(mutex_);
00212     if(!initialized_){
00213       ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use");
00214       return false;
00215     }
00216 
00217     //clear the plan, just in case
00218     plan.clear();
00219 
00220     ros::NodeHandle n;
00221 
00222     //until tf can handle transforming things that are way in the past... we'll require the goal to be in our global frame
00223     if(tf::resolve(tf_prefix_, goal.header.frame_id) != tf::resolve(tf_prefix_, global_frame_)){
00224       ROS_ERROR("The goal pose passed to this planner must be in the %s frame.  It is instead in the %s frame.", 
00225                 tf::resolve(tf_prefix_, global_frame_).c_str(), tf::resolve(tf_prefix_, goal.header.frame_id).c_str());
00226       return false;
00227     }
00228 
00229     if(tf::resolve(tf_prefix_, start.header.frame_id) != tf::resolve(tf_prefix_, global_frame_)){
00230       ROS_ERROR("The start pose passed to this planner must be in the %s frame.  It is instead in the %s frame.", 
00231                 tf::resolve(tf_prefix_, global_frame_).c_str(), tf::resolve(tf_prefix_, start.header.frame_id).c_str());
00232       return false;
00233     }
00234 
00235     double wx = start.pose.position.x;
00236     double wy = start.pose.position.y;
00237 
00238     unsigned int mx, my;
00239     if(!costmap_->worldToMap(wx, wy, mx, my)){
00240       ROS_WARN("The robot's start position is off the global costmap. Planning will always fail, are you sure the robot has been properly localized?");
00241       return false;
00242     }
00243 
00244     //clear the starting cell within the costmap because we know it can't be an obstacle
00245     tf::Stamped<tf::Pose> start_pose;
00246     tf::poseStampedMsgToTF(start, start_pose);
00247     clearRobotCell(start_pose, mx, my);
00248 
00249 #if 0
00250     {
00251       static int n = 0;
00252       static char filename[1000];
00253       snprintf( filename, 1000, "navfnros-makeplan-costmapB-%04d.pgm", n++ );
00254       costmap->saveRawMap( std::string( filename ));
00255     }
00256 #endif
00257 
00258     //make sure to resize the underlying array that Navfn uses
00259     planner_->setNavArr(costmap_->getSizeInCellsX(), costmap_->getSizeInCellsY());
00260     planner_->setCostmap(costmap_->getCharMap(), true, allow_unknown_);
00261 
00262 #if 0
00263     {
00264       static int n = 0;
00265       static char filename[1000];
00266       snprintf( filename, 1000, "navfnros-makeplan-costmapC-%04d", n++ );
00267       planner_->savemap( filename );
00268     }
00269 #endif
00270 
00271     int map_start[2];
00272     map_start[0] = mx;
00273     map_start[1] = my;
00274 
00275     wx = goal.pose.position.x;
00276     wy = goal.pose.position.y;
00277 
00278     if(!costmap_->worldToMap(wx, wy, mx, my)){
00279       if(tolerance <= 0.0){
00280         ROS_WARN_THROTTLE(1.0, "The goal sent to the navfn planner is off the global costmap. Planning will always fail to this goal.");
00281         return false;
00282       }
00283       mx = 0;
00284       my = 0;
00285     }
00286 
00287     int map_goal[2];
00288     map_goal[0] = mx;
00289     map_goal[1] = my;
00290 
00291     planner_->setStart(map_goal);
00292     planner_->setGoal(map_start);
00293 
00294     //bool success = planner_->calcNavFnAstar();
00295     planner_->calcNavFnDijkstra(true);
00296 
00297     double resolution = costmap_->getResolution();
00298     geometry_msgs::PoseStamped p, best_pose;
00299     p = goal;
00300 
00301     bool found_legal = false;
00302     double best_sdist = DBL_MAX;
00303 
00304     p.pose.position.y = goal.pose.position.y - tolerance;
00305 
00306     while(p.pose.position.y <= goal.pose.position.y + tolerance){
00307       p.pose.position.x = goal.pose.position.x - tolerance;
00308       while(p.pose.position.x <= goal.pose.position.x + tolerance){
00309         double potential = getPointPotential(p.pose.position);
00310         double sdist = sq_distance(p, goal);
00311         if(potential < POT_HIGH && sdist < best_sdist){
00312           best_sdist = sdist;
00313           best_pose = p;
00314           found_legal = true;
00315         }
00316         p.pose.position.x += resolution;
00317       }
00318       p.pose.position.y += resolution;
00319     }
00320 
00321     if(found_legal){
00322       //extract the plan
00323       if(getPlanFromPotential(best_pose, plan)){
00324         //make sure the goal we push on has the same timestamp as the rest of the plan
00325         geometry_msgs::PoseStamped goal_copy = best_pose;
00326         goal_copy.header.stamp = ros::Time::now();
00327         plan.push_back(goal_copy);
00328       }
00329       else{
00330         ROS_ERROR("Failed to get a plan from potential when a legal potential was found. This shouldn't happen.");
00331       }
00332     }
00333 
00334     if (visualize_potential_){
00335       //publish potential array
00336       pcl::PointCloud<PotarrPoint> pot_area;
00337       pot_area.header.frame_id = global_frame_;
00338       pot_area.points.clear();
00339       std_msgs::Header header;
00340       pcl_conversions::fromPCL(pot_area.header, header);
00341       header.stamp = ros::Time::now();
00342       pot_area.header = pcl_conversions::toPCL(header);
00343 
00344       PotarrPoint pt;
00345       float *pp = planner_->potarr;
00346       double pot_x, pot_y;
00347       for (unsigned int i = 0; i < (unsigned int)planner_->ny*planner_->nx ; i++)
00348       {
00349         if (pp[i] < 10e7)
00350         {
00351           mapToWorld(i%planner_->nx, i/planner_->nx, pot_x, pot_y);
00352           pt.x = pot_x;
00353           pt.y = pot_y;
00354           pt.z = pp[i]/pp[planner_->start[1]*planner_->nx + planner_->start[0]]*20;
00355           pt.pot_value = pp[i];
00356           pot_area.push_back(pt);
00357         }
00358       }
00359       potarr_pub_.publish(pot_area);
00360     }
00361 
00362     //publish the plan for visualization purposes
00363     publishPlan(plan, 0.0, 1.0, 0.0, 0.0);
00364 
00365     return !plan.empty();
00366   }
00367 
00368   void NavfnROS::publishPlan(const std::vector<geometry_msgs::PoseStamped>& path, double r, double g, double b, double a){
00369     if(!initialized_){
00370       ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use");
00371       return;
00372     }
00373 
00374     //create a message for the plan 
00375     nav_msgs::Path gui_path;
00376     gui_path.poses.resize(path.size());
00377 
00378     if(!path.empty())
00379     {
00380       gui_path.header.frame_id = path[0].header.frame_id;
00381       gui_path.header.stamp = path[0].header.stamp;
00382     }
00383 
00384     // Extract the plan in world co-ordinates, we assume the path is all in the same frame
00385     for(unsigned int i=0; i < path.size(); i++){
00386       gui_path.poses[i] = path[i];
00387     }
00388 
00389     plan_pub_.publish(gui_path);
00390   }
00391 
00392   bool NavfnROS::getPlanFromPotential(const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan){
00393     if(!initialized_){
00394       ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use");
00395       return false;
00396     }
00397 
00398     //clear the plan, just in case
00399     plan.clear();
00400 
00401     //until tf can handle transforming things that are way in the past... we'll require the goal to be in our global frame
00402     if(tf::resolve(tf_prefix_, goal.header.frame_id) != tf::resolve(tf_prefix_, global_frame_)){
00403       ROS_ERROR("The goal pose passed to this planner must be in the %s frame.  It is instead in the %s frame.", 
00404                 tf::resolve(tf_prefix_, global_frame_).c_str(), tf::resolve(tf_prefix_, goal.header.frame_id).c_str());
00405       return false;
00406     }
00407 
00408     double wx = goal.pose.position.x;
00409     double wy = goal.pose.position.y;
00410 
00411     //the potential has already been computed, so we won't update our copy of the costmap
00412     unsigned int mx, my;
00413     if(!costmap_->worldToMap(wx, wy, mx, my)){
00414       ROS_WARN_THROTTLE(1.0, "The goal sent to the navfn planner is off the global costmap. Planning will always fail to this goal.");
00415       return false;
00416     }
00417 
00418     int map_goal[2];
00419     map_goal[0] = mx;
00420     map_goal[1] = my;
00421 
00422     planner_->setStart(map_goal);
00423 
00424     planner_->calcPath(costmap_->getSizeInCellsX() * 4);
00425 
00426     //extract the plan
00427     float *x = planner_->getPathX();
00428     float *y = planner_->getPathY();
00429     int len = planner_->getPathLen();
00430     ros::Time plan_time = ros::Time::now();
00431 
00432     for(int i = len - 1; i >= 0; --i){
00433       //convert the plan to world coordinates
00434       double world_x, world_y;
00435       mapToWorld(x[i], y[i], world_x, world_y);
00436 
00437       geometry_msgs::PoseStamped pose;
00438       pose.header.stamp = plan_time;
00439       pose.header.frame_id = global_frame_;
00440       pose.pose.position.x = world_x;
00441       pose.pose.position.y = world_y;
00442       pose.pose.position.z = 0.0;
00443       pose.pose.orientation.x = 0.0;
00444       pose.pose.orientation.y = 0.0;
00445       pose.pose.orientation.z = 0.0;
00446       pose.pose.orientation.w = 1.0;
00447       plan.push_back(pose);
00448     }
00449 
00450     //publish the plan for visualization purposes
00451     publishPlan(plan, 0.0, 1.0, 0.0, 0.0);
00452     return !plan.empty();
00453   }
00454 };


explore
Author(s): Jiri Horner
autogenerated on Sun Mar 26 2017 03:48:06