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