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