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 <cmath>
00040
00041 #include <boost/algorithm/string.hpp>
00042 #include <boost/thread.hpp>
00043
00044 #include <geometry_msgs/Twist.h>
00045
00046 namespace move_base {
00047
00048 MoveBase::MoveBase(tf::TransformListener& tf) :
00049 tf_(tf),
00050 as_(NULL),
00051 planner_costmap_ros_(NULL), controller_costmap_ros_(NULL),
00052 bgp_loader_("nav_core", "nav_core::BaseGlobalPlanner"),
00053 blp_loader_("nav_core", "nav_core::BaseLocalPlanner"),
00054 recovery_loader_("nav_core", "nav_core::RecoveryBehavior"),
00055 planner_plan_(NULL), latest_plan_(NULL), controller_plan_(NULL),
00056 runPlanner_(false), setup_(false), p_freq_change_(false), c_freq_change_(false), new_global_plan_(false) {
00057
00058 as_ = new MoveBaseActionServer(ros::NodeHandle(), "move_base", boost::bind(&MoveBase::executeCb, this, _1), false);
00059
00060 ros::NodeHandle private_nh("~");
00061 ros::NodeHandle nh;
00062
00063 recovery_trigger_ = PLANNING_R;
00064
00065
00066 std::string global_planner, local_planner;
00067 private_nh.param("base_global_planner", global_planner, std::string("navfn/NavfnROS"));
00068 private_nh.param("base_local_planner", local_planner, std::string("base_local_planner/TrajectoryPlannerROS"));
00069 private_nh.param("global_costmap/robot_base_frame", robot_base_frame_, std::string("base_link"));
00070 private_nh.param("global_costmap/global_frame", global_frame_, std::string("/map"));
00071 private_nh.param("planner_frequency", planner_frequency_, 0.0);
00072 private_nh.param("controller_frequency", controller_frequency_, 20.0);
00073 private_nh.param("planner_patience", planner_patience_, 5.0);
00074 private_nh.param("controller_patience", controller_patience_, 15.0);
00075 private_nh.param("max_planning_retries", max_planning_retries_, -1);
00076
00077 private_nh.param("oscillation_timeout", oscillation_timeout_, 0.0);
00078 private_nh.param("oscillation_distance", oscillation_distance_, 0.5);
00079
00080
00081 planner_plan_ = new std::vector<geometry_msgs::PoseStamped>();
00082 latest_plan_ = new std::vector<geometry_msgs::PoseStamped>();
00083 controller_plan_ = new std::vector<geometry_msgs::PoseStamped>();
00084
00085
00086 planner_thread_ = new boost::thread(boost::bind(&MoveBase::planThread, this));
00087
00088
00089 vel_pub_ = nh.advertise<geometry_msgs::Twist>("cmd_vel", 1);
00090 current_goal_pub_ = private_nh.advertise<geometry_msgs::PoseStamped>("current_goal", 0 );
00091
00092 ros::NodeHandle action_nh("move_base");
00093 action_goal_pub_ = action_nh.advertise<move_base_msgs::MoveBaseActionGoal>("goal", 1);
00094
00095
00096
00097
00098 ros::NodeHandle simple_nh("move_base_simple");
00099 goal_sub_ = simple_nh.subscribe<geometry_msgs::PoseStamped>("goal", 1, boost::bind(&MoveBase::goalCB, this, _1));
00100
00101
00102 private_nh.param("local_costmap/inscribed_radius", inscribed_radius_, 0.325);
00103 private_nh.param("local_costmap/circumscribed_radius", circumscribed_radius_, 0.46);
00104 private_nh.param("clearing_radius", clearing_radius_, circumscribed_radius_);
00105 private_nh.param("conservative_reset_dist", conservative_reset_dist_, 3.0);
00106
00107 private_nh.param("shutdown_costmaps", shutdown_costmaps_, false);
00108 private_nh.param("clearing_rotation_allowed", clearing_rotation_allowed_, true);
00109 private_nh.param("recovery_behavior_enabled", recovery_behavior_enabled_, true);
00110
00111
00112 planner_costmap_ros_ = new costmap_2d::Costmap2DROS("global_costmap", tf_);
00113 planner_costmap_ros_->pause();
00114
00115
00116 try {
00117 planner_ = bgp_loader_.createInstance(global_planner);
00118 planner_->initialize(bgp_loader_.getName(global_planner), planner_costmap_ros_);
00119 } catch (const pluginlib::PluginlibException& ex) {
00120 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());
00121 exit(1);
00122 }
00123
00124
00125 controller_costmap_ros_ = new costmap_2d::Costmap2DROS("local_costmap", tf_);
00126 controller_costmap_ros_->pause();
00127
00128
00129 try {
00130 tc_ = blp_loader_.createInstance(local_planner);
00131 ROS_INFO("Created local_planner %s", local_planner.c_str());
00132 tc_->initialize(blp_loader_.getName(local_planner), &tf_, controller_costmap_ros_);
00133 } catch (const pluginlib::PluginlibException& ex) {
00134 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());
00135 exit(1);
00136 }
00137
00138
00139 planner_costmap_ros_->start();
00140 controller_costmap_ros_->start();
00141
00142
00143 make_plan_srv_ = private_nh.advertiseService("make_plan", &MoveBase::planService, this);
00144
00145
00146 clear_costmaps_srv_ = private_nh.advertiseService("clear_costmaps", &MoveBase::clearCostmapsService, this);
00147
00148
00149 if(shutdown_costmaps_){
00150 ROS_DEBUG_NAMED("move_base","Stopping costmaps initially");
00151 planner_costmap_ros_->stop();
00152 controller_costmap_ros_->stop();
00153 }
00154
00155
00156 if(!loadRecoveryBehaviors(private_nh)){
00157 loadDefaultRecoveryBehaviors();
00158 }
00159
00160
00161 state_ = PLANNING;
00162
00163
00164 recovery_index_ = 0;
00165
00166
00167 as_->start();
00168
00169 dsrv_ = new dynamic_reconfigure::Server<move_base::MoveBaseConfig>(ros::NodeHandle("~"));
00170 dynamic_reconfigure::Server<move_base::MoveBaseConfig>::CallbackType cb = boost::bind(&MoveBase::reconfigureCB, this, _1, _2);
00171 dsrv_->setCallback(cb);
00172 }
00173
00174 void MoveBase::reconfigureCB(move_base::MoveBaseConfig &config, uint32_t level){
00175 boost::recursive_mutex::scoped_lock l(configuration_mutex_);
00176
00177
00178
00179 if(!setup_)
00180 {
00181 last_config_ = config;
00182 default_config_ = config;
00183 setup_ = true;
00184 return;
00185 }
00186
00187 if(config.restore_defaults) {
00188 config = default_config_;
00189
00190 config.restore_defaults = false;
00191 }
00192
00193 if(planner_frequency_ != config.planner_frequency)
00194 {
00195 planner_frequency_ = config.planner_frequency;
00196 p_freq_change_ = true;
00197 }
00198
00199 if(controller_frequency_ != config.controller_frequency)
00200 {
00201 controller_frequency_ = config.controller_frequency;
00202 c_freq_change_ = true;
00203 }
00204
00205 planner_patience_ = config.planner_patience;
00206 controller_patience_ = config.controller_patience;
00207 max_planning_retries_ = config.max_planning_retries;
00208 conservative_reset_dist_ = config.conservative_reset_dist;
00209
00210 recovery_behavior_enabled_ = config.recovery_behavior_enabled;
00211 clearing_rotation_allowed_ = config.clearing_rotation_allowed;
00212 shutdown_costmaps_ = config.shutdown_costmaps;
00213
00214 oscillation_timeout_ = config.oscillation_timeout;
00215 oscillation_distance_ = config.oscillation_distance;
00216 if(config.base_global_planner != last_config_.base_global_planner) {
00217 boost::shared_ptr<nav_core::BaseGlobalPlanner> old_planner = planner_;
00218
00219 ROS_INFO("Loading global planner %s", config.base_global_planner.c_str());
00220 try {
00221 planner_ = bgp_loader_.createInstance(config.base_global_planner);
00222
00223
00224 boost::unique_lock<boost::mutex> lock(planner_mutex_);
00225
00226
00227 planner_plan_->clear();
00228 latest_plan_->clear();
00229 controller_plan_->clear();
00230 resetState();
00231 planner_->initialize(bgp_loader_.getName(config.base_global_planner), planner_costmap_ros_);
00232
00233 lock.unlock();
00234 } catch (const pluginlib::PluginlibException& ex) {
00235 ROS_FATAL("Failed to create the %s planner, are you sure it is properly registered and that the \
00236 containing library is built? Exception: %s", config.base_global_planner.c_str(), ex.what());
00237 planner_ = old_planner;
00238 config.base_global_planner = last_config_.base_global_planner;
00239 }
00240 }
00241
00242 if(config.base_local_planner != last_config_.base_local_planner){
00243 boost::shared_ptr<nav_core::BaseLocalPlanner> old_planner = tc_;
00244
00245 try {
00246 tc_ = blp_loader_.createInstance(config.base_local_planner);
00247
00248 planner_plan_->clear();
00249 latest_plan_->clear();
00250 controller_plan_->clear();
00251 resetState();
00252 tc_->initialize(blp_loader_.getName(config.base_local_planner), &tf_, controller_costmap_ros_);
00253 } catch (const pluginlib::PluginlibException& ex) {
00254 ROS_FATAL("Failed to create the %s planner, are you sure it is properly registered and that the \
00255 containing library is built? Exception: %s", config.base_local_planner.c_str(), ex.what());
00256 tc_ = old_planner;
00257 config.base_local_planner = last_config_.base_local_planner;
00258 }
00259 }
00260
00261 last_config_ = config;
00262 }
00263
00264 void MoveBase::goalCB(const geometry_msgs::PoseStamped::ConstPtr& goal){
00265 ROS_DEBUG_NAMED("move_base","In ROS goal callback, wrapping the PoseStamped in the action message and re-sending to the server.");
00266 move_base_msgs::MoveBaseActionGoal action_goal;
00267 action_goal.header.stamp = ros::Time::now();
00268 action_goal.goal.target_pose = *goal;
00269
00270 action_goal_pub_.publish(action_goal);
00271 }
00272
00273 void MoveBase::clearCostmapWindows(double size_x, double size_y){
00274 tf::Stamped<tf::Pose> global_pose;
00275
00276
00277 planner_costmap_ros_->getRobotPose(global_pose);
00278
00279 std::vector<geometry_msgs::Point> clear_poly;
00280 double x = global_pose.getOrigin().x();
00281 double y = global_pose.getOrigin().y();
00282 geometry_msgs::Point pt;
00283
00284 pt.x = x - size_x / 2;
00285 pt.y = y - size_y / 2;
00286 clear_poly.push_back(pt);
00287
00288 pt.x = x + size_x / 2;
00289 pt.y = y - size_y / 2;
00290 clear_poly.push_back(pt);
00291
00292 pt.x = x + size_x / 2;
00293 pt.y = y + size_y / 2;
00294 clear_poly.push_back(pt);
00295
00296 pt.x = x - size_x / 2;
00297 pt.y = y + size_y / 2;
00298 clear_poly.push_back(pt);
00299
00300 planner_costmap_ros_->getCostmap()->setConvexPolygonCost(clear_poly, costmap_2d::FREE_SPACE);
00301
00302
00303 controller_costmap_ros_->getRobotPose(global_pose);
00304
00305 clear_poly.clear();
00306 x = global_pose.getOrigin().x();
00307 y = global_pose.getOrigin().y();
00308
00309 pt.x = x - size_x / 2;
00310 pt.y = y - size_y / 2;
00311 clear_poly.push_back(pt);
00312
00313 pt.x = x + size_x / 2;
00314 pt.y = y - size_y / 2;
00315 clear_poly.push_back(pt);
00316
00317 pt.x = x + size_x / 2;
00318 pt.y = y + size_y / 2;
00319 clear_poly.push_back(pt);
00320
00321 pt.x = x - size_x / 2;
00322 pt.y = y + size_y / 2;
00323 clear_poly.push_back(pt);
00324
00325 controller_costmap_ros_->getCostmap()->setConvexPolygonCost(clear_poly, costmap_2d::FREE_SPACE);
00326 }
00327
00328 bool MoveBase::clearCostmapsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp){
00329
00330 planner_costmap_ros_->resetLayers();
00331 controller_costmap_ros_->resetLayers();
00332 return true;
00333 }
00334
00335
00336 bool MoveBase::planService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp){
00337 if(as_->isActive()){
00338 ROS_ERROR("move_base must be in an inactive state to make a plan for an external user");
00339 return false;
00340 }
00341
00342 if(planner_costmap_ros_ == NULL){
00343 ROS_ERROR("move_base cannot make a plan for you because it doesn't have a costmap");
00344 return false;
00345 }
00346 tf::Stamped<tf::Pose> global_pose;
00347 if(!planner_costmap_ros_->getRobotPose(global_pose)){
00348 ROS_ERROR("move_base cannot make a plan for you because it could not get the start pose of the robot");
00349 return false;
00350 }
00351 geometry_msgs::PoseStamped start;
00352
00353 if(req.start.header.frame_id == "")
00354 tf::poseStampedTFToMsg(global_pose, start);
00355 else
00356 start = req.start;
00357
00358
00359 clearCostmapWindows(2 * clearing_radius_, 2 * clearing_radius_);
00360
00361
00362 std::vector<geometry_msgs::PoseStamped> global_plan;
00363 if(!planner_->makePlan(start, req.goal, global_plan) || global_plan.empty()){
00364 ROS_DEBUG_NAMED("move_base","Failed to find a plan to exact goal of (%.2f, %.2f), searching for a feasible goal within tolerance",
00365 req.goal.pose.position.x, req.goal.pose.position.y);
00366
00367
00368 geometry_msgs::PoseStamped p;
00369 p = req.goal;
00370 bool found_legal = false;
00371 float resolution = planner_costmap_ros_->getCostmap()->getResolution();
00372 float search_increment = resolution*3.0;
00373 if(req.tolerance > 0.0 && req.tolerance < search_increment) search_increment = req.tolerance;
00374 for(float max_offset = search_increment; max_offset <= req.tolerance && !found_legal; max_offset += search_increment) {
00375 for(float y_offset = 0; y_offset <= max_offset && !found_legal; y_offset += search_increment) {
00376 for(float x_offset = 0; x_offset <= max_offset && !found_legal; x_offset += search_increment) {
00377
00378
00379 if(x_offset < max_offset-1e-9 && y_offset < max_offset-1e-9) continue;
00380
00381
00382 for(float y_mult = -1.0; y_mult <= 1.0 + 1e-9 && !found_legal; y_mult += 2.0) {
00383
00384
00385 if(y_offset < 1e-9 && y_mult < -1.0 + 1e-9) continue;
00386
00387 for(float x_mult = -1.0; x_mult <= 1.0 + 1e-9 && !found_legal; x_mult += 2.0) {
00388 if(x_offset < 1e-9 && x_mult < -1.0 + 1e-9) continue;
00389
00390 p.pose.position.y = req.goal.pose.position.y + y_offset * y_mult;
00391 p.pose.position.x = req.goal.pose.position.x + x_offset * x_mult;
00392
00393 if(planner_->makePlan(start, p, global_plan)){
00394 if(!global_plan.empty()){
00395
00396
00397
00398 global_plan.push_back(req.goal);
00399
00400 found_legal = true;
00401 ROS_DEBUG_NAMED("move_base", "Found a plan to point (%.2f, %.2f)", p.pose.position.x, p.pose.position.y);
00402 break;
00403 }
00404 }
00405 else{
00406 ROS_DEBUG_NAMED("move_base","Failed to find a plan to point (%.2f, %.2f)", p.pose.position.x, p.pose.position.y);
00407 }
00408 }
00409 }
00410 }
00411 }
00412 }
00413 }
00414
00415
00416 resp.plan.poses.resize(global_plan.size());
00417 for(unsigned int i = 0; i < global_plan.size(); ++i){
00418 resp.plan.poses[i] = global_plan[i];
00419 }
00420
00421 return true;
00422 }
00423
00424 MoveBase::~MoveBase(){
00425 recovery_behaviors_.clear();
00426
00427 delete dsrv_;
00428
00429 if(as_ != NULL)
00430 delete as_;
00431
00432 if(planner_costmap_ros_ != NULL)
00433 delete planner_costmap_ros_;
00434
00435 if(controller_costmap_ros_ != NULL)
00436 delete controller_costmap_ros_;
00437
00438 planner_thread_->interrupt();
00439 planner_thread_->join();
00440
00441 delete planner_thread_;
00442
00443 delete planner_plan_;
00444 delete latest_plan_;
00445 delete controller_plan_;
00446
00447 planner_.reset();
00448 tc_.reset();
00449 }
00450
00451 bool MoveBase::makePlan(const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan){
00452 boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(planner_costmap_ros_->getCostmap()->getMutex()));
00453
00454
00455 plan.clear();
00456
00457
00458 if(planner_costmap_ros_ == NULL) {
00459 ROS_ERROR("Planner costmap ROS is NULL, unable to create global plan");
00460 return false;
00461 }
00462
00463
00464 tf::Stamped<tf::Pose> global_pose;
00465 if(!planner_costmap_ros_->getRobotPose(global_pose)) {
00466 ROS_WARN("Unable to get starting pose of robot, unable to create global plan");
00467 return false;
00468 }
00469
00470 geometry_msgs::PoseStamped start;
00471 tf::poseStampedTFToMsg(global_pose, start);
00472
00473
00474 if(!planner_->makePlan(start, goal, plan) || plan.empty()){
00475 ROS_DEBUG_NAMED("move_base","Failed to find a plan to point (%.2f, %.2f)", goal.pose.position.x, goal.pose.position.y);
00476 publishZeroVelocity();
00477 return false;
00478 }
00479
00480 return true;
00481 }
00482
00483 void MoveBase::publishZeroVelocity(){
00484 geometry_msgs::Twist cmd_vel;
00485 cmd_vel.linear.x = 0.0;
00486 cmd_vel.linear.y = 0.0;
00487 cmd_vel.angular.z = 0.0;
00488 vel_pub_.publish(cmd_vel);
00489 }
00490
00491 bool MoveBase::isQuaternionValid(const geometry_msgs::Quaternion& q){
00492
00493 if(!std::isfinite(q.x) || !std::isfinite(q.y) || !std::isfinite(q.z) || !std::isfinite(q.w)){
00494 ROS_ERROR("Quaternion has nans or infs... discarding as a navigation goal");
00495 return false;
00496 }
00497
00498 tf::Quaternion tf_q(q.x, q.y, q.z, q.w);
00499
00500
00501 if(tf_q.length2() < 1e-6){
00502 ROS_ERROR("Quaternion has length close to zero... discarding as navigation goal");
00503 return false;
00504 }
00505
00506
00507 tf_q.normalize();
00508
00509 tf::Vector3 up(0, 0, 1);
00510
00511 double dot = up.dot(up.rotate(tf_q.getAxis(), tf_q.getAngle()));
00512
00513 if(fabs(dot - 1) > 1e-3){
00514 ROS_ERROR("Quaternion is invalid... for navigation the z-axis of the quaternion must be close to vertical.");
00515 return false;
00516 }
00517
00518 return true;
00519 }
00520
00521 geometry_msgs::PoseStamped MoveBase::goalToGlobalFrame(const geometry_msgs::PoseStamped& goal_pose_msg){
00522 std::string global_frame = planner_costmap_ros_->getGlobalFrameID();
00523 tf::Stamped<tf::Pose> goal_pose, global_pose;
00524 poseStampedMsgToTF(goal_pose_msg, goal_pose);
00525
00526
00527
00528 goal_pose.stamp_ = ros::Time();
00529
00530 try{
00531 tf_.transformPose(global_frame, goal_pose, global_pose);
00532 }
00533 catch(tf::TransformException& ex){
00534 ROS_WARN("Failed to transform the goal pose from %s into the %s frame: %s",
00535 goal_pose.frame_id_.c_str(), global_frame.c_str(), ex.what());
00536 return goal_pose_msg;
00537 }
00538
00539 geometry_msgs::PoseStamped global_pose_msg;
00540 tf::poseStampedTFToMsg(global_pose, global_pose_msg);
00541 return global_pose_msg;
00542 }
00543
00544 void MoveBase::wakePlanner(const ros::TimerEvent& event)
00545 {
00546
00547 planner_cond_.notify_one();
00548 }
00549
00550 void MoveBase::planThread(){
00551 ROS_DEBUG_NAMED("move_base_plan_thread","Starting planner thread...");
00552 ros::NodeHandle n;
00553 ros::Timer timer;
00554 bool wait_for_wake = false;
00555 boost::unique_lock<boost::mutex> lock(planner_mutex_);
00556 while(n.ok()){
00557
00558 while(wait_for_wake || !runPlanner_){
00559
00560 ROS_DEBUG_NAMED("move_base_plan_thread","Planner thread is suspending");
00561 planner_cond_.wait(lock);
00562 wait_for_wake = false;
00563 }
00564 ros::Time start_time = ros::Time::now();
00565
00566
00567 geometry_msgs::PoseStamped temp_goal = planner_goal_;
00568 lock.unlock();
00569 ROS_DEBUG_NAMED("move_base_plan_thread","Planning...");
00570
00571
00572 planner_plan_->clear();
00573 bool gotPlan = n.ok() && makePlan(temp_goal, *planner_plan_);
00574
00575 if(gotPlan){
00576 ROS_DEBUG_NAMED("move_base_plan_thread","Got Plan with %zu points!", planner_plan_->size());
00577
00578 std::vector<geometry_msgs::PoseStamped>* temp_plan = planner_plan_;
00579
00580 lock.lock();
00581 planner_plan_ = latest_plan_;
00582 latest_plan_ = temp_plan;
00583 last_valid_plan_ = ros::Time::now();
00584 planning_retries_ = 0;
00585 new_global_plan_ = true;
00586
00587 ROS_DEBUG_NAMED("move_base_plan_thread","Generated a plan from the base_global_planner");
00588
00589
00590 if(runPlanner_)
00591 state_ = CONTROLLING;
00592 if(planner_frequency_ <= 0)
00593 runPlanner_ = false;
00594 lock.unlock();
00595 }
00596
00597 else if(state_==PLANNING){
00598 ROS_DEBUG_NAMED("move_base_plan_thread","No Plan...");
00599 ros::Time attempt_end = last_valid_plan_ + ros::Duration(planner_patience_);
00600
00601
00602
00603
00604 lock.lock();
00605 if(runPlanner_ &&
00606 (ros::Time::now() > attempt_end || ++planning_retries_ > uint32_t(max_planning_retries_))){
00607
00608 state_ = CLEARING;
00609 publishZeroVelocity();
00610 recovery_trigger_ = PLANNING_R;
00611 }
00612 lock.unlock();
00613 }
00614
00615
00616 lock.lock();
00617
00618
00619 if(planner_frequency_ > 0){
00620 ros::Duration sleep_time = (start_time + ros::Duration(1.0/planner_frequency_)) - ros::Time::now();
00621 if (sleep_time > ros::Duration(0.0)){
00622 wait_for_wake = true;
00623 timer = n.createTimer(sleep_time, &MoveBase::wakePlanner, this);
00624 }
00625 }
00626 }
00627 }
00628
00629 void MoveBase::executeCb(const move_base_msgs::MoveBaseGoalConstPtr& move_base_goal)
00630 {
00631 if(!isQuaternionValid(move_base_goal->target_pose.pose.orientation)){
00632 as_->setAborted(move_base_msgs::MoveBaseResult(), "Aborting on goal because it was sent with an invalid quaternion");
00633 return;
00634 }
00635
00636 geometry_msgs::PoseStamped goal = goalToGlobalFrame(move_base_goal->target_pose);
00637
00638
00639 boost::unique_lock<boost::mutex> lock(planner_mutex_);
00640 planner_goal_ = goal;
00641 runPlanner_ = true;
00642 planner_cond_.notify_one();
00643 lock.unlock();
00644
00645 current_goal_pub_.publish(goal);
00646 std::vector<geometry_msgs::PoseStamped> global_plan;
00647
00648 ros::Rate r(controller_frequency_);
00649 if(shutdown_costmaps_){
00650 ROS_DEBUG_NAMED("move_base","Starting up costmaps that were shut down previously");
00651 planner_costmap_ros_->start();
00652 controller_costmap_ros_->start();
00653 }
00654
00655
00656 last_valid_control_ = ros::Time::now();
00657 last_valid_plan_ = ros::Time::now();
00658 last_oscillation_reset_ = ros::Time::now();
00659 planning_retries_ = 0;
00660
00661 ros::NodeHandle n;
00662 while(n.ok())
00663 {
00664 if(c_freq_change_)
00665 {
00666 ROS_INFO("Setting controller frequency to %.2f", controller_frequency_);
00667 r = ros::Rate(controller_frequency_);
00668 c_freq_change_ = false;
00669 }
00670
00671 if(as_->isPreemptRequested()){
00672 if(as_->isNewGoalAvailable()){
00673
00674 move_base_msgs::MoveBaseGoal new_goal = *as_->acceptNewGoal();
00675
00676 if(!isQuaternionValid(new_goal.target_pose.pose.orientation)){
00677 as_->setAborted(move_base_msgs::MoveBaseResult(), "Aborting on goal because it was sent with an invalid quaternion");
00678 return;
00679 }
00680
00681 goal = goalToGlobalFrame(new_goal.target_pose);
00682
00683
00684 recovery_index_ = 0;
00685 state_ = PLANNING;
00686
00687
00688 lock.lock();
00689 planner_goal_ = goal;
00690 runPlanner_ = true;
00691 planner_cond_.notify_one();
00692 lock.unlock();
00693
00694
00695 ROS_DEBUG_NAMED("move_base","move_base has received a goal of x: %.2f, y: %.2f", goal.pose.position.x, goal.pose.position.y);
00696 current_goal_pub_.publish(goal);
00697
00698
00699 last_valid_control_ = ros::Time::now();
00700 last_valid_plan_ = ros::Time::now();
00701 last_oscillation_reset_ = ros::Time::now();
00702 planning_retries_ = 0;
00703 }
00704 else {
00705
00706 resetState();
00707
00708
00709 ROS_DEBUG_NAMED("move_base","Move base preempting the current goal");
00710 as_->setPreempted();
00711
00712
00713 return;
00714 }
00715 }
00716
00717
00718 if(goal.header.frame_id != planner_costmap_ros_->getGlobalFrameID()){
00719 goal = goalToGlobalFrame(goal);
00720
00721
00722 recovery_index_ = 0;
00723 state_ = PLANNING;
00724
00725
00726 lock.lock();
00727 planner_goal_ = goal;
00728 runPlanner_ = true;
00729 planner_cond_.notify_one();
00730 lock.unlock();
00731
00732
00733 ROS_DEBUG_NAMED("move_base","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);
00734 current_goal_pub_.publish(goal);
00735
00736
00737 last_valid_control_ = ros::Time::now();
00738 last_valid_plan_ = ros::Time::now();
00739 last_oscillation_reset_ = ros::Time::now();
00740 planning_retries_ = 0;
00741 }
00742
00743
00744 ros::WallTime start = ros::WallTime::now();
00745
00746
00747 bool done = executeCycle(goal, global_plan);
00748
00749
00750 if(done)
00751 return;
00752
00753
00754
00755 ros::WallDuration t_diff = ros::WallTime::now() - start;
00756 ROS_DEBUG_NAMED("move_base","Full control cycle time: %.9f\n", t_diff.toSec());
00757
00758 r.sleep();
00759
00760 if(r.cycleTime() > ros::Duration(1 / controller_frequency_) && state_ == CONTROLLING)
00761 ROS_WARN("Control loop missed its desired rate of %.4fHz... the loop actually took %.4f seconds", controller_frequency_, r.cycleTime().toSec());
00762 }
00763
00764
00765 lock.lock();
00766 runPlanner_ = true;
00767 planner_cond_.notify_one();
00768 lock.unlock();
00769
00770
00771 as_->setAborted(move_base_msgs::MoveBaseResult(), "Aborting on the goal because the node has been killed");
00772 return;
00773 }
00774
00775 double MoveBase::distance(const geometry_msgs::PoseStamped& p1, const geometry_msgs::PoseStamped& p2)
00776 {
00777 return hypot(p1.pose.position.x - p2.pose.position.x, p1.pose.position.y - p2.pose.position.y);
00778 }
00779
00780 bool MoveBase::executeCycle(geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& global_plan){
00781 boost::recursive_mutex::scoped_lock ecl(configuration_mutex_);
00782
00783 geometry_msgs::Twist cmd_vel;
00784
00785
00786 tf::Stamped<tf::Pose> global_pose;
00787 planner_costmap_ros_->getRobotPose(global_pose);
00788 geometry_msgs::PoseStamped current_position;
00789 tf::poseStampedTFToMsg(global_pose, current_position);
00790
00791
00792 move_base_msgs::MoveBaseFeedback feedback;
00793 feedback.base_position = current_position;
00794 as_->publishFeedback(feedback);
00795
00796
00797 if(distance(current_position, oscillation_pose_) >= oscillation_distance_)
00798 {
00799 last_oscillation_reset_ = ros::Time::now();
00800 oscillation_pose_ = current_position;
00801
00802
00803 if(recovery_trigger_ == OSCILLATION_R)
00804 recovery_index_ = 0;
00805 }
00806
00807
00808 if(!controller_costmap_ros_->isCurrent()){
00809 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());
00810 publishZeroVelocity();
00811 return false;
00812 }
00813
00814
00815 if(new_global_plan_){
00816
00817 new_global_plan_ = false;
00818
00819 ROS_DEBUG_NAMED("move_base","Got a new plan...swap pointers");
00820
00821
00822 std::vector<geometry_msgs::PoseStamped>* temp_plan = controller_plan_;
00823
00824 boost::unique_lock<boost::mutex> lock(planner_mutex_);
00825 controller_plan_ = latest_plan_;
00826 latest_plan_ = temp_plan;
00827 lock.unlock();
00828 ROS_DEBUG_NAMED("move_base","pointers swapped!");
00829
00830 if(!tc_->setPlan(*controller_plan_)){
00831
00832 ROS_ERROR("Failed to pass global plan to the controller, aborting.");
00833 resetState();
00834
00835
00836 lock.lock();
00837 runPlanner_ = false;
00838 lock.unlock();
00839
00840 as_->setAborted(move_base_msgs::MoveBaseResult(), "Failed to pass global plan to the controller.");
00841 return true;
00842 }
00843
00844
00845 if(recovery_trigger_ == PLANNING_R)
00846 recovery_index_ = 0;
00847 }
00848
00849
00850 switch(state_){
00851
00852 case PLANNING:
00853 {
00854 boost::mutex::scoped_lock lock(planner_mutex_);
00855 runPlanner_ = true;
00856 planner_cond_.notify_one();
00857 }
00858 ROS_DEBUG_NAMED("move_base","Waiting for plan, in the planning state.");
00859 break;
00860
00861
00862 case CONTROLLING:
00863 ROS_DEBUG_NAMED("move_base","In controlling state.");
00864
00865
00866 if(tc_->isGoalReached()){
00867 ROS_DEBUG_NAMED("move_base","Goal reached!");
00868 resetState();
00869
00870
00871 boost::unique_lock<boost::mutex> lock(planner_mutex_);
00872 runPlanner_ = false;
00873 lock.unlock();
00874
00875 as_->setSucceeded(move_base_msgs::MoveBaseResult(), "Goal reached.");
00876 return true;
00877 }
00878
00879
00880 if(oscillation_timeout_ > 0.0 &&
00881 last_oscillation_reset_ + ros::Duration(oscillation_timeout_) < ros::Time::now())
00882 {
00883 publishZeroVelocity();
00884 state_ = CLEARING;
00885 recovery_trigger_ = OSCILLATION_R;
00886 }
00887
00888 {
00889 boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(controller_costmap_ros_->getCostmap()->getMutex()));
00890
00891 if(tc_->computeVelocityCommands(cmd_vel)){
00892 ROS_DEBUG_NAMED( "move_base", "Got a valid command from the local planner: %.3lf, %.3lf, %.3lf",
00893 cmd_vel.linear.x, cmd_vel.linear.y, cmd_vel.angular.z );
00894 last_valid_control_ = ros::Time::now();
00895
00896 vel_pub_.publish(cmd_vel);
00897 if(recovery_trigger_ == CONTROLLING_R)
00898 recovery_index_ = 0;
00899 }
00900 else {
00901 ROS_DEBUG_NAMED("move_base", "The local planner could not find a valid plan.");
00902 ros::Time attempt_end = last_valid_control_ + ros::Duration(controller_patience_);
00903
00904
00905 if(ros::Time::now() > attempt_end){
00906
00907 publishZeroVelocity();
00908 state_ = CLEARING;
00909 recovery_trigger_ = CONTROLLING_R;
00910 }
00911 else{
00912
00913 last_valid_plan_ = ros::Time::now();
00914 planning_retries_ = 0;
00915 state_ = PLANNING;
00916 publishZeroVelocity();
00917
00918
00919 boost::unique_lock<boost::mutex> lock(planner_mutex_);
00920 runPlanner_ = true;
00921 planner_cond_.notify_one();
00922 lock.unlock();
00923 }
00924 }
00925 }
00926
00927 break;
00928
00929
00930 case CLEARING:
00931 ROS_DEBUG_NAMED("move_base","In clearing/recovery state");
00932
00933 if(recovery_behavior_enabled_ && recovery_index_ < recovery_behaviors_.size()){
00934 ROS_DEBUG_NAMED("move_base_recovery","Executing behavior %u of %zu", recovery_index_, recovery_behaviors_.size());
00935 recovery_behaviors_[recovery_index_]->runBehavior();
00936
00937
00938 last_oscillation_reset_ = ros::Time::now();
00939
00940
00941 ROS_DEBUG_NAMED("move_base_recovery","Going back to planning state");
00942 state_ = PLANNING;
00943
00944
00945 recovery_index_++;
00946 }
00947 else{
00948 ROS_DEBUG_NAMED("move_base_recovery","All recovery behaviors have failed, locking the planner and disabling it.");
00949
00950 boost::unique_lock<boost::mutex> lock(planner_mutex_);
00951 runPlanner_ = false;
00952 lock.unlock();
00953
00954 ROS_DEBUG_NAMED("move_base_recovery","Something should abort after this.");
00955
00956 if(recovery_trigger_ == CONTROLLING_R){
00957 ROS_ERROR("Aborting because a valid control could not be found. Even after executing all recovery behaviors");
00958 as_->setAborted(move_base_msgs::MoveBaseResult(), "Failed to find a valid control. Even after executing recovery behaviors.");
00959 }
00960 else if(recovery_trigger_ == PLANNING_R){
00961 ROS_ERROR("Aborting because a valid plan could not be found. Even after executing all recovery behaviors");
00962 as_->setAborted(move_base_msgs::MoveBaseResult(), "Failed to find a valid plan. Even after executing recovery behaviors.");
00963 }
00964 else if(recovery_trigger_ == OSCILLATION_R){
00965 ROS_ERROR("Aborting because the robot appears to be oscillating over and over. Even after executing all recovery behaviors");
00966 as_->setAborted(move_base_msgs::MoveBaseResult(), "Robot is oscillating. Even after executing recovery behaviors.");
00967 }
00968 resetState();
00969 return true;
00970 }
00971 break;
00972 default:
00973 ROS_ERROR("This case should never be reached, something is wrong, aborting");
00974 resetState();
00975
00976 boost::unique_lock<boost::mutex> lock(planner_mutex_);
00977 runPlanner_ = false;
00978 lock.unlock();
00979 as_->setAborted(move_base_msgs::MoveBaseResult(), "Reached a case that should not be hit in move_base. This is a bug, please report it.");
00980 return true;
00981 }
00982
00983
00984 return false;
00985 }
00986
00987 bool MoveBase::loadRecoveryBehaviors(ros::NodeHandle node){
00988 XmlRpc::XmlRpcValue behavior_list;
00989 if(node.getParam("recovery_behaviors", behavior_list)){
00990 if(behavior_list.getType() == XmlRpc::XmlRpcValue::TypeArray){
00991 for(int i = 0; i < behavior_list.size(); ++i){
00992 if(behavior_list[i].getType() == XmlRpc::XmlRpcValue::TypeStruct){
00993 if(behavior_list[i].hasMember("name") && behavior_list[i].hasMember("type")){
00994
00995 for(int j = i + 1; j < behavior_list.size(); j++){
00996 if(behavior_list[j].getType() == XmlRpc::XmlRpcValue::TypeStruct){
00997 if(behavior_list[j].hasMember("name") && behavior_list[j].hasMember("type")){
00998 std::string name_i = behavior_list[i]["name"];
00999 std::string name_j = behavior_list[j]["name"];
01000 if(name_i == name_j){
01001 ROS_ERROR("A recovery behavior with the name %s already exists, this is not allowed. Using the default recovery behaviors instead.",
01002 name_i.c_str());
01003 return false;
01004 }
01005 }
01006 }
01007 }
01008 }
01009 else{
01010 ROS_ERROR("Recovery behaviors must have a name and a type and this does not. Using the default recovery behaviors instead.");
01011 return false;
01012 }
01013 }
01014 else{
01015 ROS_ERROR("Recovery behaviors must be specified as maps, but they are XmlRpcType %d. We'll use the default recovery behaviors instead.",
01016 behavior_list[i].getType());
01017 return false;
01018 }
01019 }
01020
01021
01022 for(int i = 0; i < behavior_list.size(); ++i){
01023 try{
01024
01025 if(!recovery_loader_.isClassAvailable(behavior_list[i]["type"])){
01026 std::vector<std::string> classes = recovery_loader_.getDeclaredClasses();
01027 for(unsigned int i = 0; i < classes.size(); ++i){
01028 if(behavior_list[i]["type"] == recovery_loader_.getName(classes[i])){
01029
01030 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.",
01031 std::string(behavior_list[i]["type"]).c_str(), classes[i].c_str());
01032 behavior_list[i]["type"] = classes[i];
01033 break;
01034 }
01035 }
01036 }
01037
01038 boost::shared_ptr<nav_core::RecoveryBehavior> behavior(recovery_loader_.createInstance(behavior_list[i]["type"]));
01039
01040
01041 if(behavior.get() == NULL){
01042 ROS_ERROR("The ClassLoader returned a null pointer without throwing an exception. This should not happen");
01043 return false;
01044 }
01045
01046
01047 behavior->initialize(behavior_list[i]["name"], &tf_, planner_costmap_ros_, controller_costmap_ros_);
01048 recovery_behaviors_.push_back(behavior);
01049 }
01050 catch(pluginlib::PluginlibException& ex){
01051 ROS_ERROR("Failed to load a plugin. Using default recovery behaviors. Error: %s", ex.what());
01052 return false;
01053 }
01054 }
01055 }
01056 else{
01057 ROS_ERROR("The recovery behavior specification must be a list, but is of XmlRpcType %d. We'll use the default recovery behaviors instead.",
01058 behavior_list.getType());
01059 return false;
01060 }
01061 }
01062 else{
01063
01064 return false;
01065 }
01066
01067
01068 return true;
01069 }
01070
01071
01072 void MoveBase::loadDefaultRecoveryBehaviors(){
01073 recovery_behaviors_.clear();
01074 try{
01075
01076 ros::NodeHandle n("~");
01077 n.setParam("conservative_reset/reset_distance", conservative_reset_dist_);
01078 n.setParam("aggressive_reset/reset_distance", circumscribed_radius_ * 4);
01079
01080
01081 boost::shared_ptr<nav_core::RecoveryBehavior> cons_clear(recovery_loader_.createInstance("clear_costmap_recovery/ClearCostmapRecovery"));
01082 cons_clear->initialize("conservative_reset", &tf_, planner_costmap_ros_, controller_costmap_ros_);
01083 recovery_behaviors_.push_back(cons_clear);
01084
01085
01086 boost::shared_ptr<nav_core::RecoveryBehavior> rotate(recovery_loader_.createInstance("rotate_recovery/RotateRecovery"));
01087 if(clearing_rotation_allowed_){
01088 rotate->initialize("rotate_recovery", &tf_, planner_costmap_ros_, controller_costmap_ros_);
01089 recovery_behaviors_.push_back(rotate);
01090 }
01091
01092
01093 boost::shared_ptr<nav_core::RecoveryBehavior> ags_clear(recovery_loader_.createInstance("clear_costmap_recovery/ClearCostmapRecovery"));
01094 ags_clear->initialize("aggressive_reset", &tf_, planner_costmap_ros_, controller_costmap_ros_);
01095 recovery_behaviors_.push_back(ags_clear);
01096
01097
01098 if(clearing_rotation_allowed_)
01099 recovery_behaviors_.push_back(rotate);
01100 }
01101 catch(pluginlib::PluginlibException& ex){
01102 ROS_FATAL("Failed to load a plugin. This should not happen on default recovery behaviors. Error: %s", ex.what());
01103 }
01104
01105 return;
01106 }
01107
01108 void MoveBase::resetState(){
01109
01110 boost::unique_lock<boost::mutex> lock(planner_mutex_);
01111 runPlanner_ = false;
01112 lock.unlock();
01113
01114
01115 state_ = PLANNING;
01116 recovery_index_ = 0;
01117 recovery_trigger_ = PLANNING_R;
01118 publishZeroVelocity();
01119
01120
01121 if(shutdown_costmaps_){
01122 ROS_DEBUG_NAMED("move_base","Stopping costmaps");
01123 planner_costmap_ros_->stop();
01124 controller_costmap_ros_->stop();
01125 }
01126 }
01127 };