00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 #include <move_base/move_base.h>
00039 #include <boost/algorithm/string.hpp>
00040 
00041 namespace move_base {
00042 
00043   MoveBase::MoveBase(std::string name, tf::TransformListener& tf) :
00044     tf_(tf),
00045     as_(NULL),
00046     tc_(NULL), planner_costmap_ros_(NULL), controller_costmap_ros_(NULL),
00047     planner_(NULL), bgp_loader_("nav_core", "nav_core::BaseGlobalPlanner"),
00048     blp_loader_("nav_core", "nav_core::BaseLocalPlanner"), 
00049     recovery_loader_("nav_core", "nav_core::RecoveryBehavior"),
00050     planner_plan(NULL), latest_plan(NULL), controller_plan(NULL),
00051     runPlanner(false){
00052 
00053     as_ = new MoveBaseActionServer(ros::NodeHandle(), "move_base", boost::bind(&MoveBase::executeCb, this, _1), false);
00054     
00055     ros::NodeHandle private_nh("~");
00056     ros::NodeHandle nh;
00057 
00058     control_failure_recovery_ = false;
00059 
00060     
00061     std::string global_planner, local_planner;
00062     private_nh.param("base_global_planner", global_planner, std::string("navfn/NavfnROS"));
00063     private_nh.param("base_local_planner", local_planner, std::string("base_local_planner/TrajectoryPlannerROS"));
00064     private_nh.param("global_costmap/robot_base_frame", robot_base_frame_, std::string("base_link"));
00065     private_nh.param("global_costmap/global_frame", global_frame_, std::string("/map"));
00066     private_nh.param("controller_frequency", controller_frequency_, 20.0);
00067     private_nh.param("controller_patience", controller_patience_, 15.0);
00068     private_nh.param("planner_frequency", planner_frequency_, 0.0);
00069     private_nh.param("planner_patience", planner_patience_, 5.0);
00070 
00071 
00072     
00073     planner_plan = new std::vector<geometry_msgs::PoseStamped>();
00074     latest_plan = new std::vector<geometry_msgs::PoseStamped>();
00075     controller_plan = new std::vector<geometry_msgs::PoseStamped>();
00076 
00077     
00078     planner_lock = new boost::unique_lock<boost::mutex>(planner_mutex);
00079     planner_lock->unlock();
00080     
00081     planner_thread = new boost::thread(boost::bind(&MoveBase::planThread, this));
00082 
00083 
00084     
00085     vel_pub_ = nh.advertise<geometry_msgs::Twist>("cmd_vel", 1);
00086     current_goal_pub_ = private_nh.advertise<geometry_msgs::PoseStamped>("current_goal", 0 );
00087 
00088     ros::NodeHandle action_nh("move_base");
00089     action_goal_pub_ = action_nh.advertise<move_base_msgs::MoveBaseActionGoal>("goal", 1);
00090 
00091     
00092     
00093     
00094     ros::NodeHandle simple_nh("move_base_simple");
00095     goal_sub_ = simple_nh.subscribe<geometry_msgs::PoseStamped>("goal", 1, boost::bind(&MoveBase::goalCB, this, _1));
00096 
00097     
00098     private_nh.param("local_costmap/inscribed_radius", inscribed_radius_, 0.325);
00099     private_nh.param("local_costmap/circumscribed_radius", circumscribed_radius_, 0.46);
00100     private_nh.param("clearing_radius", clearing_radius_, circumscribed_radius_);
00101     private_nh.param("conservative_reset_dist", conservative_reset_dist_, 3.0);
00102 
00103     private_nh.param("shutdown_costmaps", shutdown_costmaps_, false);
00104     private_nh.param("clearing_roatation_allowed", clearing_roatation_allowed_, true);
00105     private_nh.param("recovery_behavior_enabled", recovery_behavior_enabled_, true);
00106 
00107     
00108     planner_costmap_ros_ = new costmap_2d::Costmap2DROS("global_costmap", tf_);
00109     planner_costmap_ros_->pause();
00110 
00111     
00112     try {
00113       
00114       if(!bgp_loader_.isClassAvailable(global_planner)){
00115         std::vector<std::string> classes = bgp_loader_.getDeclaredClasses();
00116         for(unsigned int i = 0; i < classes.size(); ++i){
00117           if(global_planner == bgp_loader_.getName(classes[i])){
00118             
00119             ROS_WARN("Planner specifications should now include the package name. You are using a deprecated API. Please switch from %s to %s in your yaml file.",
00120                 global_planner.c_str(), classes[i].c_str());
00121             global_planner = classes[i];
00122             break;
00123           }
00124         }
00125       }
00126 
00127       planner_ = bgp_loader_.createClassInstance(global_planner);
00128       planner_->initialize(bgp_loader_.getName(global_planner), planner_costmap_ros_);
00129     } catch (const pluginlib::PluginlibException& ex)
00130     {
00131       ROS_FATAL("Failed to create the %s planner, are you sure it is properly registered and that the containing library is built? Exception: %s", global_planner.c_str(), ex.what());
00132       exit(0);
00133     }
00134 
00135     ROS_INFO("MAP SIZE: %d, %d", planner_costmap_ros_->getSizeInCellsX(), planner_costmap_ros_->getSizeInCellsY());
00136 
00137     
00138     controller_costmap_ros_ = new costmap_2d::Costmap2DROS("local_costmap", tf_);
00139     controller_costmap_ros_->pause();
00140 
00141     
00142     try {
00143       
00144       if(!blp_loader_.isClassAvailable(local_planner)){
00145         std::vector<std::string> classes = blp_loader_.getDeclaredClasses();
00146         for(unsigned int i = 0; i < classes.size(); ++i){
00147           if(local_planner == blp_loader_.getName(classes[i])){
00148             
00149             ROS_WARN("Planner specifications should now include the package name. You are using a deprecated API. Please switch from %s to %s in your yaml file.",
00150                 local_planner.c_str(), classes[i].c_str());
00151             local_planner = classes[i];
00152             break;
00153           }
00154         }
00155       }
00156 
00157       tc_ = blp_loader_.createClassInstance(local_planner);
00158       tc_->initialize(blp_loader_.getName(local_planner), &tf_, controller_costmap_ros_);
00159     } catch (const pluginlib::PluginlibException& ex)
00160     {
00161       ROS_FATAL("Failed to create the %s planner, are you sure it is properly registered and that the containing library is built? Exception: %s", local_planner.c_str(), ex.what());
00162       exit(0);
00163     }
00164 
00165     
00166     planner_costmap_ros_->start();
00167     controller_costmap_ros_->start();
00168 
00169     
00170     make_plan_srv_ = private_nh.advertiseService("make_plan", &MoveBase::planService, this);
00171 
00172     
00173     clear_unknown_srv_ = private_nh.advertiseService("clear_unknown_space", &MoveBase::clearUnknownService, this);
00174 
00175     
00176     planner_costmap_ros_->clearNonLethalWindow(circumscribed_radius_ * 4, circumscribed_radius_ * 4);
00177     controller_costmap_ros_->clearNonLethalWindow(circumscribed_radius_ * 4, circumscribed_radius_ * 4);
00178 
00179     
00180     if(shutdown_costmaps_){
00181       ROS_DEBUG("Stopping costmaps initially");
00182       planner_costmap_ros_->stop();
00183       controller_costmap_ros_->stop();
00184     }
00185 
00186     
00187     if(!loadRecoveryBehaviors(private_nh)){
00188       loadDefaultRecoveryBehaviors();
00189     }
00190 
00191     
00192     state_ = PLANNING;
00193 
00194     
00195     recovery_index_ = 0;
00196 
00197     
00198     as_->start();
00199   }
00200 
00201   void MoveBase::goalCB(const geometry_msgs::PoseStamped::ConstPtr& goal){
00202     ROS_DEBUG("In ROS goal callback, wrapping the PoseStamped in the action message and re-sending to the server.");
00203     move_base_msgs::MoveBaseActionGoal action_goal;
00204     action_goal.header.stamp = ros::Time::now();
00205     action_goal.goal.target_pose = *goal;
00206 
00207     action_goal_pub_.publish(action_goal);
00208   }
00209 
00210   void MoveBase::clearCostmapWindows(double size_x, double size_y){
00211     tf::Stamped<tf::Pose> global_pose;
00212 
00213     
00214     planner_costmap_ros_->getRobotPose(global_pose);
00215 
00216     std::vector<geometry_msgs::Point> clear_poly;
00217     double x = global_pose.getOrigin().x();
00218     double y = global_pose.getOrigin().y();
00219     geometry_msgs::Point pt;
00220 
00221     pt.x = x - size_x / 2;
00222     pt.y = y - size_x / 2;
00223     clear_poly.push_back(pt);
00224 
00225     pt.x = x + size_x / 2;
00226     pt.y = y - size_x / 2;
00227     clear_poly.push_back(pt);
00228 
00229     pt.x = x + size_x / 2;
00230     pt.y = y + size_x / 2;
00231     clear_poly.push_back(pt);
00232 
00233     pt.x = x - size_x / 2;
00234     pt.y = y + size_x / 2;
00235     clear_poly.push_back(pt);
00236 
00237     planner_costmap_ros_->setConvexPolygonCost(clear_poly, costmap_2d::FREE_SPACE);
00238 
00239     
00240     controller_costmap_ros_->getRobotPose(global_pose);
00241 
00242     clear_poly.clear();
00243     x = global_pose.getOrigin().x();
00244     y = global_pose.getOrigin().y();
00245 
00246     pt.x = x - size_x / 2;
00247     pt.y = y - size_x / 2;
00248     clear_poly.push_back(pt);
00249 
00250     pt.x = x + size_x / 2;
00251     pt.y = y - size_x / 2;
00252     clear_poly.push_back(pt);
00253 
00254     pt.x = x + size_x / 2;
00255     pt.y = y + size_x / 2;
00256     clear_poly.push_back(pt);
00257 
00258     pt.x = x - size_x / 2;
00259     pt.y = y + size_x / 2;
00260     clear_poly.push_back(pt);
00261 
00262     controller_costmap_ros_->setConvexPolygonCost(clear_poly, costmap_2d::FREE_SPACE);
00263   }
00264 
00265   bool MoveBase::clearUnknownService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp){
00266     
00267     planner_costmap_ros_->clearNonLethalWindow(circumscribed_radius_ * 4, circumscribed_radius_ * 4);
00268     controller_costmap_ros_->clearNonLethalWindow(circumscribed_radius_ * 4, circumscribed_radius_ * 4);
00269     return true;
00270   }
00271 
00272   bool MoveBase::planService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp){
00273     if(as_->isActive()){
00274       ROS_ERROR("move_base must be in an inactive state to make a plan for an external user");
00275       return false;
00276     }
00277 
00278     
00279     if(planner_costmap_ros_ == NULL){
00280       ROS_ERROR("move_base cannot make a plan for you because it doesn't have a costmap");
00281       return false;
00282     }
00283 
00284     tf::Stamped<tf::Pose> global_pose;
00285     if(!planner_costmap_ros_->getRobotPose(global_pose)){
00286       ROS_ERROR("move_base cannot make a plan for you because it could not get the start pose of the robot");
00287       return false;
00288     }
00289 
00290     geometry_msgs::PoseStamped start;
00291     tf::poseStampedTFToMsg(global_pose, start);
00292 
00293     
00294     clearCostmapWindows(2 * clearing_radius_, 2 * clearing_radius_);
00295 
00296     
00297     
00298     double resolution = planner_costmap_ros_->getResolution();
00299     std::vector<geometry_msgs::PoseStamped> global_plan;
00300     geometry_msgs::PoseStamped p;
00301     p = req.goal;
00302     p.pose.position.y = req.goal.pose.position.y - req.tolerance;
00303     bool found_legal = false;
00304     while(!found_legal && p.pose.position.y <= req.goal.pose.position.y + req.tolerance){
00305       p.pose.position.x = req.goal.pose.position.x - req.tolerance;
00306       while(!found_legal && p.pose.position.x <= req.goal.pose.position.x + req.tolerance){
00307         if(planner_->makePlan(start, p, global_plan)){
00308           if(!global_plan.empty()){
00309             global_plan.push_back(p);
00310             found_legal = true;
00311           }
00312           else
00313             ROS_DEBUG("Failed to find a  plan to point (%.2f, %.2f)", p.pose.position.x, p.pose.position.y);
00314         }
00315         p.pose.position.x += resolution*3.0;
00316       }
00317       p.pose.position.y += resolution*3.0;
00318     }
00319 
00320     
00321     resp.plan.poses.resize(global_plan.size());
00322     for(unsigned int i = 0; i < global_plan.size(); ++i){
00323       resp.plan.poses[i] = global_plan[i];
00324     }
00325 
00326 
00327 
00328     return true;
00329   }
00330 
00331   MoveBase::~MoveBase(){
00332     recovery_behaviors_.clear();
00333 
00334     if(as_ != NULL)
00335       delete as_;
00336 
00337     if(planner_ != NULL)
00338       delete planner_;
00339 
00340     if(tc_ != NULL)
00341       delete tc_;
00342 
00343     if(planner_costmap_ros_ != NULL)
00344       delete planner_costmap_ros_;
00345 
00346     if(controller_costmap_ros_ != NULL)
00347       delete controller_costmap_ros_;
00348 
00349     planner_thread->join();
00350 
00351     delete planner_plan;
00352     delete latest_plan;
00353     delete controller_plan;
00354     delete planner_lock;
00355   }
00356 
00357   bool MoveBase::makePlan(const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan){
00358     
00359     plan.clear();
00360 
00361     
00362     if(planner_costmap_ros_ == NULL)
00363       return false;
00364 
00365     
00366     tf::Stamped<tf::Pose> global_pose;
00367     if(!planner_costmap_ros_->getRobotPose(global_pose))
00368       return false;
00369 
00370     geometry_msgs::PoseStamped start;
00371     tf::poseStampedTFToMsg(global_pose, start);
00372 
00373     
00374     if(!planner_->makePlan(start, goal, plan) || plan.empty()){
00375       ROS_DEBUG("Failed to find a  plan to point (%.2f, %.2f)", goal.pose.position.x, goal.pose.position.y);
00376       return false;
00377     }
00378 
00379     return true;
00380   }
00381 
00382   void MoveBase::publishZeroVelocity(){
00383     geometry_msgs::Twist cmd_vel;
00384     cmd_vel.linear.x = 0.0;
00385     cmd_vel.linear.y = 0.0;
00386     cmd_vel.angular.z = 0.0;
00387     vel_pub_.publish(cmd_vel);
00388 
00389   }
00390 
00391   bool MoveBase::isQuaternionValid(const geometry_msgs::Quaternion& q){
00392     
00393     if(!std::isfinite(q.x) || !std::isfinite(q.y) || !std::isfinite(q.z) || !std::isfinite(q.w)){
00394       ROS_ERROR("Quaternion has nans or infs... discarding as a navigation goal");
00395       return false;
00396     }
00397 
00398     tf::Quaternion tf_q(q.x, q.y, q.z, q.w);
00399 
00400     
00401     if(tf_q.length2() < 1e-6){
00402       ROS_ERROR("Quaternion has length close to zero... discarding as navigation goal");
00403       return false;
00404     }
00405 
00406     
00407     tf_q.normalize();
00408 
00409     btVector3 up(0, 0, 1);
00410 
00411     double dot = up.dot(up.rotate(tf_q.getAxis(), tf_q.getAngle()));
00412 
00413     if(fabs(dot - 1) > 1e-3){
00414       ROS_ERROR("Quaternion is invalid... for navigation the z-axis of the quaternion must be close to vertical.");
00415       return false;
00416     }
00417 
00418     return true;
00419   }
00420 
00421   geometry_msgs::PoseStamped MoveBase::goalToGlobalFrame(const geometry_msgs::PoseStamped& goal_pose_msg){
00422     std::string global_frame = planner_costmap_ros_->getGlobalFrameID();
00423     tf::Stamped<tf::Pose> goal_pose, global_pose;
00424     poseStampedMsgToTF(goal_pose_msg, goal_pose);
00425 
00426     
00427     
00428     goal_pose.stamp_ = ros::Time();
00429 
00430     try{
00431       tf_.transformPose(global_frame, goal_pose, global_pose);
00432     }
00433     catch(tf::TransformException& ex){
00434       ROS_WARN("Failed to transform the goal pose from %s into the %s frame: %s",
00435           goal_pose.frame_id_.c_str(), global_frame.c_str(), ex.what());
00436       return goal_pose_msg;
00437     }
00438 
00439     geometry_msgs::PoseStamped global_pose_msg;
00440     tf::poseStampedTFToMsg(global_pose, global_pose_msg);
00441     return global_pose_msg;
00442 
00443   }
00444 
00445   void MoveBase::planThread(){
00446     ROS_DEBUG("Starting planner thread...");
00447     ros::NodeHandle n;
00448     ros::Rate r(planner_frequency_);
00449     while(n.ok()){
00450       
00451       
00452       planner_lock->lock();
00453       while(!runPlanner){
00454         
00455         ROS_DEBUG("Planner thread is suspending");
00456         planner_cond.wait(*planner_lock);
00457       }
00458       planner_lock->unlock();
00459       ROS_DEBUG("Planning...");
00460 
00461       
00462       ROS_DEBUG("In planning state");
00463       planner_plan->clear();
00464       bool gotPlan = n.ok() && makePlan(planner_goal, *planner_plan);
00465 
00466       if(gotPlan){
00467         ROS_DEBUG("Got Plan!");
00468         
00469         std::vector<geometry_msgs::PoseStamped>* temp_plan = planner_plan;
00470         plan_lock.lock();
00471         planner_plan = latest_plan;
00472         latest_plan = temp_plan;
00473         plan_lock.unlock();
00474 
00475         last_valid_plan_ = ros::Time::now();
00476 
00477         ROS_DEBUG("Generated a plan from the base_global_planner");
00478         
00479         
00480         if(runPlanner)
00481           state_ = CONTROLLING;
00482         if(planner_frequency_ <= 0)
00483           runPlanner = false;
00484 
00485       }
00486       
00487       else if(state_==PLANNING){
00488         ROS_DEBUG("No Plan...");
00489         ros::Time attempt_end = last_valid_plan_ + ros::Duration(planner_patience_);
00490 
00491         
00492         if(ros::Time::now() > attempt_end){
00493           
00494           state_ = CLEARING;
00495           publishZeroVelocity();
00496 
00497         }
00498       }
00499 
00500       if(planner_frequency_ > 0)
00501         r.sleep();
00502     }
00503   }
00504 
00505   void MoveBase::executeCb(const move_base_msgs::MoveBaseGoalConstPtr& move_base_goal)
00506   {
00507     if(!isQuaternionValid(move_base_goal->target_pose.pose.orientation)){
00508       as_->setAborted(move_base_msgs::MoveBaseResult(), "Aborting on goal because it was sent with an invalid quaternion");
00509       return;
00510     }
00511 
00512     geometry_msgs::PoseStamped goal = goalToGlobalFrame(move_base_goal->target_pose);
00513     
00514     planner_goal = goal;
00515     runPlanner = true;
00516     planner_cond.notify_one();
00517 
00518     current_goal_pub_.publish(goal);
00519     std::vector<geometry_msgs::PoseStamped> global_plan;
00520 
00521     ros::Rate r(controller_frequency_);
00522     if(shutdown_costmaps_){
00523       ROS_DEBUG("Starting up costmaps that were shut down previously");
00524       planner_costmap_ros_->start();
00525       controller_costmap_ros_->start();
00526     }
00527 
00528     
00529     last_valid_control_ = ros::Time::now();
00530     last_valid_plan_ = ros::Time::now();
00531     last_plan_swap_ = ros::Time::now();
00532 
00533     ros::NodeHandle n;
00534     while(n.ok())
00535     {
00536       if(as_->isPreemptRequested()){
00537         if(as_->isNewGoalAvailable()){
00538           
00539           move_base_msgs::MoveBaseGoal new_goal = *as_->acceptNewGoal();
00540 
00541           if(!isQuaternionValid(new_goal.target_pose.pose.orientation)){
00542             as_->setAborted(move_base_msgs::MoveBaseResult(), "Aborting on goal because it was sent with an invalid quaternion");
00543             return;
00544           }
00545 
00546           goal = goalToGlobalFrame(new_goal.target_pose);
00547 
00548           
00549           recovery_index_ = 0;
00550           state_ = PLANNING;
00551           
00552           planner_goal = goal;
00553           runPlanner = true;
00554           planner_cond.notify_one();
00555 
00556           
00557           ROS_DEBUG("move_base has received a goal of x: %.2f, y: %.2f", goal.pose.position.x, goal.pose.position.y);
00558           current_goal_pub_.publish(goal);
00559 
00560           
00561           last_valid_control_ = ros::Time::now();
00562           last_valid_plan_ = ros::Time::now();
00563           last_plan_swap_ = ros::Time::now();
00564         }
00565         else {
00566           
00567           resetState();
00568 
00569           
00570           ROS_DEBUG("Move base preempting the current goal");
00571           as_->setPreempted();
00572 
00573           
00574           return;
00575         }
00576       }
00577 
00578       
00579       ros::WallTime start = ros::WallTime::now();
00580 
00581       
00582       bool done = executeCycle(goal, global_plan);
00583 
00584       
00585       if(done)
00586         return;
00587 
00588       
00589 
00590       ros::WallDuration t_diff = ros::WallTime::now() - start;
00591       ROS_DEBUG("Full control cycle time: %.9f\n", t_diff.toSec());
00592 
00593       r.sleep();
00594       
00595       if(r.cycleTime() > ros::Duration(1 / controller_frequency_) && state_ == CONTROLLING)
00596         ROS_WARN("Control loop missed its desired rate of %.4fHz... the loop actually took %.4f seconds", controller_frequency_, r.cycleTime().toSec());
00597     }
00598     runPlanner = true;
00599     planner_cond.notify_one();
00600 
00601     
00602     as_->setAborted(move_base_msgs::MoveBaseResult(), "Aborting on the goal because the node has been killed");
00603     return;
00604   }
00605 
00606   bool MoveBase::executeCycle(geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& global_plan){
00607     ROS_DEBUG("executeCycle");
00608     
00609     geometry_msgs::Twist cmd_vel;
00610 
00611     
00612     tf::Stamped<tf::Pose> global_pose;
00613     planner_costmap_ros_->getRobotPose(global_pose);
00614     geometry_msgs::PoseStamped current_position;
00615     tf::poseStampedTFToMsg(global_pose, current_position);
00616 
00617     
00618     move_base_msgs::MoveBaseFeedback feedback;
00619     feedback.base_position = current_position;
00620     as_->publishFeedback(feedback);
00621 
00622     
00623     if(!controller_costmap_ros_->isCurrent()){
00624       ROS_WARN("[%s]:Sensor data is out of date, we're not going to allow commanding of the base for safety",ros::this_node::getName().c_str());
00625       publishZeroVelocity();
00626       return false;
00627     }
00628 
00629     
00630     ROS_DEBUG("time compare");
00631     if(last_valid_plan_.toSec() > last_plan_swap_.toSec()){
00632       ROS_DEBUG("new plan...swap pointers");
00633 
00634       
00635       last_plan_swap_ = ros::Time::now();
00636       std::vector<geometry_msgs::PoseStamped>* temp_plan = controller_plan;
00637       plan_lock.lock();
00638       controller_plan = latest_plan;
00639       latest_plan = temp_plan;
00640       plan_lock.unlock();
00641       ROS_DEBUG("pointers swapped!");
00642 
00643       if(!tc_->setPlan(*controller_plan)){
00644         
00645         ROS_ERROR("Failed to pass global plan to the controller, aborting.");
00646         resetState();
00647 
00648         
00649         runPlanner = false;
00650 
00651         as_->setAborted(move_base_msgs::MoveBaseResult(), "Failed to pass global plan to the controller.");
00652         return true;
00653       }
00654 
00655       
00656       if(!control_failure_recovery_)
00657         recovery_index_ = 0;
00658     }
00659     ROS_DEBUG("past time compare");
00660 
00661     
00662     switch(state_){
00663       
00664       case PLANNING:
00665         ROS_DEBUG("Waiting for plan...");
00666         
00667         break;
00668 
00669       
00670       case CONTROLLING:
00671         ROS_DEBUG("In controlling state");
00672 
00673         
00674         if(tc_->isGoalReached()){
00675           ROS_DEBUG("Goal reached!");
00676           resetState();
00677 
00678           
00679           runPlanner = false;
00680 
00681           as_->setSucceeded(move_base_msgs::MoveBaseResult(), "Goal reached.");
00682           return true;
00683         }
00684 
00685         if(tc_->computeVelocityCommands(cmd_vel)){
00686           last_valid_control_ = ros::Time::now();
00687           
00688           vel_pub_.publish(cmd_vel);
00689           control_failure_recovery_ = false;
00690           recovery_index_ = 0;
00691         }
00692         else {
00693           ros::Time attempt_end = last_valid_control_ + ros::Duration(controller_patience_);
00694 
00695           
00696           if(ros::Time::now() > attempt_end){
00697             
00698             publishZeroVelocity();
00699             state_ = CLEARING;
00700             control_failure_recovery_ = true;
00701           }
00702           else{
00703             
00704             last_valid_plan_ = ros::Time::now();
00705             state_ = PLANNING;
00706             publishZeroVelocity();
00707 
00708             
00709             runPlanner = true;
00710             planner_cond.notify_one();
00711           }
00712         }
00713 
00714         break;
00715 
00716       
00717       case CLEARING:
00718         ROS_DEBUG("In clearing/recovery state");
00719         
00720         if(recovery_behavior_enabled_ && recovery_index_ < recovery_behaviors_.size()){
00721           recovery_behaviors_[recovery_index_]->runBehavior();
00722 
00723           
00724           state_ = PLANNING;
00725 
00726           
00727           recovery_index_++;
00728         }
00729         else{
00730           if(control_failure_recovery_){
00731             ROS_ERROR("Aborting because a valid control could not be found. Even after executing all recovery behaviors");
00732 
00733             
00734             runPlanner = false;
00735 
00736             as_->setAborted(move_base_msgs::MoveBaseResult(), "Failed to find a valid control. Even after executing recovery behaviors.");
00737           }
00738           else{
00739             ROS_ERROR("Aborting because a valid plan could not be found. Even after executing all recovery behaviors");
00740 
00741             
00742             runPlanner = false;
00743 
00744             as_->setAborted(move_base_msgs::MoveBaseResult(), "Failed to find a valid plan. Even after executing recovery behaviors.");
00745           }
00746           resetState();
00747           return true;
00748         }
00749         break;
00750       default:
00751         ROS_ERROR("This case should never be reached, something is wrong, aborting");
00752         resetState();
00753 
00754         
00755         runPlanner = false;
00756 
00757         as_->setAborted(move_base_msgs::MoveBaseResult(), "Reached a case that should not be hit in move_base. This is a bug, please report it.");
00758         return true;
00759     }
00760 
00761     
00762     return false;
00763   }
00764 
00765   bool MoveBase::loadRecoveryBehaviors(ros::NodeHandle node){
00766     XmlRpc::XmlRpcValue behavior_list;
00767     if(node.getParam("recovery_behaviors", behavior_list)){
00768       if(behavior_list.getType() == XmlRpc::XmlRpcValue::TypeArray){
00769         for(int i = 0; i < behavior_list.size(); ++i){
00770           if(behavior_list[i].getType() == XmlRpc::XmlRpcValue::TypeStruct){
00771             if(behavior_list[i].hasMember("name") && behavior_list[i].hasMember("type")){
00772               
00773               for(int j = i + 1; j < behavior_list.size(); j++){
00774                 if(behavior_list[j].getType() == XmlRpc::XmlRpcValue::TypeStruct){
00775                   if(behavior_list[j].hasMember("name") && behavior_list[j].hasMember("type")){
00776                     std::string name_i = behavior_list[i]["name"];
00777                     std::string name_j = behavior_list[j]["name"];
00778                     if(name_i == name_j){
00779                       ROS_ERROR("A recovery behavior with the name %s already exists, this is not allowed. Using the default recovery behaviors instead.", 
00780                           name_i.c_str());
00781                       return false;
00782                     }
00783                   }
00784                 }
00785               }
00786             }
00787             else{
00788               ROS_ERROR("Recovery behaviors must have a name and a type and this does not. Using the default recovery behaviors instead.");
00789               return false;
00790             }
00791           }
00792           else{
00793             ROS_ERROR("Recovery behaviors must be specified as maps, but they are XmlRpcType %d. We'll use the default recovery behaviors instead.",
00794                 behavior_list[i].getType());
00795             return false;
00796           }
00797         }
00798 
00799         
00800         for(int i = 0; i < behavior_list.size(); ++i){
00801           try{
00802             
00803             if(!recovery_loader_.isClassAvailable(behavior_list[i]["type"])){
00804               std::vector<std::string> classes = recovery_loader_.getDeclaredClasses();
00805               for(unsigned int i = 0; i < classes.size(); ++i){
00806                 if(behavior_list[i]["type"] == recovery_loader_.getName(classes[i])){
00807                   
00808                   ROS_WARN("Recovery behavior specifications should now include the package name. You are using a deprecated API. Please switch from %s to %s in your yaml file.",
00809                       std::string(behavior_list[i]["type"]).c_str(), classes[i].c_str());
00810                   behavior_list[i]["type"] = classes[i];
00811                   break;
00812                 }
00813               }
00814             }
00815 
00816             boost::shared_ptr<nav_core::RecoveryBehavior> behavior(recovery_loader_.createClassInstance(behavior_list[i]["type"]));
00817 
00818             
00819             if(behavior.get() == NULL){
00820               ROS_ERROR("The ClassLoader returned a null pointer without throwing an exception. This should not happen");
00821               return false;
00822             }
00823 
00824             
00825             behavior->initialize(behavior_list[i]["name"], &tf_, planner_costmap_ros_, controller_costmap_ros_);
00826             recovery_behaviors_.push_back(behavior);
00827           }
00828           catch(pluginlib::PluginlibException& ex){
00829             ROS_ERROR("Failed to load a plugin. Using default recovery behaviors. Error: %s", ex.what());
00830             return false;
00831           }
00832         }
00833       }
00834       else{
00835         ROS_ERROR("The recovery behavior specification must be a list, but is of XmlRpcType %d. We'll use the default recovery behaviors instead.", 
00836             behavior_list.getType());
00837         return false;
00838       }
00839     }
00840     else{
00841       
00842       return false;
00843     }
00844 
00845     
00846     return true;
00847   }
00848 
00849   
00850   void MoveBase::loadDefaultRecoveryBehaviors(){
00851     recovery_behaviors_.clear();
00852     try{
00853       
00854       ros::NodeHandle n("~");
00855       n.setParam("conservative_reset/reset_distance", conservative_reset_dist_);
00856       n.setParam("aggressive_reset/reset_distance", circumscribed_radius_ * 4);
00857 
00858       
00859       boost::shared_ptr<nav_core::RecoveryBehavior> cons_clear(recovery_loader_.createClassInstance("clear_costmap_recovery/ClearCostmapRecovery"));
00860       cons_clear->initialize("conservative_reset", &tf_, planner_costmap_ros_, controller_costmap_ros_);
00861       recovery_behaviors_.push_back(cons_clear);
00862 
00863       
00864       boost::shared_ptr<nav_core::RecoveryBehavior> rotate(recovery_loader_.createClassInstance("rotate_recovery/RotateRecovery"));
00865       if(clearing_roatation_allowed_){
00866         boost::shared_ptr<nav_core::RecoveryBehavior> rotate(recovery_loader_.createClassInstance("rotate_recovery/RotateRecovery"));
00867         rotate->initialize("rotate_recovery", &tf_, planner_costmap_ros_, controller_costmap_ros_);
00868         recovery_behaviors_.push_back(rotate);
00869       }
00870 
00871       
00872       boost::shared_ptr<nav_core::RecoveryBehavior> ags_clear(recovery_loader_.createClassInstance("clear_costmap_recovery/ClearCostmapRecovery"));
00873       ags_clear->initialize("aggressive_reset", &tf_, planner_costmap_ros_, controller_costmap_ros_);
00874       recovery_behaviors_.push_back(ags_clear);
00875 
00876       
00877       if(clearing_roatation_allowed_){
00878         recovery_behaviors_.push_back(rotate);
00879       }
00880     }
00881     catch(pluginlib::PluginlibException& ex){
00882       ROS_FATAL("Failed to load a plugin. This should not happen on default recovery behaviors. Error: %s", ex.what());
00883     }
00884 
00885     return;
00886   }
00887 
00888   void MoveBase::resetState(){
00889     state_ = PLANNING;
00890     recovery_index_ = 0;
00891     control_failure_recovery_ = false;
00892     publishZeroVelocity();
00893 
00894     
00895     if(shutdown_costmaps_){
00896       ROS_DEBUG("Stopping costmaps");
00897       planner_costmap_ros_->stop();
00898       controller_costmap_ros_->stop();
00899     }
00900   }
00901 
00902 };
00903 
00904 int main(int argc, char** argv){
00905   ros::init(argc, argv, "move_base_node");
00906   tf::TransformListener tf(ros::Duration(10));
00907 
00908   move_base::MoveBase move_base("move_base", tf);
00909 
00910   
00911   ros::spin();
00912 
00913   return(0);
00914 
00915 }