sbpl_recovery.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2009, 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  *********************************************************************/
00037 
00038 #include <sbpl_recovery/sbpl_recovery.h>
00039 #include <pluginlib/class_list_macros.hpp>
00040 
00041 PLUGINLIB_EXPORT_CLASS(sbpl_recovery::SBPLRecovery, nav_core::RecoveryBehavior)
00042 
00043 namespace sbpl_recovery
00044 {
00045   SBPLRecovery::SBPLRecovery():
00046     global_costmap_(NULL),
00047     local_costmap_(NULL),
00048     tf_(NULL),
00049     initialized_(false)
00050   {
00051   }
00052 
00053   void SBPLRecovery::initialize (std::string n, tf::TransformListener* tf,
00054       costmap_2d::Costmap2DROS* global_costmap,
00055       costmap_2d::Costmap2DROS* local_costmap)
00056   {
00057     ros::NodeHandle nh = ros::NodeHandle();
00058     ros::NodeHandle p_nh = ros::NodeHandle("~/" + n);
00059 
00060     std::string plan_topic;
00061     p_nh.param("plan_topic", plan_topic, std::string("NavfnROS/plan"));
00062     p_nh.param("control_frequency", control_frequency_, 10.0);
00063     p_nh.param("controller_patience", controller_patience_, 5.0);
00064     p_nh.param("planning_attempts", planning_attempts_, 3);
00065     p_nh.param("attempts_per_run", attempts_per_run_, 3);
00066     p_nh.param("use_local_frame", use_local_frame_, true);
00067 
00068     double planning_distance;
00069     p_nh.param("planning_distance", planning_distance, 2.0);
00070     sq_planning_distance_ = planning_distance * planning_distance;
00071 
00072     //we need to initialize our costmaps
00073     global_costmap_ = global_costmap;
00074     local_costmap_ = local_costmap;
00075     tf_ = tf;
00076 
00077     //we need to initialize our local and global planners
00078     if(use_local_frame_)
00079       global_planner_.initialize(n + "/sbpl_lattice_planner", local_costmap_);
00080     else
00081       global_planner_.initialize(n + "/sbpl_lattice_planner", global_costmap_);
00082 
00083     local_planner_.initialize(n + "/pose_follower", tf, local_costmap_);
00084 
00085     //we'll need to subscribe to get the latest plan information 
00086     vel_pub_ = nh.advertise<geometry_msgs::Twist>("cmd_vel", 1);
00087 
00088     ros::NodeHandle node_nh("~/");
00089     plan_sub_ = node_nh.subscribe<nav_msgs::Path>(plan_topic, 1, boost::bind(&SBPLRecovery::planCB, this, _1));
00090     initialized_ = true;
00091   }
00092 
00093   void SBPLRecovery::planCB(const nav_msgs::Path::ConstPtr& plan)
00094   {
00095     //just copy the plan data over
00096 
00097     tf::Stamped<tf::Pose> global_pose;
00098     local_costmap_->getRobotPose(global_pose);
00099 
00100     costmap_2d::Costmap2D costmap;
00101     costmap = *(local_costmap_->getCostmap());
00102 
00103     if(use_local_frame_)
00104     {
00105       std::vector<geometry_msgs::PoseStamped> transformed_plan;
00106       if(base_local_planner::transformGlobalPlan(*tf_, plan->poses, global_pose, costmap, local_costmap_->getGlobalFrameID(), transformed_plan))
00107       {
00108         boost::mutex::scoped_lock l(plan_mutex_);
00109         if(!transformed_plan.empty())
00110           plan_.header = transformed_plan[0].header;
00111         plan_.poses = transformed_plan;
00112       }
00113       else
00114         ROS_WARN("Could not transform to frame of the local recovery");
00115     }
00116     else
00117     {
00118       boost::mutex::scoped_lock l(plan_mutex_);
00119       plan_ = *plan;
00120     }
00121   }
00122 
00123   double SBPLRecovery::sqDistance(const geometry_msgs::PoseStamped& p1, 
00124       const geometry_msgs::PoseStamped& p2)
00125   {
00126     return (p1.pose.position.x - p2.pose.position.x) * (p1.pose.position.x - p2.pose.position.x) +
00127       (p1.pose.position.y - p2.pose.position.y) * (p1.pose.position.y - p2.pose.position.y);
00128   }
00129 
00130   std::vector<geometry_msgs::PoseStamped> SBPLRecovery::makePlan()
00131   {
00132     boost::mutex::scoped_lock l(plan_mutex_);
00133     std::vector<geometry_msgs::PoseStamped> sbpl_plan;
00134 
00135     tf::Stamped<tf::Pose> global_pose;
00136     if(use_local_frame_)
00137     {
00138       if(!local_costmap_->getRobotPose(global_pose))
00139       {
00140         ROS_ERROR("SBPL recovery behavior could not get the current pose of the robot. Doing nothing.");
00141         return sbpl_plan;
00142       }
00143     }
00144     else
00145     {
00146       if(!global_costmap_->getRobotPose(global_pose))
00147       {
00148         ROS_ERROR("SBPL recovery behavior could not get the current pose of the robot. Doing nothing.");
00149         return sbpl_plan;
00150       }
00151     }
00152 
00153     geometry_msgs::PoseStamped start;
00154     tf::poseStampedTFToMsg(global_pose, start);
00155 
00156     //first, we want to walk far enough along the path that we get to a point
00157     //that is within the recovery distance from the robot. Otherwise, we might
00158     //move backwards along the plan
00159     unsigned int index = 0;
00160     for(index=0; index < plan_.poses.size(); ++index)
00161     {
00162       if(sqDistance(start, plan_.poses[index]) < sq_planning_distance_)
00163         break;
00164     }
00165 
00166     //next, we want to find a goal point that is far enough away from the robot on the
00167     //original plan and attempt to plan to it
00168     int unsuccessful_attempts = 0;
00169     for(unsigned int i = index; i < plan_.poses.size(); ++i)
00170     {
00171       ROS_DEBUG("SQ Distance: %.2f,  spd: %.2f, start (%.2f, %.2f), goal (%.2f, %.2f)",
00172           sqDistance(start, plan_.poses[i]),
00173           sq_planning_distance_,
00174           start.pose.position.x, start.pose.position.y,
00175           plan_.poses[i].pose.position.x,
00176           plan_.poses[i].pose.position.y);
00177       if(sqDistance(start, plan_.poses[i]) >= sq_planning_distance_ || i == (plan_.poses.size() - 1))
00178       {
00179         ROS_INFO("Calling sbpl planner with start (%.2f, %.2f), goal (%.2f, %.2f)",
00180             start.pose.position.x, start.pose.position.y,
00181             plan_.poses[i].pose.position.x,
00182             plan_.poses[i].pose.position.y);
00183         if(global_planner_.makePlan(start, plan_.poses[i], sbpl_plan) && !sbpl_plan.empty())
00184         {
00185           ROS_INFO("Got a valid plan");
00186           return sbpl_plan;
00187         }
00188         sbpl_plan.clear();
00189 
00190         //make sure that we don't spend forever planning
00191         unsuccessful_attempts++;
00192         if(unsuccessful_attempts >= attempts_per_run_)
00193           return sbpl_plan;
00194       }
00195     }
00196 
00197     return sbpl_plan;
00198   }
00199 
00200   void SBPLRecovery::runBehavior()
00201   {
00202     if(!initialized_)
00203     {
00204       ROS_ERROR("Please initialize this recovery behavior before attempting to run it.");
00205       return;
00206     }
00207 
00208     ROS_INFO("Starting the sbpl recovery behavior");
00209 
00210     for(int i=0; i <= planning_attempts_; ++i)
00211     {
00212       std::vector<geometry_msgs::PoseStamped> sbpl_plan = makePlan();
00213 
00214       if(sbpl_plan.empty())
00215       {
00216         ROS_ERROR("Unable to find a valid pose to plan to on the global plan.");
00217         return;
00218       }
00219 
00220       //ok... now we've got a plan so we need to try to follow it
00221       local_planner_.setPlan(sbpl_plan);
00222       ros::Rate r(control_frequency_);
00223       ros::Time last_valid_control = ros::Time::now();
00224       while(ros::ok() && 
00225           last_valid_control + ros::Duration(controller_patience_) >= ros::Time::now() && 
00226           !local_planner_.isGoalReached())
00227       {
00228         geometry_msgs::Twist cmd_vel;
00229         bool valid_control = local_planner_.computeVelocityCommands(cmd_vel);
00230 
00231         if(valid_control)
00232           last_valid_control = ros::Time::now();
00233 
00234         vel_pub_.publish(cmd_vel);
00235         r.sleep();
00236       }
00237 
00238       if(local_planner_.isGoalReached())
00239         ROS_INFO("The sbpl recovery behavior made it to its desired goal");
00240       else
00241         ROS_WARN("The sbpl recovery behavior failed to make it to its desired goal");
00242     }
00243   }
00244 };


sbpl_recovery
Author(s): Eitan Marder-Eppstein
autogenerated on Thu Mar 28 2019 03:37:43