planner_core.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2008, 2013, 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 Willow Garage, Inc. 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  *         David V. Lu!!
00037  *********************************************************************/
00038 #include <global_planner/planner_core.h>
00039 #include <pluginlib/class_list_macros.h>
00040 #include <tf/transform_listener.h>
00041 #include <costmap_2d/cost_values.h>
00042 #include <costmap_2d/costmap_2d.h>
00043 
00044 #include <global_planner/dijkstra.h>
00045 #include <global_planner/astar.h>
00046 #include <global_planner/grid_path.h>
00047 #include <global_planner/gradient_path.h>
00048 #include <global_planner/quadratic_calculator.h>
00049 
00050 //register this planner as a BaseGlobalPlanner plugin
00051 PLUGINLIB_EXPORT_CLASS(global_planner::GlobalPlanner, nav_core::BaseGlobalPlanner)
00052 
00053 namespace global_planner {
00054 
00055 void GlobalPlanner::outlineMap(unsigned char* costarr, int nx, int ny, unsigned char value) {
00056     unsigned char* pc = costarr;
00057     for (int i = 0; i < nx; i++)
00058         *pc++ = value;
00059     pc = costarr + (ny - 1) * nx;
00060     for (int i = 0; i < nx; i++)
00061         *pc++ = value;
00062     pc = costarr;
00063     for (int i = 0; i < ny; i++, pc += nx)
00064         *pc = value;
00065     pc = costarr + nx - 1;
00066     for (int i = 0; i < ny; i++, pc += nx)
00067         *pc = value;
00068 }
00069 
00070 GlobalPlanner::GlobalPlanner() :
00071         costmap_(NULL), initialized_(false), allow_unknown_(true) {
00072 }
00073 
00074 GlobalPlanner::GlobalPlanner(std::string name, costmap_2d::Costmap2D* costmap, std::string frame_id) :
00075         costmap_(NULL), initialized_(false), allow_unknown_(true) {
00076     //initialize the planner
00077     initialize(name, costmap, frame_id);
00078 }
00079 
00080 void GlobalPlanner::initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros) {
00081     initialize(name, costmap_ros->getCostmap(), costmap_ros->getGlobalFrameID());
00082 }
00083 
00084 void GlobalPlanner::initialize(std::string name, costmap_2d::Costmap2D* costmap, std::string frame_id) {
00085     if (!initialized_) {
00086         ros::NodeHandle private_nh("~/" + name);
00087         costmap_ = costmap;
00088         frame_id_ = frame_id;
00089 
00090         unsigned int cx = costmap->getSizeInCellsX(), cy = costmap->getSizeInCellsY();
00091 
00092         private_nh.param("old_navfn_behavior", old_navfn_behavior_, false);
00093         if(!old_navfn_behavior_)
00094             convert_offset_ = 0.5;
00095         else
00096             convert_offset_ = 0.0;
00097 
00098         bool use_quadratic;
00099         private_nh.param("use_quadratic", use_quadratic, true);
00100         if (use_quadratic)
00101             p_calc_ = new QuadraticCalculator(cx, cy);
00102         else
00103             p_calc_ = new PotentialCalculator(cx, cy);
00104 
00105         bool use_dijkstra;
00106         private_nh.param("use_dijkstra", use_dijkstra, true);
00107         if (use_dijkstra)
00108         {
00109             DijkstraExpansion* de = new DijkstraExpansion(p_calc_, cx, cy);
00110             if(!old_navfn_behavior_)
00111                 de->setPreciseStart(true);
00112             planner_ = de;
00113         }
00114         else
00115             planner_ = new AStarExpansion(p_calc_, cx, cy);
00116 
00117         bool use_grid_path;
00118         private_nh.param("use_grid_path", use_grid_path, false);
00119         if (use_grid_path)
00120             path_maker_ = new GridPath(p_calc_);
00121         else
00122             path_maker_ = new GradientPath(p_calc_);
00123 
00124         plan_pub_ = private_nh.advertise<nav_msgs::Path>("plan", 1);
00125         potential_pub_ = private_nh.advertise<nav_msgs::OccupancyGrid>("potential", 1);
00126 
00127         private_nh.param("allow_unknown", allow_unknown_, true);
00128         planner_->setHasUnknown(allow_unknown_);
00129         private_nh.param("planner_window_x", planner_window_x_, 0.0);
00130         private_nh.param("planner_window_y", planner_window_y_, 0.0);
00131         private_nh.param("default_tolerance", default_tolerance_, 0.0);
00132         private_nh.param("publish_scale", publish_scale_, 100);
00133 
00134         double costmap_pub_freq;
00135         private_nh.param("planner_costmap_publish_frequency", costmap_pub_freq, 0.0);
00136 
00137         //get the tf prefix
00138         ros::NodeHandle prefix_nh;
00139         tf_prefix_ = tf::getPrefixParam(prefix_nh);
00140 
00141         make_plan_srv_ = private_nh.advertiseService("make_plan", &GlobalPlanner::makePlanService, this);
00142 
00143         dsrv_ = new dynamic_reconfigure::Server<global_planner::GlobalPlannerConfig>(ros::NodeHandle("~/" + name));
00144         dynamic_reconfigure::Server<global_planner::GlobalPlannerConfig>::CallbackType cb = boost::bind(
00145                 &GlobalPlanner::reconfigureCB, this, _1, _2);
00146         dsrv_->setCallback(cb);
00147 
00148         initialized_ = true;
00149     } else
00150         ROS_WARN("This planner has already been initialized, you can't call it twice, doing nothing");
00151 
00152 }
00153 
00154 void GlobalPlanner::reconfigureCB(global_planner::GlobalPlannerConfig& config, uint32_t level) {
00155     planner_->setLethalCost(config.lethal_cost);
00156     path_maker_->setLethalCost(config.lethal_cost);
00157     planner_->setNeutralCost(config.neutral_cost);
00158     planner_->setFactor(config.cost_factor);
00159     publish_potential_ = config.publish_potential;
00160 }
00161 
00162 void GlobalPlanner::clearRobotCell(const tf::Stamped<tf::Pose>& global_pose, unsigned int mx, unsigned int my) {
00163     if (!initialized_) {
00164         ROS_ERROR(
00165                 "This planner has not been initialized yet, but it is being used, please call initialize() before use");
00166         return;
00167     }
00168 
00169     //set the associated costs in the cost map to be free
00170     costmap_->setCost(mx, my, costmap_2d::FREE_SPACE);
00171 }
00172 
00173 bool GlobalPlanner::makePlanService(nav_msgs::GetPlan::Request& req, nav_msgs::GetPlan::Response& resp) {
00174     makePlan(req.start, req.goal, resp.plan.poses);
00175 
00176     resp.plan.header.stamp = ros::Time::now();
00177     resp.plan.header.frame_id = frame_id_;
00178 
00179     return true;
00180 }
00181 
00182 void GlobalPlanner::mapToWorld(double mx, double my, double& wx, double& wy) {
00183     wx = costmap_->getOriginX() + (mx+convert_offset_) * costmap_->getResolution();
00184     wy = costmap_->getOriginY() + (my+convert_offset_) * costmap_->getResolution();
00185 }
00186 
00187 bool GlobalPlanner::worldToMap(double wx, double wy, double& mx, double& my) {
00188     double origin_x = costmap_->getOriginX(), origin_y = costmap_->getOriginY();
00189     double resolution = costmap_->getResolution();
00190 
00191     if (wx < origin_x || wy < origin_y)
00192         return false;
00193 
00194     mx = (wx - origin_x) / resolution - convert_offset_;
00195     my = (wy - origin_y) / resolution - convert_offset_;
00196 
00197     if (mx < costmap_->getSizeInCellsX() && my < costmap_->getSizeInCellsY())
00198         return true;
00199 
00200     return false;
00201 }
00202 
00203 bool GlobalPlanner::makePlan(const geometry_msgs::PoseStamped& start, const geometry_msgs::PoseStamped& goal,
00204                            std::vector<geometry_msgs::PoseStamped>& plan) {
00205     return makePlan(start, goal, default_tolerance_, plan);
00206 }
00207 
00208 bool GlobalPlanner::makePlan(const geometry_msgs::PoseStamped& start, const geometry_msgs::PoseStamped& goal,
00209                            double tolerance, std::vector<geometry_msgs::PoseStamped>& plan) {
00210     boost::mutex::scoped_lock lock(mutex_);
00211     if (!initialized_) {
00212         ROS_ERROR(
00213                 "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     std::string global_frame = frame_id_;
00222 
00223     //until tf can handle transforming things that are way in the past... we'll require the goal to be in our global frame
00224     if (tf::resolve(tf_prefix_, goal.header.frame_id) != tf::resolve(tf_prefix_, global_frame)) {
00225         ROS_ERROR(
00226                 "The goal pose passed to this planner must be in the %s frame.  It is instead in the %s frame.", tf::resolve(tf_prefix_, global_frame).c_str(), tf::resolve(tf_prefix_, goal.header.frame_id).c_str());
00227         return false;
00228     }
00229 
00230     if (tf::resolve(tf_prefix_, start.header.frame_id) != tf::resolve(tf_prefix_, global_frame)) {
00231         ROS_ERROR(
00232                 "The start pose passed to this planner must be in the %s frame.  It is instead in the %s frame.", tf::resolve(tf_prefix_, global_frame).c_str(), tf::resolve(tf_prefix_, start.header.frame_id).c_str());
00233         return false;
00234     }
00235 
00236     double wx = start.pose.position.x;
00237     double wy = start.pose.position.y;
00238 
00239     unsigned int start_x_i, start_y_i, goal_x_i, goal_y_i;
00240     double start_x, start_y, goal_x, goal_y;
00241 
00242     if (!costmap_->worldToMap(wx, wy, start_x_i, start_y_i)) {
00243         ROS_WARN(
00244                 "The robot's start position is off the global costmap. Planning will always fail, are you sure the robot has been properly localized?");
00245         return false;
00246     }
00247     if(old_navfn_behavior_){
00248         start_x = start_x_i;
00249         start_y = start_y_i;
00250     }else{
00251         worldToMap(wx, wy, start_x, start_y);
00252     }
00253 
00254     wx = goal.pose.position.x;
00255     wy = goal.pose.position.y;
00256 
00257     if (!costmap_->worldToMap(wx, wy, goal_x_i, goal_y_i)) {
00258         ROS_WARN(
00259                 "The goal sent to the navfn planner is off the global costmap. Planning will always fail to this goal.");
00260         return false;
00261     }
00262     if(old_navfn_behavior_){
00263         goal_x = goal_x_i;
00264         goal_y = goal_y_i;
00265     }else{
00266         worldToMap(wx, wy, goal_x, goal_y);
00267     }
00268 
00269     //clear the starting cell within the costmap because we know it can't be an obstacle
00270     tf::Stamped<tf::Pose> start_pose;
00271     tf::poseStampedMsgToTF(start, start_pose);
00272     clearRobotCell(start_pose, start_x_i, start_y_i);
00273 
00274     int nx = costmap_->getSizeInCellsX(), ny = costmap_->getSizeInCellsY();
00275 
00276     //make sure to resize the underlying array that Navfn uses
00277     p_calc_->setSize(nx, ny);
00278     planner_->setSize(nx, ny);
00279     path_maker_->setSize(nx, ny);
00280     potential_array_ = new float[nx * ny];
00281 
00282     outlineMap(costmap_->getCharMap(), nx, ny, costmap_2d::LETHAL_OBSTACLE);
00283 
00284     bool found_legal = planner_->calculatePotentials(costmap_->getCharMap(), start_x, start_y, goal_x, goal_y,
00285                                                     nx * ny * 2, potential_array_);
00286 
00287     if(!old_navfn_behavior_)
00288         planner_->clearEndpoint(costmap_->getCharMap(), potential_array_, goal_x_i, goal_y_i, 2);
00289     if(publish_potential_)
00290         publishPotential(potential_array_);
00291 
00292     if (found_legal) {
00293         //extract the plan
00294         if (getPlanFromPotential(start_x, start_y, goal_x, goal_y, goal, plan)) {
00295             //make sure the goal we push on has the same timestamp as the rest of the plan
00296             geometry_msgs::PoseStamped goal_copy = goal;
00297             goal_copy.header.stamp = ros::Time::now();
00298             plan.push_back(goal_copy);
00299         } else {
00300             ROS_ERROR("Failed to get a plan from potential when a legal potential was found. This shouldn't happen.");
00301         }
00302     }else{
00303         ROS_ERROR("Failed to get a plan.");
00304     }
00305 
00306     //publish the plan for visualization purposes
00307     publishPlan(plan);
00308     delete potential_array_;
00309     return !plan.empty();
00310 }
00311 
00312 void GlobalPlanner::publishPlan(const std::vector<geometry_msgs::PoseStamped>& path) {
00313     if (!initialized_) {
00314         ROS_ERROR(
00315                 "This planner has not been initialized yet, but it is being used, please call initialize() before use");
00316         return;
00317     }
00318 
00319     //create a message for the plan 
00320     nav_msgs::Path gui_path;
00321     gui_path.poses.resize(path.size());
00322 
00323     if (!path.empty()) {
00324         gui_path.header.frame_id = path[0].header.frame_id;
00325         gui_path.header.stamp = path[0].header.stamp;
00326     }
00327 
00328     // Extract the plan in world co-ordinates, we assume the path is all in the same frame
00329     for (unsigned int i = 0; i < path.size(); i++) {
00330         gui_path.poses[i] = path[i];
00331     }
00332 
00333     plan_pub_.publish(gui_path);
00334 }
00335 
00336 bool GlobalPlanner::getPlanFromPotential(double start_x, double start_y, double goal_x, double goal_y,
00337                                       const geometry_msgs::PoseStamped& goal,
00338                                        std::vector<geometry_msgs::PoseStamped>& plan) {
00339     if (!initialized_) {
00340         ROS_ERROR(
00341                 "This planner has not been initialized yet, but it is being used, please call initialize() before use");
00342         return false;
00343     }
00344 
00345     std::string global_frame = frame_id_;
00346 
00347     //clear the plan, just in case
00348     plan.clear();
00349 
00350     std::vector<std::pair<float, float> > path;
00351 
00352     if (!path_maker_->getPath(potential_array_, start_x, start_y, goal_x, goal_y, path)) {
00353         ROS_ERROR("NO PATH!");
00354         return false;
00355     }
00356 
00357     ros::Time plan_time = ros::Time::now();
00358     for (int i = path.size() -1; i>=0; i--) {
00359         std::pair<float, float> point = path[i];
00360         //convert the plan to world coordinates
00361         double world_x, world_y;
00362         mapToWorld(point.first, point.second, world_x, world_y);
00363 
00364         geometry_msgs::PoseStamped pose;
00365         pose.header.stamp = plan_time;
00366         pose.header.frame_id = global_frame;
00367         pose.pose.position.x = world_x;
00368         pose.pose.position.y = world_y;
00369         pose.pose.position.z = 0.0;
00370         pose.pose.orientation.x = 0.0;
00371         pose.pose.orientation.y = 0.0;
00372         pose.pose.orientation.z = 0.0;
00373         pose.pose.orientation.w = 1.0;
00374         plan.push_back(pose);
00375     }
00376     if(old_navfn_behavior_){
00377             plan.push_back(goal);
00378     }
00379     return !plan.empty();
00380 }
00381 
00382 void GlobalPlanner::publishPotential(float* potential)
00383 {
00384     int nx = costmap_->getSizeInCellsX(), ny = costmap_->getSizeInCellsY();
00385     double resolution = costmap_->getResolution();
00386     nav_msgs::OccupancyGrid grid;
00387     // Publish Whole Grid
00388     grid.header.frame_id = frame_id_;
00389     grid.header.stamp = ros::Time::now();
00390     grid.info.resolution = resolution;
00391 
00392     grid.info.width = nx;
00393     grid.info.height = ny;
00394 
00395     double wx, wy;
00396     costmap_->mapToWorld(0, 0, wx, wy);
00397     grid.info.origin.position.x = wx - resolution / 2;
00398     grid.info.origin.position.y = wy - resolution / 2;
00399     grid.info.origin.position.z = 0.0;
00400     grid.info.origin.orientation.w = 1.0;
00401 
00402     grid.data.resize(nx * ny);
00403 
00404     float max = 0.0;
00405     for (unsigned int i = 0; i < grid.data.size(); i++) {
00406         float potential = potential_array_[i];
00407         if (potential < POT_HIGH) {
00408             if (potential > max) {
00409                 max = potential;
00410             }
00411         }
00412     }
00413 
00414     for (unsigned int i = 0; i < grid.data.size(); i++) {
00415         if (potential_array_[i] >= POT_HIGH) {
00416             grid.data[i] = -1;
00417         } else 
00418             grid.data[i] = potential_array_[i] * publish_scale_ / max;
00419     }
00420     potential_pub_.publish(grid);
00421 }
00422 
00423 } //end namespace global_planner
00424 


global_planner
Author(s): David Lu!!
autogenerated on Thu Aug 27 2015 14:07:53