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