move_base.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2008, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of the Willow Garage nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *
35 * Author: Eitan Marder-Eppstein
36 * Mike Phillips (put the planner in its own thread)
37 *********************************************************************/
38 #include <move_base/move_base.h>
39 #include <move_base_msgs/RecoveryStatus.h>
40 #include <cmath>
41 
42 #include <boost/algorithm/string.hpp>
43 #include <boost/thread.hpp>
44 
45 #include <geometry_msgs/Twist.h>
46 
48 
49 namespace move_base {
50 
52  tf_(tf),
53  as_(NULL),
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) {
60 
61  as_ = new MoveBaseActionServer(ros::NodeHandle(), "move_base", [this](auto& goal){ executeCb(goal); }, false);
62 
63  ros::NodeHandle private_nh("~");
64  ros::NodeHandle nh;
65 
66  recovery_trigger_ = PLANNING_R;
67 
68  //get some parameters that will be global to the move base node
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); // disabled by default
79 
80  private_nh.param("oscillation_timeout", oscillation_timeout_, 0.0);
81  private_nh.param("oscillation_distance", oscillation_distance_, 0.5);
82 
83  // parameters of make_plan service
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);
86 
87  //set up plan triple buffer
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>();
91 
92  //set up the planner's thread
93  planner_thread_ = new boost::thread(boost::bind(&MoveBase::planThread, this));
94 
95  //for commanding the base
96  vel_pub_ = nh.advertise<geometry_msgs::Twist>("cmd_vel", 1);
97  current_goal_pub_ = private_nh.advertise<geometry_msgs::PoseStamped>("current_goal", 0 );
98 
99  ros::NodeHandle action_nh("move_base");
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);
102 
103  //we'll provide a mechanism for some people to send goals as PoseStamped messages over a topic
104  //they won't get any useful information back about its status, but this is useful for tools
105  //like nav_view and rviz
106  ros::NodeHandle simple_nh("move_base_simple");
107  goal_sub_ = simple_nh.subscribe<geometry_msgs::PoseStamped>("goal", 1, [this](auto& goal){ goalCB(goal); });
108 
109  //we'll assume the radius of the robot to be consistent with what's specified for the costmaps
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);
114 
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);
118 
119  //create the ros wrapper for the planner's costmap... and initializer a pointer we'll use with the underlying map
120  planner_costmap_ros_ = new costmap_2d::Costmap2DROS("global_costmap", tf_);
121  planner_costmap_ros_->pause();
122 
123  //initialize the global planner
124  try {
125  planner_ = bgp_loader_.createInstance(global_planner);
126  planner_->initialize(bgp_loader_.getName(global_planner), planner_costmap_ros_);
127  } catch (const pluginlib::PluginlibException& ex) {
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());
129  exit(1);
130  }
131 
132  //create the ros wrapper for the controller's costmap... and initializer a pointer we'll use with the underlying map
133  controller_costmap_ros_ = new costmap_2d::Costmap2DROS("local_costmap", tf_);
134  controller_costmap_ros_->pause();
135 
136  //create a local planner
137  try {
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_);
141  } catch (const pluginlib::PluginlibException& ex) {
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());
143  exit(1);
144  }
145 
146  // Start actively updating costmaps based on sensor data
147  planner_costmap_ros_->start();
148  controller_costmap_ros_->start();
149 
150  //advertise a service for getting a plan
151  make_plan_srv_ = private_nh.advertiseService("make_plan", &MoveBase::planService, this);
152 
153  //advertise a service for clearing the costmaps
154  clear_costmaps_srv_ = private_nh.advertiseService("clear_costmaps", &MoveBase::clearCostmapsService, this);
155 
156  //if we shutdown our costmaps when we're deactivated... we'll do that now
157  if(shutdown_costmaps_){
158  ROS_DEBUG_NAMED("move_base","Stopping costmaps initially");
159  planner_costmap_ros_->stop();
160  controller_costmap_ros_->stop();
161  }
162 
163  //load any user specified recovery behaviors, and if that fails load the defaults
164  if(!loadRecoveryBehaviors(private_nh)){
165  loadDefaultRecoveryBehaviors();
166  }
167 
168  //initially, we'll need to make a plan
169  state_ = PLANNING;
170 
171  //we'll start executing recovery behaviors at the beginning of our list
172  recovery_index_ = 0;
173 
174  //we're all set up now so we can start the action server
175  as_->start();
176 
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);
180  }
181 
182  void MoveBase::reconfigureCB(move_base::MoveBaseConfig &config, uint32_t level){
183  boost::recursive_mutex::scoped_lock l(configuration_mutex_);
184 
185  //The first time we're called, we just want to make sure we have the
186  //original configuration
187  if(!setup_)
188  {
189  last_config_ = config;
190  default_config_ = config;
191  setup_ = true;
192  return;
193  }
194 
195  if(config.restore_defaults) {
196  config = default_config_;
197  //if someone sets restore defaults on the parameter server, prevent looping
198  config.restore_defaults = false;
199  }
200 
201  if(planner_frequency_ != config.planner_frequency)
202  {
203  planner_frequency_ = config.planner_frequency;
204  p_freq_change_ = true;
205  }
206 
207  if(controller_frequency_ != config.controller_frequency)
208  {
209  controller_frequency_ = config.controller_frequency;
210  c_freq_change_ = true;
211  }
212 
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;
217 
218  recovery_behavior_enabled_ = config.recovery_behavior_enabled;
219  clearing_rotation_allowed_ = config.clearing_rotation_allowed;
220  shutdown_costmaps_ = config.shutdown_costmaps;
221 
222  oscillation_timeout_ = config.oscillation_timeout;
223  oscillation_distance_ = config.oscillation_distance;
224  if(config.base_global_planner != last_config_.base_global_planner) {
225  boost::shared_ptr<nav_core::BaseGlobalPlanner> old_planner = planner_;
226  //initialize the global planner
227  ROS_INFO("Loading global planner %s", config.base_global_planner.c_str());
228  try {
229  planner_ = bgp_loader_.createInstance(config.base_global_planner);
230 
231  // wait for the current planner to finish planning
232  boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
233 
234  // Clean up before initializing the new planner
235  planner_plan_->clear();
236  latest_plan_->clear();
237  controller_plan_->clear();
238  resetState();
239  planner_->initialize(bgp_loader_.getName(config.base_global_planner), planner_costmap_ros_);
240 
241  lock.unlock();
242  } catch (const pluginlib::PluginlibException& ex) {
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;
247  }
248  }
249 
250  if(config.base_local_planner != last_config_.base_local_planner){
252  //create a local planner
253  try {
254  tc_ = blp_loader_.createInstance(config.base_local_planner);
255  // Clean up before initializing the new planner
256  planner_plan_->clear();
257  latest_plan_->clear();
258  controller_plan_->clear();
259  resetState();
260  tc_->initialize(blp_loader_.getName(config.base_local_planner), &tf_, controller_costmap_ros_);
261  } catch (const pluginlib::PluginlibException& ex) {
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());
264  tc_ = old_planner;
265  config.base_local_planner = last_config_.base_local_planner;
266  }
267  }
268 
269  make_plan_clear_costmap_ = config.make_plan_clear_costmap;
270  make_plan_add_unreachable_goal_ = config.make_plan_add_unreachable_goal;
271 
272  last_config_ = config;
273  }
274 
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;
278  action_goal.header.stamp = ros::Time::now();
279  action_goal.goal.target_pose = *goal;
280 
281  action_goal_pub_.publish(action_goal);
282  }
283 
284  void MoveBase::clearCostmapWindows(double size_x, double size_y){
285  geometry_msgs::PoseStamped global_pose;
286 
287  //clear the planner's costmap
288  getRobotPose(global_pose, planner_costmap_ros_);
289 
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;
294 
295  pt.x = x - size_x / 2;
296  pt.y = y - size_y / 2;
297  clear_poly.push_back(pt);
298 
299  pt.x = x + size_x / 2;
300  pt.y = y - size_y / 2;
301  clear_poly.push_back(pt);
302 
303  pt.x = x + size_x / 2;
304  pt.y = y + size_y / 2;
305  clear_poly.push_back(pt);
306 
307  pt.x = x - size_x / 2;
308  pt.y = y + size_y / 2;
309  clear_poly.push_back(pt);
310 
311  planner_costmap_ros_->getCostmap()->setConvexPolygonCost(clear_poly, costmap_2d::FREE_SPACE);
312 
313  //clear the controller's costmap
314  getRobotPose(global_pose, controller_costmap_ros_);
315 
316  clear_poly.clear();
317  x = global_pose.pose.position.x;
318  y = global_pose.pose.position.y;
319 
320  pt.x = x - size_x / 2;
321  pt.y = y - size_y / 2;
322  clear_poly.push_back(pt);
323 
324  pt.x = x + size_x / 2;
325  pt.y = y - size_y / 2;
326  clear_poly.push_back(pt);
327 
328  pt.x = x + size_x / 2;
329  pt.y = y + size_y / 2;
330  clear_poly.push_back(pt);
331 
332  pt.x = x - size_x / 2;
333  pt.y = y + size_y / 2;
334  clear_poly.push_back(pt);
335 
336  controller_costmap_ros_->getCostmap()->setConvexPolygonCost(clear_poly, costmap_2d::FREE_SPACE);
337  }
338 
339  bool MoveBase::clearCostmapsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp){
340  //clear the costmaps
341  boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock_controller(*(controller_costmap_ros_->getCostmap()->getMutex()));
342  controller_costmap_ros_->resetLayers();
343 
344  boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock_planner(*(planner_costmap_ros_->getCostmap()->getMutex()));
345  planner_costmap_ros_->resetLayers();
346  return true;
347  }
348 
349 
350  bool MoveBase::planService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp){
351  if(as_->isActive()){
352  ROS_ERROR("move_base must be in an inactive state to make a plan for an external user");
353  return false;
354  }
355  //make sure we have a costmap for our planner
356  if(planner_costmap_ros_ == NULL){
357  ROS_ERROR("move_base cannot make a plan for you because it doesn't have a costmap");
358  return false;
359  }
360 
361  geometry_msgs::PoseStamped start;
362  //if the user does not specify a start pose, identified by an empty frame id, then use the robot's pose
363  if(req.start.header.frame_id.empty())
364  {
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");
368  return false;
369  }
370  start = global_pose;
371  }
372  else
373  {
374  start = req.start;
375  }
376 
377  if (make_plan_clear_costmap_) {
378  //update the copy of the costmap the planner uses
379  clearCostmapWindows(2 * clearing_radius_, 2 * clearing_radius_);
380  }
381 
382  //first try to make a plan to the exact desired goal
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);
387 
388  //search outwards for a feasible goal within the specified tolerance
389  geometry_msgs::PoseStamped p;
390  p = req.goal;
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) {
398 
399  //don't search again inside the current outer layer
400  if(x_offset < max_offset-1e-9 && y_offset < max_offset-1e-9) continue;
401 
402  //search to both sides of the desired goal
403  for(float y_mult = -1.0; y_mult <= 1.0 + 1e-9 && !found_legal; y_mult += 2.0) {
404 
405  //if one of the offsets is 0, -1*0 is still 0 (so get rid of one of the two)
406  if(y_offset < 1e-9 && y_mult < -1.0 + 1e-9) continue;
407 
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;
410 
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;
413 
414  if(planner_->makePlan(start, p, global_plan)){
415  if(!global_plan.empty()){
416 
417  if (make_plan_add_unreachable_goal_) {
418  //adding the (unreachable) original goal to the end of the global plan, in case the local planner can get you there
419  //(the reachable goal should have been added by the global planner)
420  global_plan.push_back(req.goal);
421  }
422 
423  found_legal = true;
424  ROS_DEBUG_NAMED("move_base", "Found a plan to point (%.2f, %.2f)", p.pose.position.x, p.pose.position.y);
425  break;
426  }
427  }
428  else{
429  ROS_DEBUG_NAMED("move_base","Failed to find a plan to point (%.2f, %.2f)", p.pose.position.x, p.pose.position.y);
430  }
431  }
432  }
433  }
434  }
435  }
436  }
437 
438  //copy the plan into a message to send out
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];
442  }
443 
444  return true;
445  }
446 
447  MoveBase::~MoveBase(){
448  recovery_behaviors_.clear();
449 
450  delete dsrv_;
451 
452  if(as_ != NULL)
453  delete as_;
454 
455  if(planner_costmap_ros_ != NULL)
456  delete planner_costmap_ros_;
457 
458  if(controller_costmap_ros_ != NULL)
459  delete controller_costmap_ros_;
460 
461  planner_thread_->interrupt();
462  planner_thread_->join();
463 
464  delete planner_thread_;
465 
466  delete planner_plan_;
467  delete latest_plan_;
468  delete controller_plan_;
469 
470  planner_.reset();
471  tc_.reset();
472  }
473 
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()));
476 
477  //make sure to set the plan to be empty initially
478  plan.clear();
479 
480  //since this gets called on handle activate
481  if(planner_costmap_ros_ == NULL) {
482  ROS_ERROR("Planner costmap ROS is NULL, unable to create global plan");
483  return false;
484  }
485 
486  //get the starting pose of the robot
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");
490  return false;
491  }
492 
493  const geometry_msgs::PoseStamped& start = global_pose;
494 
495  //if the planner fails or returns a zero length plan, planning failed
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);
498  return false;
499  }
500 
501  return true;
502  }
503 
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);
510  }
511 
512  bool MoveBase::isQuaternionValid(const geometry_msgs::Quaternion& q){
513  //first we need to check if the quaternion has nan's or infs
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");
516  return false;
517  }
518 
519  tf2::Quaternion tf_q(q.x, q.y, q.z, q.w);
520 
521  //next, we need to check if the length of the quaternion is close to zero
522  if(tf_q.length2() < 1e-6){
523  ROS_ERROR("Quaternion has length close to zero... discarding as navigation goal");
524  return false;
525  }
526 
527  //next, we'll normalize the quaternion and check that it transforms the vertical vector correctly
528  tf_q.normalize();
529 
530  tf2::Vector3 up(0, 0, 1);
531 
532  double dot = up.dot(up.rotate(tf_q.getAxis(), tf_q.getAngle()));
533 
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.");
536  return false;
537  }
538 
539  return true;
540  }
541 
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;
546 
547  //just get the latest available transform... for accuracy they should send
548  //goals in the frame of the planner
549  goal_pose.header.stamp = ros::Time();
550 
551  try{
552  tf_.transform(goal_pose_msg, global_pose, global_frame);
553  }
554  catch(tf2::TransformException& ex){
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;
558  }
559 
560  return global_pose;
561  }
562 
563  void MoveBase::wakePlanner(const ros::TimerEvent& event)
564  {
565  // we have slept long enough for rate
566  planner_cond_.notify_one();
567  }
568 
569  void MoveBase::planThread(){
570  ROS_DEBUG_NAMED("move_base_plan_thread","Starting planner thread...");
571  ros::NodeHandle n;
572  ros::Timer timer;
573  bool wait_for_wake = false;
574  boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
575  while(n.ok()){
576  //check if we should run the planner (the mutex is locked)
577  while(wait_for_wake || !runPlanner_){
578  //if we should not be running the planner then suspend this thread
579  ROS_DEBUG_NAMED("move_base_plan_thread","Planner thread is suspending");
580  planner_cond_.wait(lock);
581  wait_for_wake = false;
582  }
583  ros::Time start_time = ros::Time::now();
584 
585  //time to plan! get a copy of the goal and unlock the mutex
586  geometry_msgs::PoseStamped temp_goal = planner_goal_;
587  lock.unlock();
588  ROS_DEBUG_NAMED("move_base_plan_thread","Planning...");
589 
590  //run planner
591  planner_plan_->clear();
592  bool gotPlan = n.ok() && makePlan(temp_goal, *planner_plan_);
593 
594  if(gotPlan){
595  ROS_DEBUG_NAMED("move_base_plan_thread","Got Plan with %zu points!", planner_plan_->size());
596  //pointer swap the plans under mutex (the controller will pull from latest_plan_)
597  std::vector<geometry_msgs::PoseStamped>* temp_plan = planner_plan_;
598 
599  lock.lock();
600  planner_plan_ = latest_plan_;
601  latest_plan_ = temp_plan;
602  last_valid_plan_ = ros::Time::now();
603  planning_retries_ = 0;
604  new_global_plan_ = true;
605 
606  ROS_DEBUG_NAMED("move_base_plan_thread","Generated a plan from the base_global_planner");
607 
608  //make sure we only start the controller if we still haven't reached the goal
609  if(runPlanner_)
610  state_ = CONTROLLING;
611  if(planner_frequency_ <= 0)
612  runPlanner_ = false;
613  lock.unlock();
614  }
615  //if we didn't get a plan and we are in the planning state (the robot isn't moving)
616  else if(state_==PLANNING){
617  ROS_DEBUG_NAMED("move_base_plan_thread","No Plan...");
618  ros::Time attempt_end = last_valid_plan_ + ros::Duration(planner_patience_);
619 
620  //check if we've tried to make a plan for over our time limit or our maximum number of retries
621  //issue #496: we stop planning when one of the conditions is true, but if max_planning_retries_
622  //is negative (the default), it is just ignored and we have the same behavior as ever
623  lock.lock();
624  planning_retries_++;
625  if(runPlanner_ &&
626  (ros::Time::now() > attempt_end || planning_retries_ > uint32_t(max_planning_retries_))){
627  //we'll move into our obstacle clearing mode
628  state_ = CLEARING;
629  runPlanner_ = false; // proper solution for issue #523
630  publishZeroVelocity();
631  recovery_trigger_ = PLANNING_R;
632  }
633 
634  lock.unlock();
635  }
636 
637  //take the mutex for the next iteration
638  lock.lock();
639 
640  //setup sleep interface if needed
641  if(planner_frequency_ > 0){
642  ros::Duration sleep_time = (start_time + ros::Duration(1.0/planner_frequency_)) - ros::Time::now();
643  if (sleep_time > ros::Duration(0.0)){
644  wait_for_wake = true;
645  timer = n.createTimer(sleep_time, &MoveBase::wakePlanner, this);
646  }
647  }
648  }
649  }
650 
651  void MoveBase::executeCb(const move_base_msgs::MoveBaseGoalConstPtr& move_base_goal)
652  {
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");
655  return;
656  }
657 
658  geometry_msgs::PoseStamped goal = goalToGlobalFrame(move_base_goal->target_pose);
659 
660  publishZeroVelocity();
661  //we have a goal so start the planner
662  boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
663  planner_goal_ = goal;
664  runPlanner_ = true;
665  planner_cond_.notify_one();
666  lock.unlock();
667 
668  current_goal_pub_.publish(goal);
669 
670  ros::Rate r(controller_frequency_);
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();
675  }
676 
677  //we want to make sure that we reset the last time we had a valid plan and control
678  last_valid_control_ = ros::Time::now();
679  last_valid_plan_ = ros::Time::now();
680  last_oscillation_reset_ = ros::Time::now();
681  planning_retries_ = 0;
682 
683  ros::NodeHandle n;
684  while(n.ok())
685  {
686  if(c_freq_change_)
687  {
688  ROS_INFO("Setting controller frequency to %.2f", controller_frequency_);
689  r = ros::Rate(controller_frequency_);
690  c_freq_change_ = false;
691  }
692 
693  if(as_->isPreemptRequested()){
694  if(as_->isNewGoalAvailable()){
695  //if we're active and a new goal is available, we'll accept it, but we won't shut anything down
696  move_base_msgs::MoveBaseGoal new_goal = *as_->acceptNewGoal();
697 
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");
700  return;
701  }
702 
703  goal = goalToGlobalFrame(new_goal.target_pose);
704 
705  //we'll make sure that we reset our state for the next execution cycle
706  recovery_index_ = 0;
707  state_ = PLANNING;
708 
709  //we have a new goal so make sure the planner is awake
710  lock.lock();
711  planner_goal_ = goal;
712  runPlanner_ = true;
713  planner_cond_.notify_one();
714  lock.unlock();
715 
716  //publish the goal point to the visualizer
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);
719 
720  //make sure to reset our timeouts and counters
721  last_valid_control_ = ros::Time::now();
722  last_valid_plan_ = ros::Time::now();
723  last_oscillation_reset_ = ros::Time::now();
724  planning_retries_ = 0;
725  }
726  else {
727  //if we've been preempted explicitly we need to shut things down
728  resetState();
729 
730  //notify the ActionServer that we've successfully preempted
731  ROS_DEBUG_NAMED("move_base","Move base preempting the current goal");
732  as_->setPreempted();
733 
734  //we'll actually return from execute after preempting
735  return;
736  }
737  }
738 
739  //we also want to check if we've changed global frames because we need to transform our goal pose
740  if(goal.header.frame_id != planner_costmap_ros_->getGlobalFrameID()){
741  goal = goalToGlobalFrame(goal);
742 
743  //we want to go back to the planning state for the next execution cycle
744  recovery_index_ = 0;
745  state_ = PLANNING;
746 
747  //we have a new goal so make sure the planner is awake
748  lock.lock();
749  planner_goal_ = goal;
750  runPlanner_ = true;
751  planner_cond_.notify_one();
752  lock.unlock();
753 
754  //publish the goal point to the visualizer
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);
757 
758  //make sure to reset our timeouts and counters
759  last_valid_control_ = ros::Time::now();
760  last_valid_plan_ = ros::Time::now();
761  last_oscillation_reset_ = ros::Time::now();
762  planning_retries_ = 0;
763  }
764 
765  //for timing that gives real time even in simulation
767 
768  //the real work on pursuing a goal is done here
769  bool done = executeCycle(goal);
770 
771  //if we're done, then we'll return from execute
772  if(done)
773  return;
774 
775  //check if execution of the goal has completed in some way
776 
778  ROS_DEBUG_NAMED("move_base","Full control cycle time: %.9f\n", t_diff.toSec());
779 
780  r.sleep();
781  //make sure to sleep for the remainder of our cycle time
782  if(r.cycleTime() > ros::Duration(1 / controller_frequency_) && state_ == CONTROLLING)
783  ROS_WARN("Control loop missed its desired rate of %.4fHz... the loop actually took %.4f seconds", controller_frequency_, r.cycleTime().toSec());
784  }
785 
786  //wake up the planner thread so that it can exit cleanly
787  lock.lock();
788  runPlanner_ = true;
789  planner_cond_.notify_one();
790  lock.unlock();
791 
792  //if the node is killed then we'll abort and return
793  as_->setAborted(move_base_msgs::MoveBaseResult(), "Aborting on the goal because the node has been killed");
794  return;
795  }
796 
797  double MoveBase::distance(const geometry_msgs::PoseStamped& p1, const geometry_msgs::PoseStamped& p2)
798  {
799  return hypot(p1.pose.position.x - p2.pose.position.x, p1.pose.position.y - p2.pose.position.y);
800  }
801 
802  bool MoveBase::executeCycle(geometry_msgs::PoseStamped& goal){
803  boost::recursive_mutex::scoped_lock ecl(configuration_mutex_);
804  //we need to be able to publish velocity commands
805  geometry_msgs::Twist cmd_vel;
806 
807  //update feedback to correspond to our curent position
808  geometry_msgs::PoseStamped global_pose;
809  getRobotPose(global_pose, planner_costmap_ros_);
810  const geometry_msgs::PoseStamped& current_position = global_pose;
811 
812  //push the feedback out
813  move_base_msgs::MoveBaseFeedback feedback;
814  feedback.base_position = current_position;
815  as_->publishFeedback(feedback);
816 
817  //check to see if we've moved far enough to reset our oscillation timeout
818  if(distance(current_position, oscillation_pose_) >= oscillation_distance_)
819  {
820  last_oscillation_reset_ = ros::Time::now();
821  oscillation_pose_ = current_position;
822 
823  //if our last recovery was caused by oscillation, we want to reset the recovery index
824  if(recovery_trigger_ == OSCILLATION_R)
825  recovery_index_ = 0;
826  }
827 
828  //check that the observation buffers for the costmap are current, we don't want to drive blind
829  if(!controller_costmap_ros_->isCurrent()){
830  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());
831  publishZeroVelocity();
832  return false;
833  }
834 
835  //if we have a new plan then grab it and give it to the controller
836  if(new_global_plan_){
837  //make sure to set the new plan flag to false
838  new_global_plan_ = false;
839 
840  ROS_DEBUG_NAMED("move_base","Got a new plan...swap pointers");
841 
842  //do a pointer swap under mutex
843  std::vector<geometry_msgs::PoseStamped>* temp_plan = controller_plan_;
844 
845  boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
846  controller_plan_ = latest_plan_;
847  latest_plan_ = temp_plan;
848  lock.unlock();
849  ROS_DEBUG_NAMED("move_base","pointers swapped!");
850 
851  if(!tc_->setPlan(*controller_plan_)){
852  //ABORT and SHUTDOWN COSTMAPS
853  ROS_ERROR("Failed to pass global plan to the controller, aborting.");
854  resetState();
855 
856  //disable the planner thread
857  lock.lock();
858  runPlanner_ = false;
859  lock.unlock();
860 
861  as_->setAborted(move_base_msgs::MoveBaseResult(), "Failed to pass global plan to the controller.");
862  return true;
863  }
864 
865  //make sure to reset recovery_index_ since we were able to find a valid plan
866  if(recovery_trigger_ == PLANNING_R)
867  recovery_index_ = 0;
868  }
869 
870  //the move_base state machine, handles the control logic for navigation
871  switch(state_){
872  //if we are in a planning state, then we'll attempt to make a plan
873  case PLANNING:
874  {
875  boost::recursive_mutex::scoped_lock lock(planner_mutex_);
876  runPlanner_ = true;
877  planner_cond_.notify_one();
878  }
879  ROS_DEBUG_NAMED("move_base","Waiting for plan, in the planning state.");
880  break;
881 
882  //if we're controlling, we'll attempt to find valid velocity commands
883  case CONTROLLING:
884  ROS_DEBUG_NAMED("move_base","In controlling state.");
885 
886  //check to see if we've reached our goal
887  if(tc_->isGoalReached()){
888  ROS_DEBUG_NAMED("move_base","Goal reached!");
889  resetState();
890 
891  //disable the planner thread
892  boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
893  runPlanner_ = false;
894  lock.unlock();
895 
896  as_->setSucceeded(move_base_msgs::MoveBaseResult(), "Goal reached.");
897  return true;
898  }
899 
900  //check for an oscillation condition
901  if(oscillation_timeout_ > 0.0 &&
902  last_oscillation_reset_ + ros::Duration(oscillation_timeout_) < ros::Time::now())
903  {
904  publishZeroVelocity();
905  state_ = CLEARING;
906  recovery_trigger_ = OSCILLATION_R;
907  }
908 
909  {
910  boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(controller_costmap_ros_->getCostmap()->getMutex()));
911 
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 );
915  last_valid_control_ = ros::Time::now();
916  //make sure that we send the velocity command to the base
917  vel_pub_.publish(cmd_vel);
918  if(recovery_trigger_ == CONTROLLING_R)
919  recovery_index_ = 0;
920  }
921  else {
922  ROS_DEBUG_NAMED("move_base", "The local planner could not find a valid plan.");
923  ros::Time attempt_end = last_valid_control_ + ros::Duration(controller_patience_);
924 
925  //check if we've tried to find a valid control for longer than our time limit
926  if(ros::Time::now() > attempt_end){
927  //we'll move into our obstacle clearing mode
928  publishZeroVelocity();
929  state_ = CLEARING;
930  recovery_trigger_ = CONTROLLING_R;
931  }
932  else{
933  //otherwise, if we can't find a valid control, we'll go back to planning
934  last_valid_plan_ = ros::Time::now();
935  planning_retries_ = 0;
936  state_ = PLANNING;
937  publishZeroVelocity();
938 
939  //enable the planner thread in case it isn't running on a clock
940  boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
941  runPlanner_ = true;
942  planner_cond_.notify_one();
943  lock.unlock();
944  }
945  }
946  }
947 
948  break;
949 
950  //we'll try to clear out space with any user-provided recovery behaviors
951  case CLEARING:
952  ROS_DEBUG_NAMED("move_base","In clearing/recovery state");
953  //we'll invoke whatever recovery behavior we're currently on if they're enabled
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());
956 
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_];
962 
963  recovery_status_pub_.publish(msg);
964 
965  recovery_behaviors_[recovery_index_]->runBehavior();
966 
967  //we at least want to give the robot some time to stop oscillating after executing the behavior
968  last_oscillation_reset_ = ros::Time::now();
969 
970  //we'll check if the recovery behavior actually worked
971  ROS_DEBUG_NAMED("move_base_recovery","Going back to planning state");
972  last_valid_plan_ = ros::Time::now();
973  planning_retries_ = 0;
974  state_ = PLANNING;
975 
976  //update the index of the next recovery behavior that we'll try
977  recovery_index_++;
978  }
979  else{
980  ROS_DEBUG_NAMED("move_base_recovery","All recovery behaviors have failed, locking the planner and disabling it.");
981  //disable the planner thread
982  boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
983  runPlanner_ = false;
984  lock.unlock();
985 
986  ROS_DEBUG_NAMED("move_base_recovery","Something should abort after this.");
987 
988  if(recovery_trigger_ == CONTROLLING_R){
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.");
991  }
992  else if(recovery_trigger_ == PLANNING_R){
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.");
995  }
996  else if(recovery_trigger_ == OSCILLATION_R){
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.");
999  }
1000  resetState();
1001  return true;
1002  }
1003  break;
1004  default:
1005  ROS_ERROR("This case should never be reached, something is wrong, aborting");
1006  resetState();
1007  //disable the planner thread
1008  boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
1009  runPlanner_ = false;
1010  lock.unlock();
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.");
1012  return true;
1013  }
1014 
1015  //we aren't done yet
1016  return false;
1017  }
1018 
1019  bool MoveBase::loadRecoveryBehaviors(ros::NodeHandle node){
1020  XmlRpc::XmlRpcValue behavior_list;
1021  if(node.getParam("recovery_behaviors", behavior_list)){
1022  if(behavior_list.getType() == XmlRpc::XmlRpcValue::TypeArray){
1023  for(int i = 0; i < behavior_list.size(); ++i){
1024  if(behavior_list[i].getType() == XmlRpc::XmlRpcValue::TypeStruct){
1025  if(behavior_list[i].hasMember("name") && behavior_list[i].hasMember("type")){
1026  //check for recovery behaviors with the same name
1027  for(int j = i + 1; j < behavior_list.size(); j++){
1028  if(behavior_list[j].getType() == XmlRpc::XmlRpcValue::TypeStruct){
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.",
1034  name_i.c_str());
1035  return false;
1036  }
1037  }
1038  }
1039  }
1040  }
1041  else{
1042  ROS_ERROR("Recovery behaviors must have a name and a type and this does not. Using the default recovery behaviors instead.");
1043  return false;
1044  }
1045  }
1046  else{
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());
1049  return false;
1050  }
1051  }
1052 
1053  //if we've made it to this point, we know that the list is legal so we'll create all the recovery behaviors
1054  for(int i = 0; i < behavior_list.size(); ++i){
1055  try{
1056  //check if a non fully qualified name has potentially been passed in
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])){
1061  //if we've found a match... we'll get the fully qualified name and break out of the loop
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];
1065  break;
1066  }
1067  }
1068  }
1069 
1070  boost::shared_ptr<nav_core::RecoveryBehavior> behavior(recovery_loader_.createInstance(behavior_list[i]["type"]));
1071 
1072  //shouldn't be possible, but it won't hurt to check
1073  if(behavior.get() == NULL){
1074  ROS_ERROR("The ClassLoader returned a null pointer without throwing an exception. This should not happen");
1075  return false;
1076  }
1077 
1078  //initialize the recovery behavior with its name
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);
1082  }
1083  catch(pluginlib::PluginlibException& ex){
1084  ROS_ERROR("Failed to load a plugin. Using default recovery behaviors. Error: %s", ex.what());
1085  return false;
1086  }
1087  }
1088  }
1089  else{
1090  ROS_ERROR("The recovery behavior specification must be a list, but is of XmlRpcType %d. We'll use the default recovery behaviors instead.",
1091  behavior_list.getType());
1092  return false;
1093  }
1094  }
1095  else{
1096  //if no recovery_behaviors are specified, we'll just load the defaults
1097  return false;
1098  }
1099 
1100  //if we've made it here... we've constructed a recovery behavior list successfully
1101  return true;
1102  }
1103 
1104  //we'll load our default recovery behaviors here
1105  void MoveBase::loadDefaultRecoveryBehaviors(){
1106  recovery_behaviors_.clear();
1107  try{
1108  //we need to set some parameters based on what's been passed in to us to maintain backwards compatibility
1109  ros::NodeHandle n("~");
1110  n.setParam("conservative_reset/reset_distance", conservative_reset_dist_);
1111  n.setParam("aggressive_reset/reset_distance", circumscribed_radius_ * 4);
1112 
1113  //first, we'll load a recovery behavior to clear the costmap
1114  boost::shared_ptr<nav_core::RecoveryBehavior> cons_clear(recovery_loader_.createInstance("clear_costmap_recovery/ClearCostmapRecovery"));
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);
1118 
1119  //next, we'll load a recovery behavior to rotate in place
1120  boost::shared_ptr<nav_core::RecoveryBehavior> rotate(recovery_loader_.createInstance("rotate_recovery/RotateRecovery"));
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);
1125  }
1126 
1127  //next, we'll load a recovery behavior that will do an aggressive reset of the costmap
1128  boost::shared_ptr<nav_core::RecoveryBehavior> ags_clear(recovery_loader_.createInstance("clear_costmap_recovery/ClearCostmapRecovery"));
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);
1132 
1133  //we'll rotate in-place one more time
1134  if(clearing_rotation_allowed_){
1135  recovery_behaviors_.push_back(rotate);
1136  recovery_behavior_names_.push_back("rotate_recovery");
1137  }
1138  }
1139  catch(pluginlib::PluginlibException& ex){
1140  ROS_FATAL("Failed to load a plugin. This should not happen on default recovery behaviors. Error: %s", ex.what());
1141  }
1142 
1143  return;
1144  }
1145 
1146  void MoveBase::resetState(){
1147  // Disable the planner thread
1148  boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
1149  runPlanner_ = false;
1150  lock.unlock();
1151 
1152  // Reset statemachine
1153  state_ = PLANNING;
1154  recovery_index_ = 0;
1155  recovery_trigger_ = PLANNING_R;
1156  publishZeroVelocity();
1157 
1158  //if we shutdown our costmaps when we're deactivated... we'll do that now
1159  if(shutdown_costmaps_){
1160  ROS_DEBUG_NAMED("move_base","Stopping costmaps");
1161  planner_costmap_ros_->stop();
1162  controller_costmap_ros_->stop();
1163  }
1164  }
1165 
1166  bool MoveBase::getRobotPose(geometry_msgs::PoseStamped& global_pose, costmap_2d::Costmap2DROS* costmap)
1167  {
1168  tf2::toMsg(tf2::Transform::getIdentity(), global_pose.pose);
1169  geometry_msgs::PoseStamped robot_pose;
1170  tf2::toMsg(tf2::Transform::getIdentity(), robot_pose.pose);
1171  robot_pose.header.frame_id = robot_base_frame_;
1172  robot_pose.header.stamp = ros::Time(); // latest available
1173  ros::Time current_time = ros::Time::now(); // save time for checking tf delay later
1174 
1175  // get robot pose on the given costmap frame
1176  try
1177  {
1178  tf_.transform(robot_pose, global_pose, costmap->getGlobalFrameID());
1179  }
1180  catch (tf2::LookupException& ex)
1181  {
1182  ROS_ERROR_THROTTLE(1.0, "No Transform available Error looking up robot pose: %s\n", ex.what());
1183  return false;
1184  }
1185  catch (tf2::ConnectivityException& ex)
1186  {
1187  ROS_ERROR_THROTTLE(1.0, "Connectivity Error looking up robot pose: %s\n", ex.what());
1188  return false;
1189  }
1190  catch (tf2::ExtrapolationException& ex)
1191  {
1192  ROS_ERROR_THROTTLE(1.0, "Extrapolation Error looking up robot pose: %s\n", ex.what());
1193  return false;
1194  }
1195 
1196  // check if global_pose time stamp is within costmap transform tolerance
1197  if (!global_pose.header.stamp.isZero() &&
1198  current_time.toSec() - global_pose.header.stamp.toSec() > costmap->getTransformTolerance())
1199  {
1200  ROS_WARN_THROTTLE(1.0, "Transform timeout for %s. " \
1201  "Current time: %.4f, pose stamp: %.4f, tolerance: %.4f", costmap->getName().c_str(),
1202  current_time.toSec(), global_pose.header.stamp.toSec(), costmap->getTransformTolerance());
1203  return false;
1204  }
1205 
1206  return true;
1207  }
1208 };
XmlRpc::XmlRpcValue::size
int size() const
ROS_ERROR_THROTTLE
#define ROS_ERROR_THROTTLE(period,...)
ros::NodeHandle::setParam
void setParam(const std::string &key, bool b) const
boost::shared_ptr< nav_core::BaseGlobalPlanner >
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ROS_WARN_THROTTLE
#define ROS_WARN_THROTTLE(period,...)
move_base::CLEARING
@ CLEARING
Definition: move_base.h:104
move_base::CONTROLLING
@ CONTROLLING
Definition: move_base.h:103
TimeBase< Time, Duration >::toSec
double toSec() const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
XmlRpc::XmlRpcValue::TypeStruct
TypeStruct
move_base::MoveBaseActionServer
actionlib::SimpleActionServer< move_base_msgs::MoveBaseAction > MoveBaseActionServer
Definition: move_base.h:99
pluginlib::PluginlibException
costmap_2d::Costmap2DROS::getTransformTolerance
double getTransformTolerance() const
dot
TFSIMD_FORCE_INLINE tfScalar dot(const Quaternion &q1, const Quaternion &q2)
tf2::Transform::getIdentity
static const Transform & getIdentity()
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
ros::WallTime::now
static WallTime now()
tf2::ExtrapolationException
move_base
Definition: move_base.h:62
start
int start[2]
ROS_WARN
#define ROS_WARN(...)
tf2_ros::Buffer
move_base.h
distance
double distance(double x0, double y0, double x1, double y1)
move_base::PLANNING
@ PLANNING
Definition: move_base.h:102
goal
int goal[2]
tf2::LookupException
ros::TimerEvent
ros::WallTime
tf2::ConnectivityException
XmlRpc::XmlRpcValue::getType
const Type & getType() const
ROS_FATAL
#define ROS_FATAL(...)
move_base::MoveBase::MoveBase
MoveBase(tf2_ros::Buffer &tf)
Constructor for the actions.
Definition: move_base.cpp:87
XmlRpc::XmlRpcValue::TypeArray
TypeArray
ros::this_node::getName
const ROSCPP_DECL std::string & getName()
ros::NodeHandle::ok
bool ok() const
tf2_ros::BufferInterface::transform
B & transform(const A &in, B &out, const std::string &target_frame, const ros::Time &target_time, const std::string &fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
move_base::PLANNING_R
@ PLANNING_R
Definition: move_base.h:109
ros::Time
ROS_ERROR
#define ROS_ERROR(...)
move_base::OSCILLATION_R
@ OSCILLATION_R
Definition: move_base.h:111
costmap_2d::Costmap2DROS::getName
const std::string & getName() const noexcept
tf2::Quaternion
tf2_geometry_msgs.h
tf2::toMsg
B toMsg(const A &a)
ros::Rate
tf
costmap_2d::FREE_SPACE
static const unsigned char FREE_SPACE
DurationBase< WallDuration >::toSec
double toSec() const
costmap_2d::Costmap2DROS::getGlobalFrameID
const std::string & getGlobalFrameID() const noexcept
ros::WallDuration
tf_
tf2_ros::Buffer * tf_
tf2::TransformException
ROS_INFO
#define ROS_INFO(...)
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
ros::Timer
costmap_2d::Costmap2DROS
XmlRpc::XmlRpcValue
ros::NodeHandle
ros::Time::now
static Time now()
move_base::CONTROLLING_R
@ CONTROLLING_R
Definition: move_base.h:110


move_base
Author(s): Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:45