39 #include <move_base_msgs/RecoveryStatus.h>
42 #include <boost/algorithm/string.hpp>
43 #include <boost/thread.hpp>
45 #include <geometry_msgs/Twist.h>
54 planner_costmap_ros_(NULL), controller_costmap_ros_(NULL),
55 bgp_loader_(
"nav_core",
"nav_core::BaseGlobalPlanner"),
56 blp_loader_(
"nav_core",
"nav_core::BaseLocalPlanner"),
57 recovery_loader_(
"nav_core",
"nav_core::RecoveryBehavior"),
58 planner_plan_(NULL), latest_plan_(NULL), controller_plan_(NULL),
59 runPlanner_(false), setup_(false), p_freq_change_(false), c_freq_change_(false), new_global_plan_(false) {
69 std::string global_planner, local_planner;
70 private_nh.param(
"base_global_planner", global_planner, std::string(
"navfn/NavfnROS"));
71 private_nh.param(
"base_local_planner", local_planner, std::string(
"base_local_planner/TrajectoryPlannerROS"));
72 private_nh.param(
"global_costmap/robot_base_frame", robot_base_frame_, std::string(
"base_link"));
73 private_nh.param(
"global_costmap/global_frame", global_frame_, std::string(
"map"));
74 private_nh.param(
"planner_frequency", planner_frequency_, 0.0);
75 private_nh.param(
"controller_frequency", controller_frequency_, 20.0);
76 private_nh.param(
"planner_patience", planner_patience_, 5.0);
77 private_nh.param(
"controller_patience", controller_patience_, 15.0);
78 private_nh.param(
"max_planning_retries", max_planning_retries_, -1);
80 private_nh.param(
"oscillation_timeout", oscillation_timeout_, 0.0);
81 private_nh.param(
"oscillation_distance", oscillation_distance_, 0.5);
84 private_nh.param(
"make_plan_clear_costmap", make_plan_clear_costmap_,
true);
85 private_nh.param(
"make_plan_add_unreachable_goal", make_plan_add_unreachable_goal_,
true);
88 planner_plan_ =
new std::vector<geometry_msgs::PoseStamped>();
89 latest_plan_ =
new std::vector<geometry_msgs::PoseStamped>();
90 controller_plan_ =
new std::vector<geometry_msgs::PoseStamped>();
93 planner_thread_ =
new boost::thread(boost::bind(&MoveBase::planThread,
this));
96 vel_pub_ = nh.
advertise<geometry_msgs::Twist>(
"cmd_vel", 1);
97 current_goal_pub_ = private_nh.advertise<geometry_msgs::PoseStamped>(
"current_goal", 0 );
100 action_goal_pub_ = action_nh.advertise<move_base_msgs::MoveBaseActionGoal>(
"goal", 1);
101 recovery_status_pub_= action_nh.advertise<move_base_msgs::RecoveryStatus>(
"recovery_status", 1);
107 goal_sub_ = simple_nh.subscribe<geometry_msgs::PoseStamped>(
"goal", 1, [
this](
auto&
goal){ goalCB(goal); });
110 private_nh.param(
"local_costmap/inscribed_radius", inscribed_radius_, 0.325);
111 private_nh.param(
"local_costmap/circumscribed_radius", circumscribed_radius_, 0.46);
112 private_nh.param(
"clearing_radius", clearing_radius_, circumscribed_radius_);
113 private_nh.param(
"conservative_reset_dist", conservative_reset_dist_, 3.0);
115 private_nh.param(
"shutdown_costmaps", shutdown_costmaps_,
false);
116 private_nh.param(
"clearing_rotation_allowed", clearing_rotation_allowed_,
true);
117 private_nh.param(
"recovery_behavior_enabled", recovery_behavior_enabled_,
true);
121 planner_costmap_ros_->pause();
125 planner_ = bgp_loader_.createInstance(global_planner);
126 planner_->initialize(bgp_loader_.getName(global_planner), planner_costmap_ros_);
128 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());
134 controller_costmap_ros_->pause();
138 tc_ = blp_loader_.createInstance(local_planner);
139 ROS_INFO(
"Created local_planner %s", local_planner.c_str());
140 tc_->initialize(blp_loader_.getName(local_planner), &tf_, controller_costmap_ros_);
142 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());
147 planner_costmap_ros_->start();
148 controller_costmap_ros_->start();
151 make_plan_srv_ = private_nh.advertiseService(
"make_plan", &MoveBase::planService,
this);
154 clear_costmaps_srv_ = private_nh.advertiseService(
"clear_costmaps", &MoveBase::clearCostmapsService,
this);
157 if(shutdown_costmaps_){
159 planner_costmap_ros_->stop();
160 controller_costmap_ros_->stop();
164 if(!loadRecoveryBehaviors(private_nh)){
165 loadDefaultRecoveryBehaviors();
177 dsrv_ =
new dynamic_reconfigure::Server<move_base::MoveBaseConfig>(
ros::NodeHandle(
"~"));
178 dynamic_reconfigure::Server<move_base::MoveBaseConfig>::CallbackType cb = [
this](
auto& config,
auto level){ reconfigureCB(config, level); };
179 dsrv_->setCallback(cb);
182 void MoveBase::reconfigureCB(move_base::MoveBaseConfig &config, uint32_t level){
183 boost::recursive_mutex::scoped_lock l(configuration_mutex_);
189 last_config_ = config;
190 default_config_ = config;
195 if(config.restore_defaults) {
196 config = default_config_;
198 config.restore_defaults =
false;
201 if(planner_frequency_ != config.planner_frequency)
203 planner_frequency_ = config.planner_frequency;
204 p_freq_change_ =
true;
207 if(controller_frequency_ != config.controller_frequency)
209 controller_frequency_ = config.controller_frequency;
210 c_freq_change_ =
true;
213 planner_patience_ = config.planner_patience;
214 controller_patience_ = config.controller_patience;
215 max_planning_retries_ = config.max_planning_retries;
216 conservative_reset_dist_ = config.conservative_reset_dist;
218 recovery_behavior_enabled_ = config.recovery_behavior_enabled;
219 clearing_rotation_allowed_ = config.clearing_rotation_allowed;
220 shutdown_costmaps_ = config.shutdown_costmaps;
222 oscillation_timeout_ = config.oscillation_timeout;
223 oscillation_distance_ = config.oscillation_distance;
224 if(config.base_global_planner != last_config_.base_global_planner) {
227 ROS_INFO(
"Loading global planner %s", config.base_global_planner.c_str());
229 planner_ = bgp_loader_.createInstance(config.base_global_planner);
232 boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
235 planner_plan_->clear();
236 latest_plan_->clear();
237 controller_plan_->clear();
239 planner_->initialize(bgp_loader_.getName(config.base_global_planner), planner_costmap_ros_);
243 ROS_FATAL(
"Failed to create the %s planner, are you sure it is properly registered and that the \
244 containing library is built? Exception: %s", config.base_global_planner.c_str(), ex.what());
245 planner_ = old_planner;
246 config.base_global_planner = last_config_.base_global_planner;
250 if(config.base_local_planner != last_config_.base_local_planner){
254 tc_ = blp_loader_.createInstance(config.base_local_planner);
256 planner_plan_->clear();
257 latest_plan_->clear();
258 controller_plan_->clear();
260 tc_->initialize(blp_loader_.getName(config.base_local_planner), &tf_, controller_costmap_ros_);
262 ROS_FATAL(
"Failed to create the %s planner, are you sure it is properly registered and that the \
263 containing library is built? Exception: %s", config.base_local_planner.c_str(), ex.what());
265 config.base_local_planner = last_config_.base_local_planner;
269 make_plan_clear_costmap_ = config.make_plan_clear_costmap;
270 make_plan_add_unreachable_goal_ = config.make_plan_add_unreachable_goal;
272 last_config_ = config;
275 void MoveBase::goalCB(
const geometry_msgs::PoseStamped::ConstPtr& goal){
276 ROS_DEBUG_NAMED(
"move_base",
"In ROS goal callback, wrapping the PoseStamped in the action message and re-sending to the server.");
277 move_base_msgs::MoveBaseActionGoal action_goal;
279 action_goal.goal.target_pose = *
goal;
281 action_goal_pub_.publish(action_goal);
284 void MoveBase::clearCostmapWindows(
double size_x,
double size_y){
285 geometry_msgs::PoseStamped global_pose;
288 getRobotPose(global_pose, planner_costmap_ros_);
290 std::vector<geometry_msgs::Point> clear_poly;
291 double x = global_pose.pose.position.x;
292 double y = global_pose.pose.position.y;
293 geometry_msgs::Point pt;
295 pt.x = x - size_x / 2;
296 pt.y = y - size_y / 2;
297 clear_poly.push_back(pt);
299 pt.x = x + size_x / 2;
300 pt.y = y - size_y / 2;
301 clear_poly.push_back(pt);
303 pt.x = x + size_x / 2;
304 pt.y = y + size_y / 2;
305 clear_poly.push_back(pt);
307 pt.x = x - size_x / 2;
308 pt.y = y + size_y / 2;
309 clear_poly.push_back(pt);
314 getRobotPose(global_pose, controller_costmap_ros_);
317 x = global_pose.pose.position.x;
318 y = global_pose.pose.position.y;
320 pt.x = x - size_x / 2;
321 pt.y = y - size_y / 2;
322 clear_poly.push_back(pt);
324 pt.x = x + size_x / 2;
325 pt.y = y - size_y / 2;
326 clear_poly.push_back(pt);
328 pt.x = x + size_x / 2;
329 pt.y = y + size_y / 2;
330 clear_poly.push_back(pt);
332 pt.x = x - size_x / 2;
333 pt.y = y + size_y / 2;
334 clear_poly.push_back(pt);
339 bool MoveBase::clearCostmapsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp){
341 boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock_controller(*(controller_costmap_ros_->getCostmap()->getMutex()));
342 controller_costmap_ros_->resetLayers();
344 boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock_planner(*(planner_costmap_ros_->getCostmap()->getMutex()));
345 planner_costmap_ros_->resetLayers();
350 bool MoveBase::planService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp){
352 ROS_ERROR(
"move_base must be in an inactive state to make a plan for an external user");
356 if(planner_costmap_ros_ == NULL){
357 ROS_ERROR(
"move_base cannot make a plan for you because it doesn't have a costmap");
361 geometry_msgs::PoseStamped
start;
363 if(req.start.header.frame_id.empty())
365 geometry_msgs::PoseStamped global_pose;
366 if(!getRobotPose(global_pose, planner_costmap_ros_)){
367 ROS_ERROR(
"move_base cannot make a plan for you because it could not get the start pose of the robot");
377 if (make_plan_clear_costmap_) {
379 clearCostmapWindows(2 * clearing_radius_, 2 * clearing_radius_);
383 std::vector<geometry_msgs::PoseStamped> global_plan;
384 if(!planner_->makePlan(start, req.goal, global_plan) || global_plan.empty()){
385 ROS_DEBUG_NAMED(
"move_base",
"Failed to find a plan to exact goal of (%.2f, %.2f), searching for a feasible goal within tolerance",
386 req.goal.pose.position.x, req.goal.pose.position.y);
389 geometry_msgs::PoseStamped p;
391 bool found_legal =
false;
392 float resolution = planner_costmap_ros_->getCostmap()->getResolution();
393 float search_increment = resolution*3.0;
394 if(req.tolerance > 0.0 && req.tolerance < search_increment) search_increment = req.tolerance;
395 for(
float max_offset = search_increment; max_offset <= req.tolerance && !found_legal; max_offset += search_increment) {
396 for(
float y_offset = 0; y_offset <= max_offset && !found_legal; y_offset += search_increment) {
397 for(
float x_offset = 0; x_offset <= max_offset && !found_legal; x_offset += search_increment) {
400 if(x_offset < max_offset-1e-9 && y_offset < max_offset-1e-9)
continue;
403 for(
float y_mult = -1.0; y_mult <= 1.0 + 1e-9 && !found_legal; y_mult += 2.0) {
406 if(y_offset < 1e-9 && y_mult < -1.0 + 1e-9)
continue;
408 for(
float x_mult = -1.0; x_mult <= 1.0 + 1e-9 && !found_legal; x_mult += 2.0) {
409 if(x_offset < 1e-9 && x_mult < -1.0 + 1e-9)
continue;
411 p.pose.position.y = req.goal.pose.position.y + y_offset * y_mult;
412 p.pose.position.x = req.goal.pose.position.x + x_offset * x_mult;
414 if(planner_->makePlan(start, p, global_plan)){
415 if(!global_plan.empty()){
417 if (make_plan_add_unreachable_goal_) {
420 global_plan.push_back(req.goal);
424 ROS_DEBUG_NAMED(
"move_base",
"Found a plan to point (%.2f, %.2f)", p.pose.position.x, p.pose.position.y);
429 ROS_DEBUG_NAMED(
"move_base",
"Failed to find a plan to point (%.2f, %.2f)", p.pose.position.x, p.pose.position.y);
439 resp.plan.poses.resize(global_plan.size());
440 for(
unsigned int i = 0; i < global_plan.size(); ++i){
441 resp.plan.poses[i] = global_plan[i];
447 MoveBase::~MoveBase(){
448 recovery_behaviors_.clear();
455 if(planner_costmap_ros_ != NULL)
456 delete planner_costmap_ros_;
458 if(controller_costmap_ros_ != NULL)
459 delete controller_costmap_ros_;
461 planner_thread_->interrupt();
462 planner_thread_->join();
464 delete planner_thread_;
466 delete planner_plan_;
468 delete controller_plan_;
474 bool MoveBase::makePlan(
const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan){
475 boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(planner_costmap_ros_->getCostmap()->getMutex()));
481 if(planner_costmap_ros_ == NULL) {
482 ROS_ERROR(
"Planner costmap ROS is NULL, unable to create global plan");
487 geometry_msgs::PoseStamped global_pose;
488 if(!getRobotPose(global_pose, planner_costmap_ros_)) {
489 ROS_WARN(
"Unable to get starting pose of robot, unable to create global plan");
493 const geometry_msgs::PoseStamped&
start = global_pose;
496 if(!planner_->makePlan(start, goal, plan) || plan.empty()){
497 ROS_DEBUG_NAMED(
"move_base",
"Failed to find a plan to point (%.2f, %.2f)",
goal.pose.position.x,
goal.pose.position.y);
504 void MoveBase::publishZeroVelocity(){
505 geometry_msgs::Twist cmd_vel;
506 cmd_vel.linear.x = 0.0;
507 cmd_vel.linear.y = 0.0;
508 cmd_vel.angular.z = 0.0;
509 vel_pub_.publish(cmd_vel);
512 bool MoveBase::isQuaternionValid(
const geometry_msgs::Quaternion& q){
514 if(!std::isfinite(q.x) || !std::isfinite(q.y) || !std::isfinite(q.z) || !std::isfinite(q.w)){
515 ROS_ERROR(
"Quaternion has nans or infs... discarding as a navigation goal");
522 if(tf_q.length2() < 1e-6){
523 ROS_ERROR(
"Quaternion has length close to zero... discarding as navigation goal");
530 tf2::Vector3 up(0, 0, 1);
532 double dot = up.dot(up.rotate(tf_q.getAxis(), tf_q.getAngle()));
534 if(fabs(dot - 1) > 1e-3){
535 ROS_ERROR(
"Quaternion is invalid... for navigation the z-axis of the quaternion must be close to vertical.");
542 geometry_msgs::PoseStamped MoveBase::goalToGlobalFrame(
const geometry_msgs::PoseStamped& goal_pose_msg){
543 std::string global_frame = planner_costmap_ros_->getGlobalFrameID();
544 geometry_msgs::PoseStamped goal_pose, global_pose;
545 goal_pose = goal_pose_msg;
552 tf_.
transform(goal_pose_msg, global_pose, global_frame);
555 ROS_WARN(
"Failed to transform the goal pose from %s into the %s frame: %s",
556 goal_pose.header.frame_id.c_str(), global_frame.c_str(), ex.what());
557 return goal_pose_msg;
566 planner_cond_.notify_one();
569 void MoveBase::planThread(){
573 bool wait_for_wake =
false;
574 boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
577 while(wait_for_wake || !runPlanner_){
579 ROS_DEBUG_NAMED(
"move_base_plan_thread",
"Planner thread is suspending");
580 planner_cond_.wait(lock);
581 wait_for_wake =
false;
586 geometry_msgs::PoseStamped temp_goal = planner_goal_;
591 planner_plan_->clear();
592 bool gotPlan = n.
ok() && makePlan(temp_goal, *planner_plan_);
595 ROS_DEBUG_NAMED(
"move_base_plan_thread",
"Got Plan with %zu points!", planner_plan_->size());
597 std::vector<geometry_msgs::PoseStamped>* temp_plan = planner_plan_;
600 planner_plan_ = latest_plan_;
601 latest_plan_ = temp_plan;
603 planning_retries_ = 0;
604 new_global_plan_ =
true;
606 ROS_DEBUG_NAMED(
"move_base_plan_thread",
"Generated a plan from the base_global_planner");
611 if(planner_frequency_ <= 0)
626 (
ros::Time::now() > attempt_end || planning_retries_ > uint32_t(max_planning_retries_))){
630 publishZeroVelocity();
641 if(planner_frequency_ > 0){
644 wait_for_wake =
true;
645 timer = n.
createTimer(sleep_time, &MoveBase::wakePlanner,
this);
651 void MoveBase::executeCb(
const move_base_msgs::MoveBaseGoalConstPtr& move_base_goal)
653 if(!isQuaternionValid(move_base_goal->target_pose.pose.orientation)){
654 as_->setAborted(move_base_msgs::MoveBaseResult(),
"Aborting on goal because it was sent with an invalid quaternion");
658 geometry_msgs::PoseStamped
goal = goalToGlobalFrame(move_base_goal->target_pose);
660 publishZeroVelocity();
662 boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
663 planner_goal_ =
goal;
665 planner_cond_.notify_one();
668 current_goal_pub_.publish(goal);
671 if(shutdown_costmaps_){
672 ROS_DEBUG_NAMED(
"move_base",
"Starting up costmaps that were shut down previously");
673 planner_costmap_ros_->start();
674 controller_costmap_ros_->start();
681 planning_retries_ = 0;
688 ROS_INFO(
"Setting controller frequency to %.2f", controller_frequency_);
690 c_freq_change_ =
false;
693 if(as_->isPreemptRequested()){
694 if(as_->isNewGoalAvailable()){
696 move_base_msgs::MoveBaseGoal new_goal = *as_->acceptNewGoal();
698 if(!isQuaternionValid(new_goal.target_pose.pose.orientation)){
699 as_->setAborted(move_base_msgs::MoveBaseResult(),
"Aborting on goal because it was sent with an invalid quaternion");
703 goal = goalToGlobalFrame(new_goal.target_pose);
711 planner_goal_ =
goal;
713 planner_cond_.notify_one();
717 ROS_DEBUG_NAMED(
"move_base",
"move_base has received a goal of x: %.2f, y: %.2f",
goal.pose.position.x,
goal.pose.position.y);
718 current_goal_pub_.publish(goal);
724 planning_retries_ = 0;
740 if(
goal.header.frame_id != planner_costmap_ros_->getGlobalFrameID()){
741 goal = goalToGlobalFrame(goal);
749 planner_goal_ =
goal;
751 planner_cond_.notify_one();
755 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);
756 current_goal_pub_.publish(goal);
762 planning_retries_ = 0;
769 bool done = executeCycle(goal);
783 ROS_WARN(
"Control loop missed its desired rate of %.4fHz... the loop actually took %.4f seconds", controller_frequency_, r.cycleTime().toSec());
789 planner_cond_.notify_one();
793 as_->setAborted(move_base_msgs::MoveBaseResult(),
"Aborting on the goal because the node has been killed");
797 double MoveBase::distance(
const geometry_msgs::PoseStamped& p1,
const geometry_msgs::PoseStamped& p2)
799 return hypot(p1.pose.position.x - p2.pose.position.x, p1.pose.position.y - p2.pose.position.y);
802 bool MoveBase::executeCycle(geometry_msgs::PoseStamped& goal){
803 boost::recursive_mutex::scoped_lock ecl(configuration_mutex_);
805 geometry_msgs::Twist cmd_vel;
808 geometry_msgs::PoseStamped global_pose;
809 getRobotPose(global_pose, planner_costmap_ros_);
810 const geometry_msgs::PoseStamped& current_position = global_pose;
813 move_base_msgs::MoveBaseFeedback feedback;
814 feedback.base_position = current_position;
815 as_->publishFeedback(feedback);
818 if(
distance(current_position, oscillation_pose_) >= oscillation_distance_)
821 oscillation_pose_ = current_position;
829 if(!controller_costmap_ros_->isCurrent()){
831 publishZeroVelocity();
836 if(new_global_plan_){
838 new_global_plan_ =
false;
843 std::vector<geometry_msgs::PoseStamped>* temp_plan = controller_plan_;
845 boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
846 controller_plan_ = latest_plan_;
847 latest_plan_ = temp_plan;
851 if(!tc_->setPlan(*controller_plan_)){
853 ROS_ERROR(
"Failed to pass global plan to the controller, aborting.");
861 as_->setAborted(move_base_msgs::MoveBaseResult(),
"Failed to pass global plan to the controller.");
875 boost::recursive_mutex::scoped_lock lock(planner_mutex_);
877 planner_cond_.notify_one();
879 ROS_DEBUG_NAMED(
"move_base",
"Waiting for plan, in the planning state.");
887 if(tc_->isGoalReached()){
892 boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
896 as_->setSucceeded(move_base_msgs::MoveBaseResult(),
"Goal reached.");
901 if(oscillation_timeout_ > 0.0 &&
904 publishZeroVelocity();
910 boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(controller_costmap_ros_->getCostmap()->getMutex()));
912 if(tc_->computeVelocityCommands(cmd_vel)){
913 ROS_DEBUG_NAMED(
"move_base",
"Got a valid command from the local planner: %.3lf, %.3lf, %.3lf",
914 cmd_vel.linear.x, cmd_vel.linear.y, cmd_vel.angular.z );
917 vel_pub_.publish(cmd_vel);
922 ROS_DEBUG_NAMED(
"move_base",
"The local planner could not find a valid plan.");
928 publishZeroVelocity();
935 planning_retries_ = 0;
937 publishZeroVelocity();
940 boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
942 planner_cond_.notify_one();
954 if(recovery_behavior_enabled_ && recovery_index_ < recovery_behaviors_.size()){
955 ROS_DEBUG_NAMED(
"move_base_recovery",
"Executing behavior %u of %zu", recovery_index_+1, recovery_behaviors_.size());
957 move_base_msgs::RecoveryStatus msg;
958 msg.pose_stamped = current_position;
959 msg.current_recovery_number = recovery_index_;
960 msg.total_number_of_recoveries = recovery_behaviors_.size();
961 msg.recovery_behavior_name = recovery_behavior_names_[recovery_index_];
963 recovery_status_pub_.publish(msg);
965 recovery_behaviors_[recovery_index_]->runBehavior();
973 planning_retries_ = 0;
980 ROS_DEBUG_NAMED(
"move_base_recovery",
"All recovery behaviors have failed, locking the planner and disabling it.");
982 boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
986 ROS_DEBUG_NAMED(
"move_base_recovery",
"Something should abort after this.");
989 ROS_ERROR(
"Aborting because a valid control could not be found. Even after executing all recovery behaviors");
990 as_->setAborted(move_base_msgs::MoveBaseResult(),
"Failed to find a valid control. Even after executing recovery behaviors.");
993 ROS_ERROR(
"Aborting because a valid plan could not be found. Even after executing all recovery behaviors");
994 as_->setAborted(move_base_msgs::MoveBaseResult(),
"Failed to find a valid plan. Even after executing recovery behaviors.");
997 ROS_ERROR(
"Aborting because the robot appears to be oscillating over and over. Even after executing all recovery behaviors");
998 as_->setAborted(move_base_msgs::MoveBaseResult(),
"Robot is oscillating. Even after executing recovery behaviors.");
1005 ROS_ERROR(
"This case should never be reached, something is wrong, aborting");
1008 boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
1009 runPlanner_ =
false;
1011 as_->setAborted(move_base_msgs::MoveBaseResult(),
"Reached a case that should not be hit in move_base. This is a bug, please report it.");
1021 if(node.
getParam(
"recovery_behaviors", behavior_list)){
1023 for(
int i = 0; i < behavior_list.
size(); ++i){
1025 if(behavior_list[i].hasMember(
"name") && behavior_list[i].hasMember(
"type")){
1027 for(
int j = i + 1; j < behavior_list.
size(); j++){
1029 if(behavior_list[j].hasMember(
"name") && behavior_list[j].hasMember(
"type")){
1030 std::string name_i = behavior_list[i][
"name"];
1031 std::string name_j = behavior_list[j][
"name"];
1032 if(name_i == name_j){
1033 ROS_ERROR(
"A recovery behavior with the name %s already exists, this is not allowed. Using the default recovery behaviors instead.",
1042 ROS_ERROR(
"Recovery behaviors must have a name and a type and this does not. Using the default recovery behaviors instead.");
1047 ROS_ERROR(
"Recovery behaviors must be specified as maps, but they are XmlRpcType %d. We'll use the default recovery behaviors instead.",
1048 behavior_list[i].getType());
1054 for(
int i = 0; i < behavior_list.
size(); ++i){
1057 if(!recovery_loader_.isClassAvailable(behavior_list[i][
"type"])){
1058 std::vector<std::string> classes = recovery_loader_.getDeclaredClasses();
1059 for(
unsigned int i = 0; i < classes.size(); ++i){
1060 if(behavior_list[i][
"type"] == recovery_loader_.getName(classes[i])){
1062 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.",
1063 std::string(behavior_list[i][
"type"]).c_str(), classes[i].c_str());
1064 behavior_list[i][
"type"] = classes[i];
1073 if(behavior.get() == NULL){
1074 ROS_ERROR(
"The ClassLoader returned a null pointer without throwing an exception. This should not happen");
1079 behavior->initialize(behavior_list[i][
"name"], &
tf_, planner_costmap_ros_, controller_costmap_ros_);
1080 recovery_behavior_names_.push_back(behavior_list[i][
"name"]);
1081 recovery_behaviors_.push_back(behavior);
1084 ROS_ERROR(
"Failed to load a plugin. Using default recovery behaviors. Error: %s", ex.what());
1090 ROS_ERROR(
"The recovery behavior specification must be a list, but is of XmlRpcType %d. We'll use the default recovery behaviors instead.",
1105 void MoveBase::loadDefaultRecoveryBehaviors(){
1106 recovery_behaviors_.clear();
1110 n.
setParam(
"conservative_reset/reset_distance", conservative_reset_dist_);
1111 n.
setParam(
"aggressive_reset/reset_distance", circumscribed_radius_ * 4);
1115 cons_clear->initialize(
"conservative_reset", &tf_, planner_costmap_ros_, controller_costmap_ros_);
1116 recovery_behavior_names_.push_back(
"conservative_reset");
1117 recovery_behaviors_.push_back(cons_clear);
1121 if(clearing_rotation_allowed_){
1122 rotate->initialize(
"rotate_recovery", &tf_, planner_costmap_ros_, controller_costmap_ros_);
1123 recovery_behavior_names_.push_back(
"rotate_recovery");
1124 recovery_behaviors_.push_back(rotate);
1129 ags_clear->initialize(
"aggressive_reset", &tf_, planner_costmap_ros_, controller_costmap_ros_);
1130 recovery_behavior_names_.push_back(
"aggressive_reset");
1131 recovery_behaviors_.push_back(ags_clear);
1134 if(clearing_rotation_allowed_){
1135 recovery_behaviors_.push_back(rotate);
1136 recovery_behavior_names_.push_back(
"rotate_recovery");
1140 ROS_FATAL(
"Failed to load a plugin. This should not happen on default recovery behaviors. Error: %s", ex.what());
1146 void MoveBase::resetState(){
1148 boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
1149 runPlanner_ =
false;
1154 recovery_index_ = 0;
1156 publishZeroVelocity();
1159 if(shutdown_costmaps_){
1161 planner_costmap_ros_->stop();
1162 controller_costmap_ros_->stop();
1169 geometry_msgs::PoseStamped robot_pose;
1171 robot_pose.header.frame_id = robot_base_frame_;
1187 ROS_ERROR_THROTTLE(1.0,
"Connectivity Error looking up robot pose: %s\n", ex.what());
1192 ROS_ERROR_THROTTLE(1.0,
"Extrapolation Error looking up robot pose: %s\n", ex.what());
1197 if (!global_pose.header.stamp.isZero() &&
1201 "Current time: %.4f, pose stamp: %.4f, tolerance: %.4f", costmap->
getName().c_str(),