sbpl_lattice_planner.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: Mike Phillips
00036 *********************************************************************/
00037 
00038 #include <sbpl_lattice_planner/sbpl_lattice_planner.h>
00039 #include <pluginlib/class_list_macros.hpp>
00040 #include <nav_msgs/Path.h>
00041 #include <sbpl_lattice_planner/SBPLLatticePlannerStats.h>
00042 
00043 #include <costmap_2d/inflation_layer.h>
00044 #include <tf2/LinearMath/Quaternion.h>
00045 
00046 using namespace std;
00047 using namespace ros;
00048 
00049 
00050 PLUGINLIB_EXPORT_CLASS(sbpl_lattice_planner::SBPLLatticePlanner, nav_core::BaseGlobalPlanner)
00051 
00052 namespace geometry_msgs {
00053   bool operator== (const Point &p1, const Point &p2)
00054   {
00055     return p1.x == p2.x && p1.y == p2.y && p1.z == p2.z;
00056   }
00057 }
00058 
00059 namespace sbpl_lattice_planner{
00060 
00061 class LatticeSCQ : public StateChangeQuery{
00062   public:
00063     LatticeSCQ(EnvironmentNAVXYTHETALAT* env, std::vector<nav2dcell_t> const & changedcellsV)
00064       : env_(env), changedcellsV_(changedcellsV) {
00065     }
00066 
00067     // lazy init, because we do not always end up calling this method
00068     virtual std::vector<int> const * getPredecessors() const{
00069       if(predsOfChangedCells_.empty() && !changedcellsV_.empty())
00070         env_->GetPredsofChangedEdges(&changedcellsV_, &predsOfChangedCells_);
00071       return &predsOfChangedCells_;
00072     }
00073 
00074     // lazy init, because we do not always end up calling this method
00075     virtual std::vector<int> const * getSuccessors() const{
00076       if(succsOfChangedCells_.empty() && !changedcellsV_.empty())
00077         env_->GetSuccsofChangedEdges(&changedcellsV_, &succsOfChangedCells_);
00078       return &succsOfChangedCells_;
00079     }
00080 
00081     EnvironmentNAVXYTHETALAT * env_;
00082     std::vector<nav2dcell_t> const & changedcellsV_;
00083     mutable std::vector<int> predsOfChangedCells_;
00084     mutable std::vector<int> succsOfChangedCells_;
00085 };
00086 
00087 SBPLLatticePlanner::SBPLLatticePlanner()
00088   : initialized_(false), costmap_ros_(NULL){
00089 }
00090 
00091 SBPLLatticePlanner::SBPLLatticePlanner(std::string name, costmap_2d::Costmap2DROS* costmap_ros) 
00092   : initialized_(false), costmap_ros_(NULL){
00093   initialize(name, costmap_ros);
00094 }
00095 
00096     
00097 void SBPLLatticePlanner::initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros){
00098   if(!initialized_){
00099     ros::NodeHandle private_nh("~/"+name);
00100 
00101     ROS_INFO("Name is %s", name.c_str());
00102 
00103     private_nh.param("planner_type", planner_type_, string("ARAPlanner"));
00104     private_nh.param("allocated_time", allocated_time_, 10.0);
00105     private_nh.param("initial_epsilon",initial_epsilon_,3.0);
00106     private_nh.param("environment_type", environment_type_, string("XYThetaLattice"));
00107     private_nh.param("forward_search", forward_search_, bool(false));
00108     private_nh.param("primitive_filename",primitive_filename_,string(""));
00109     private_nh.param("force_scratch_limit",force_scratch_limit_,500);
00110 
00111     double nominalvel_mpersecs, timetoturn45degsinplace_secs;
00112     private_nh.param("nominalvel_mpersecs", nominalvel_mpersecs, 0.4);
00113     private_nh.param("timetoturn45degsinplace_secs", timetoturn45degsinplace_secs, 0.6);
00114 
00115     int lethal_obstacle;
00116     private_nh.param("lethal_obstacle",lethal_obstacle,20);
00117     lethal_obstacle_ = (unsigned char) lethal_obstacle;
00118     inscribed_inflated_obstacle_ = lethal_obstacle_-1;
00119     sbpl_cost_multiplier_ = (unsigned char) (costmap_2d::INSCRIBED_INFLATED_OBSTACLE/inscribed_inflated_obstacle_ + 1);
00120     ROS_DEBUG("SBPL: lethal: %uz, inscribed inflated: %uz, multiplier: %uz",lethal_obstacle,inscribed_inflated_obstacle_,sbpl_cost_multiplier_);
00121 
00122     name_ = name;
00123     costmap_ros_ = costmap_ros;
00124 
00125     footprint_ = costmap_ros_->getRobotFootprint();
00126 
00127     if ("XYThetaLattice" == environment_type_){
00128       ROS_DEBUG("Using a 3D costmap for theta lattice\n");
00129       env_ = new EnvironmentNAVXYTHETALAT();
00130     }
00131     else{
00132       ROS_ERROR("XYThetaLattice is currently the only supported environment!\n");
00133       exit(1);
00134     }
00135 
00136     circumscribed_cost_ = computeCircumscribedCost();
00137 
00138     if (circumscribed_cost_ == 0) {
00139       // Unfortunately, the inflation_radius is not taken into account by
00140       // inflation_layer->computeCost(). If inflation_radius is smaller than
00141       // the circumscribed radius, SBPL will ignore some obstacles, but we
00142       // cannot detect this problem. If the cost_scaling_factor is too large,
00143       // SBPL won't run into obstacles, but will always perform an expensive
00144       // footprint check, no matter how far the nearest obstacle is.
00145       ROS_WARN("The costmap value at the robot's circumscribed radius (%f m) is 0.", costmap_ros_->getLayeredCostmap()->getCircumscribedRadius());
00146       ROS_WARN("SBPL performance will suffer.");
00147       ROS_WARN("Please decrease the costmap's cost_scaling_factor.");
00148     }
00149     if(!env_->SetEnvParameter("cost_inscribed_thresh",costMapCostToSBPLCost(costmap_2d::INSCRIBED_INFLATED_OBSTACLE))){
00150       ROS_ERROR("Failed to set cost_inscribed_thresh parameter");
00151       exit(1);
00152     }
00153     if(!env_->SetEnvParameter("cost_possibly_circumscribed_thresh", circumscribed_cost_)){
00154       ROS_ERROR("Failed to set cost_possibly_circumscribed_thresh parameter");
00155       exit(1);
00156     }
00157     int obst_cost_thresh = costMapCostToSBPLCost(costmap_2d::LETHAL_OBSTACLE);
00158     vector<sbpl_2Dpt_t> perimeterptsV;
00159     perimeterptsV.reserve(footprint_.size());
00160     for (size_t ii(0); ii < footprint_.size(); ++ii) {
00161       sbpl_2Dpt_t pt;
00162       pt.x = footprint_[ii].x;
00163       pt.y = footprint_[ii].y;
00164       perimeterptsV.push_back(pt);
00165     }
00166 
00167     bool ret;
00168     try{
00169       ret = env_->InitializeEnv(costmap_ros_->getCostmap()->getSizeInCellsX(), // width
00170                                 costmap_ros_->getCostmap()->getSizeInCellsY(), // height
00171                                 0, // mapdata
00172                                 0, 0, 0, // start (x, y, theta, t)
00173                                 0, 0, 0, // goal (x, y, theta)
00174                                 0, 0, 0, //goal tolerance
00175                                 perimeterptsV, costmap_ros_->getCostmap()->getResolution(), nominalvel_mpersecs,
00176                                 timetoturn45degsinplace_secs, obst_cost_thresh,
00177                                 primitive_filename_.c_str());
00178       current_env_width_ = costmap_ros_->getCostmap()->getSizeInCellsX();
00179       current_env_height_ = costmap_ros_->getCostmap()->getSizeInCellsY();
00180     }
00181     catch(SBPL_Exception *e){
00182       ROS_ERROR("SBPL encountered a fatal exception: %s", e->what());
00183       ret = false;
00184     }
00185     if(!ret){
00186       ROS_ERROR("SBPL initialization failed!");
00187       exit(1);
00188     }
00189     for (ssize_t ix(0); ix < costmap_ros_->getCostmap()->getSizeInCellsX(); ++ix)
00190       for (ssize_t iy(0); iy < costmap_ros_->getCostmap()->getSizeInCellsY(); ++iy)
00191         env_->UpdateCost(ix, iy, costMapCostToSBPLCost(costmap_ros_->getCostmap()->getCost(ix,iy)));
00192 
00193     if ("ARAPlanner" == planner_type_){
00194       ROS_INFO("Planning with ARA*");
00195       planner_ = new ARAPlanner(env_, forward_search_);
00196     }
00197     else if ("ADPlanner" == planner_type_){
00198       ROS_INFO("Planning with AD*");
00199       planner_ = new ADPlanner(env_, forward_search_);
00200     }
00201     else{
00202       ROS_ERROR("ARAPlanner and ADPlanner are currently the only supported planners!\n");
00203       exit(1);
00204     }
00205 
00206     ROS_INFO("[sbpl_lattice_planner] Initialized successfully");
00207     plan_pub_ = private_nh.advertise<nav_msgs::Path>("plan", 1);
00208     stats_publisher_ = private_nh.advertise<sbpl_lattice_planner::SBPLLatticePlannerStats>("sbpl_lattice_planner_stats", 1);
00209     
00210     initialized_ = true;
00211   }
00212 }
00213   
00214 //Taken from Sachin's sbpl_cart_planner
00215 //This rescales the costmap according to a rosparam which sets the obstacle cost
00216 unsigned char SBPLLatticePlanner::costMapCostToSBPLCost(unsigned char newcost){
00217   if(newcost == costmap_2d::LETHAL_OBSTACLE)
00218     return lethal_obstacle_;
00219   else if(newcost == costmap_2d::INSCRIBED_INFLATED_OBSTACLE)
00220     return inscribed_inflated_obstacle_;
00221   else if(newcost == 0 || newcost == costmap_2d::NO_INFORMATION)
00222     return 0;
00223   else {
00224     unsigned char sbpl_cost = newcost / sbpl_cost_multiplier_;
00225     if (sbpl_cost == 0)
00226       sbpl_cost = 1;
00227     return sbpl_cost;
00228   }
00229 }
00230 
00231 void SBPLLatticePlanner::publishStats(int solution_cost, int solution_size, 
00232                                       const geometry_msgs::PoseStamped& start, 
00233                                       const geometry_msgs::PoseStamped& goal){
00234   // Fill up statistics and publish
00235   sbpl_lattice_planner::SBPLLatticePlannerStats stats;
00236   stats.initial_epsilon = initial_epsilon_;
00237   stats.plan_to_first_solution = false;
00238   stats.final_number_of_expands = planner_->get_n_expands();
00239   stats.allocated_time = allocated_time_;
00240 
00241   stats.time_to_first_solution = planner_->get_initial_eps_planning_time();
00242   stats.actual_time = planner_->get_final_eps_planning_time();
00243   stats.number_of_expands_initial_solution = planner_->get_n_expands_init_solution();
00244   stats.final_epsilon = planner_->get_final_epsilon();
00245 
00246   stats.solution_cost = solution_cost;
00247   stats.path_size = solution_size;
00248   stats.start = start;
00249   stats.goal = goal;
00250   stats_publisher_.publish(stats);
00251 }
00252 
00253 unsigned char SBPLLatticePlanner::computeCircumscribedCost() {
00254   unsigned char result = 0;
00255 
00256   if (!costmap_ros_) {
00257     ROS_ERROR("Costmap is not initialized");
00258     return 0;
00259   }
00260 
00261   // check if the costmap has an inflation layer
00262   for(std::vector<boost::shared_ptr<costmap_2d::Layer> >::const_iterator layer = costmap_ros_->getLayeredCostmap()->getPlugins()->begin();
00263       layer != costmap_ros_->getLayeredCostmap()->getPlugins()->end();
00264       ++layer) {
00265     boost::shared_ptr<costmap_2d::InflationLayer> inflation_layer = boost::dynamic_pointer_cast<costmap_2d::InflationLayer>(*layer);
00266     if (!inflation_layer) continue;
00267 
00268     result = costMapCostToSBPLCost(inflation_layer->computeCost(costmap_ros_->getLayeredCostmap()->getCircumscribedRadius() / costmap_ros_->getCostmap()->getResolution()));
00269   }
00270   return result;
00271 }
00272 
00273 bool SBPLLatticePlanner::makePlan(const geometry_msgs::PoseStamped& start,
00274                                  const geometry_msgs::PoseStamped& goal,
00275                                  std::vector<geometry_msgs::PoseStamped>& plan){
00276   if(!initialized_){
00277     ROS_ERROR("Global planner is not initialized");
00278     return false;
00279   }
00280 
00281   bool do_init = false;
00282   if (current_env_width_ != costmap_ros_->getCostmap()->getSizeInCellsX() ||
00283       current_env_height_ != costmap_ros_->getCostmap()->getSizeInCellsY()) {
00284     ROS_INFO("Costmap dimensions have changed from (%d x %d) to (%d x %d), reinitializing sbpl_lattice_planner.",
00285              current_env_width_, current_env_height_,
00286              costmap_ros_->getCostmap()->getSizeInCellsX(), costmap_ros_->getCostmap()->getSizeInCellsY());
00287     do_init = true;
00288   }
00289   else if (footprint_ != costmap_ros_->getRobotFootprint()) {
00290     ROS_INFO("Robot footprint has changed, reinitializing sbpl_lattice_planner.");
00291     do_init = true;
00292   }
00293   else if (circumscribed_cost_ != computeCircumscribedCost()) {
00294     ROS_INFO("Cost at circumscribed radius has changed, reinitializing sbpl_lattice_planner.");
00295     do_init = true;
00296   }
00297 
00298   if (do_init) {
00299     initialized_ = false;
00300     delete planner_;
00301     planner_ = NULL;
00302     delete env_;
00303     env_ = NULL;
00304     initialize(name_, costmap_ros_);
00305   }
00306 
00307   plan.clear();
00308 
00309   ROS_INFO("[sbpl_lattice_planner] getting start point (%g,%g) goal point (%g,%g)",
00310            start.pose.position.x, start.pose.position.y,goal.pose.position.x, goal.pose.position.y);
00311   double theta_start = 2 * atan2(start.pose.orientation.z, start.pose.orientation.w);
00312   double theta_goal = 2 * atan2(goal.pose.orientation.z, goal.pose.orientation.w);
00313 
00314   try{
00315     int ret = env_->SetStart(start.pose.position.x - costmap_ros_->getCostmap()->getOriginX(), start.pose.position.y - costmap_ros_->getCostmap()->getOriginY(), theta_start);
00316     if(ret < 0 || planner_->set_start(ret) == 0){
00317       ROS_ERROR("ERROR: failed to set start state\n");
00318       return false;
00319     }
00320   }
00321   catch(SBPL_Exception *e){
00322     ROS_ERROR("SBPL encountered a fatal exception while setting the start state");
00323     return false;
00324   }
00325 
00326   try{
00327     int ret = env_->SetGoal(goal.pose.position.x - costmap_ros_->getCostmap()->getOriginX(), goal.pose.position.y - costmap_ros_->getCostmap()->getOriginY(), theta_goal);
00328     if(ret < 0 || planner_->set_goal(ret) == 0){
00329       ROS_ERROR("ERROR: failed to set goal state\n");
00330       return false;
00331     }
00332   }
00333   catch(SBPL_Exception *e){
00334     ROS_ERROR("SBPL encountered a fatal exception while setting the goal state");
00335     return false;
00336   }
00337   
00338   int offOnCount = 0;
00339   int onOffCount = 0;
00340   int allCount = 0;
00341   vector<nav2dcell_t> changedcellsV;
00342 
00343   for(unsigned int ix = 0; ix < costmap_ros_->getCostmap()->getSizeInCellsX(); ix++) {
00344     for(unsigned int iy = 0; iy < costmap_ros_->getCostmap()->getSizeInCellsY(); iy++) {
00345 
00346       unsigned char oldCost = env_->GetMapCost(ix,iy);
00347       unsigned char newCost = costMapCostToSBPLCost(costmap_ros_->getCostmap()->getCost(ix,iy));
00348 
00349       if(oldCost == newCost) continue;
00350 
00351       allCount++;
00352 
00353       //first case - off cell goes on
00354 
00355       if((oldCost != costMapCostToSBPLCost(costmap_2d::LETHAL_OBSTACLE) && oldCost != costMapCostToSBPLCost(costmap_2d::INSCRIBED_INFLATED_OBSTACLE)) &&
00356           (newCost == costMapCostToSBPLCost(costmap_2d::LETHAL_OBSTACLE) || newCost == costMapCostToSBPLCost(costmap_2d::INSCRIBED_INFLATED_OBSTACLE))) {
00357         offOnCount++;
00358       }
00359 
00360       if((oldCost == costMapCostToSBPLCost(costmap_2d::LETHAL_OBSTACLE) || oldCost == costMapCostToSBPLCost(costmap_2d::INSCRIBED_INFLATED_OBSTACLE)) &&
00361           (newCost != costMapCostToSBPLCost(costmap_2d::LETHAL_OBSTACLE) && newCost != costMapCostToSBPLCost(costmap_2d::INSCRIBED_INFLATED_OBSTACLE))) {
00362         onOffCount++;
00363       }
00364       env_->UpdateCost(ix, iy, costMapCostToSBPLCost(costmap_ros_->getCostmap()->getCost(ix,iy)));
00365 
00366       nav2dcell_t nav2dcell;
00367       nav2dcell.x = ix;
00368       nav2dcell.y = iy;
00369       changedcellsV.push_back(nav2dcell);
00370     }
00371   }
00372 
00373   try{
00374     if(!changedcellsV.empty()){
00375       StateChangeQuery* scq = new LatticeSCQ(env_, changedcellsV);
00376       planner_->costs_changed(*scq);
00377       delete scq;
00378     }
00379 
00380     if(allCount > force_scratch_limit_)
00381       planner_->force_planning_from_scratch();
00382   }
00383   catch(SBPL_Exception *e){
00384     ROS_ERROR("SBPL failed to update the costmap");
00385     return false;
00386   }
00387 
00388   //setting planner parameters
00389   ROS_DEBUG("allocated:%f, init eps:%f\n",allocated_time_,initial_epsilon_);
00390   planner_->set_initialsolution_eps(initial_epsilon_);
00391   planner_->set_search_mode(false);
00392 
00393   ROS_DEBUG("[sbpl_lattice_planner] run planner");
00394   vector<int> solution_stateIDs;
00395   int solution_cost;
00396   try{
00397     int ret = planner_->replan(allocated_time_, &solution_stateIDs, &solution_cost);
00398     if(ret)
00399       ROS_DEBUG("Solution is found\n");
00400     else{
00401       ROS_INFO("Solution not found\n");
00402       publishStats(solution_cost, 0, start, goal);
00403       return false;
00404     }
00405   }
00406   catch(SBPL_Exception *e){
00407     ROS_ERROR("SBPL encountered a fatal exception while planning");
00408     return false;
00409   }
00410 
00411   ROS_DEBUG("size of solution=%d", (int)solution_stateIDs.size());
00412 
00413   vector<EnvNAVXYTHETALAT3Dpt_t> sbpl_path;
00414   try{
00415     env_->ConvertStateIDPathintoXYThetaPath(&solution_stateIDs, &sbpl_path);
00416   }
00417   catch(SBPL_Exception *e){
00418     ROS_ERROR("SBPL encountered a fatal exception while reconstructing the path");
00419     return false;
00420   }
00421   // if the plan has zero points, add a single point to make move_base happy
00422   if( sbpl_path.size() == 0 ) {
00423     EnvNAVXYTHETALAT3Dpt_t s(
00424         start.pose.position.x - costmap_ros_->getCostmap()->getOriginX(),
00425         start.pose.position.y - costmap_ros_->getCostmap()->getOriginY(),
00426         theta_start);
00427     sbpl_path.push_back(s);
00428   }
00429 
00430   ROS_DEBUG("Plan has %d points.\n", (int)sbpl_path.size());
00431   ros::Time plan_time = ros::Time::now();
00432 
00433   //create a message for the plan 
00434   nav_msgs::Path gui_path;
00435   gui_path.poses.resize(sbpl_path.size());
00436   gui_path.header.frame_id = costmap_ros_->getGlobalFrameID();
00437   gui_path.header.stamp = plan_time;
00438   for(unsigned int i=0; i<sbpl_path.size(); i++){
00439     geometry_msgs::PoseStamped pose;
00440     pose.header.stamp = plan_time;
00441     pose.header.frame_id = costmap_ros_->getGlobalFrameID();
00442 
00443     pose.pose.position.x = sbpl_path[i].x + costmap_ros_->getCostmap()->getOriginX();
00444     pose.pose.position.y = sbpl_path[i].y + costmap_ros_->getCostmap()->getOriginY();
00445     pose.pose.position.z = start.pose.position.z;
00446 
00447     tf2::Quaternion temp;
00448     temp.setRPY(0,0,sbpl_path[i].theta);
00449     pose.pose.orientation.x = temp.getX();
00450     pose.pose.orientation.y = temp.getY();
00451     pose.pose.orientation.z = temp.getZ();
00452     pose.pose.orientation.w = temp.getW();
00453 
00454     plan.push_back(pose);
00455 
00456     gui_path.poses[i] = plan[i];
00457   }
00458   plan_pub_.publish(gui_path);
00459   publishStats(solution_cost, sbpl_path.size(), start, goal);
00460 
00461   return true;
00462 }
00463 };


sbpl_lattice_planner
Author(s): Michael Phillips
autogenerated on Thu Mar 28 2019 03:37:42