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 <cmath>
40 
41 #include <boost/algorithm/string.hpp>
42 #include <boost/thread.hpp>
43 
44 #include <geometry_msgs/Twist.h>
45 
46 namespace move_base {
47 
49  tf_(tf),
50  as_(NULL),
51  planner_costmap_ros_(NULL), controller_costmap_ros_(NULL),
52  bgp_loader_("nav_core", "nav_core::BaseGlobalPlanner"),
53  blp_loader_("nav_core", "nav_core::BaseLocalPlanner"),
54  recovery_loader_("nav_core", "nav_core::RecoveryBehavior"),
55  planner_plan_(NULL), latest_plan_(NULL), controller_plan_(NULL),
56  runPlanner_(false), setup_(false), p_freq_change_(false), c_freq_change_(false), new_global_plan_(false) {
57 
58  as_ = new MoveBaseActionServer(ros::NodeHandle(), "move_base", boost::bind(&MoveBase::executeCb, this, _1), false);
59 
60  ros::NodeHandle private_nh("~");
61  ros::NodeHandle nh;
62 
64 
65  //get some parameters that will be global to the move base node
66  std::string global_planner, local_planner;
67  private_nh.param("base_global_planner", global_planner, std::string("navfn/NavfnROS"));
68  private_nh.param("base_local_planner", local_planner, std::string("base_local_planner/TrajectoryPlannerROS"));
69  private_nh.param("global_costmap/robot_base_frame", robot_base_frame_, std::string("base_link"));
70  private_nh.param("global_costmap/global_frame", global_frame_, std::string("/map"));
71  private_nh.param("planner_frequency", planner_frequency_, 0.0);
72  private_nh.param("controller_frequency", controller_frequency_, 20.0);
73  private_nh.param("planner_patience", planner_patience_, 5.0);
74  private_nh.param("controller_patience", controller_patience_, 15.0);
75  private_nh.param("max_planning_retries", max_planning_retries_, -1); // disabled by default
76 
77  private_nh.param("oscillation_timeout", oscillation_timeout_, 0.0);
78  private_nh.param("oscillation_distance", oscillation_distance_, 0.5);
79 
80  //set up plan triple buffer
81  planner_plan_ = new std::vector<geometry_msgs::PoseStamped>();
82  latest_plan_ = new std::vector<geometry_msgs::PoseStamped>();
83  controller_plan_ = new std::vector<geometry_msgs::PoseStamped>();
84 
85  //set up the planner's thread
86  planner_thread_ = new boost::thread(boost::bind(&MoveBase::planThread, this));
87 
88  //for commanding the base
89  vel_pub_ = nh.advertise<geometry_msgs::Twist>("cmd_vel", 1);
90  current_goal_pub_ = private_nh.advertise<geometry_msgs::PoseStamped>("current_goal", 0 );
91 
92  ros::NodeHandle action_nh("move_base");
93  action_goal_pub_ = action_nh.advertise<move_base_msgs::MoveBaseActionGoal>("goal", 1);
94 
95  //we'll provide a mechanism for some people to send goals as PoseStamped messages over a topic
96  //they won't get any useful information back about its status, but this is useful for tools
97  //like nav_view and rviz
98  ros::NodeHandle simple_nh("move_base_simple");
99  goal_sub_ = simple_nh.subscribe<geometry_msgs::PoseStamped>("goal", 1, boost::bind(&MoveBase::goalCB, this, _1));
100 
101  //we'll assume the radius of the robot to be consistent with what's specified for the costmaps
102  private_nh.param("local_costmap/inscribed_radius", inscribed_radius_, 0.325);
103  private_nh.param("local_costmap/circumscribed_radius", circumscribed_radius_, 0.46);
104  private_nh.param("clearing_radius", clearing_radius_, circumscribed_radius_);
105  private_nh.param("conservative_reset_dist", conservative_reset_dist_, 3.0);
106 
107  private_nh.param("shutdown_costmaps", shutdown_costmaps_, false);
108  private_nh.param("clearing_rotation_allowed", clearing_rotation_allowed_, true);
109  private_nh.param("recovery_behavior_enabled", recovery_behavior_enabled_, true);
110 
111  //create the ros wrapper for the planner's costmap... and initializer a pointer we'll use with the underlying map
112  planner_costmap_ros_ = new costmap_2d::Costmap2DROS("global_costmap", tf_);
114 
115  //initialize the global planner
116  try {
117  planner_ = bgp_loader_.createInstance(global_planner);
118  planner_->initialize(bgp_loader_.getName(global_planner), planner_costmap_ros_);
119  } catch (const pluginlib::PluginlibException& ex) {
120  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());
121  exit(1);
122  }
123 
124  //create the ros wrapper for the controller's costmap... and initializer a pointer we'll use with the underlying map
125  controller_costmap_ros_ = new costmap_2d::Costmap2DROS("local_costmap", tf_);
127 
128  //create a local planner
129  try {
130  tc_ = blp_loader_.createInstance(local_planner);
131  ROS_INFO("Created local_planner %s", local_planner.c_str());
132  tc_->initialize(blp_loader_.getName(local_planner), &tf_, controller_costmap_ros_);
133  } catch (const pluginlib::PluginlibException& ex) {
134  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());
135  exit(1);
136  }
137 
138  // Start actively updating costmaps based on sensor data
141 
142  //advertise a service for getting a plan
143  make_plan_srv_ = private_nh.advertiseService("make_plan", &MoveBase::planService, this);
144 
145  //advertise a service for clearing the costmaps
146  clear_costmaps_srv_ = private_nh.advertiseService("clear_costmaps", &MoveBase::clearCostmapsService, this);
147 
148  //if we shutdown our costmaps when we're deactivated... we'll do that now
149  if(shutdown_costmaps_){
150  ROS_DEBUG_NAMED("move_base","Stopping costmaps initially");
153  }
154 
155  //load any user specified recovery behaviors, and if that fails load the defaults
156  if(!loadRecoveryBehaviors(private_nh)){
158  }
159 
160  //initially, we'll need to make a plan
161  state_ = PLANNING;
162 
163  //we'll start executing recovery behaviors at the beginning of our list
164  recovery_index_ = 0;
165 
166  //we're all set up now so we can start the action server
167  as_->start();
168 
169  dsrv_ = new dynamic_reconfigure::Server<move_base::MoveBaseConfig>(ros::NodeHandle("~"));
170  dynamic_reconfigure::Server<move_base::MoveBaseConfig>::CallbackType cb = boost::bind(&MoveBase::reconfigureCB, this, _1, _2);
171  dsrv_->setCallback(cb);
172  }
173 
174  void MoveBase::reconfigureCB(move_base::MoveBaseConfig &config, uint32_t level){
175  boost::recursive_mutex::scoped_lock l(configuration_mutex_);
176 
177  //The first time we're called, we just want to make sure we have the
178  //original configuration
179  if(!setup_)
180  {
181  last_config_ = config;
182  default_config_ = config;
183  setup_ = true;
184  return;
185  }
186 
187  if(config.restore_defaults) {
188  config = default_config_;
189  //if someone sets restore defaults on the parameter server, prevent looping
190  config.restore_defaults = false;
191  }
192 
193  if(planner_frequency_ != config.planner_frequency)
194  {
195  planner_frequency_ = config.planner_frequency;
196  p_freq_change_ = true;
197  }
198 
199  if(controller_frequency_ != config.controller_frequency)
200  {
201  controller_frequency_ = config.controller_frequency;
202  c_freq_change_ = true;
203  }
204 
205  planner_patience_ = config.planner_patience;
206  controller_patience_ = config.controller_patience;
207  max_planning_retries_ = config.max_planning_retries;
208  conservative_reset_dist_ = config.conservative_reset_dist;
209 
210  recovery_behavior_enabled_ = config.recovery_behavior_enabled;
211  clearing_rotation_allowed_ = config.clearing_rotation_allowed;
212  shutdown_costmaps_ = config.shutdown_costmaps;
213 
214  oscillation_timeout_ = config.oscillation_timeout;
215  oscillation_distance_ = config.oscillation_distance;
216  if(config.base_global_planner != last_config_.base_global_planner) {
218  //initialize the global planner
219  ROS_INFO("Loading global planner %s", config.base_global_planner.c_str());
220  try {
221  planner_ = bgp_loader_.createInstance(config.base_global_planner);
222 
223  // wait for the current planner to finish planning
224  boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
225 
226  // Clean up before initializing the new planner
227  planner_plan_->clear();
228  latest_plan_->clear();
229  controller_plan_->clear();
230  resetState();
231  planner_->initialize(bgp_loader_.getName(config.base_global_planner), planner_costmap_ros_);
232 
233  lock.unlock();
234  } catch (const pluginlib::PluginlibException& ex) {
235  ROS_FATAL("Failed to create the %s planner, are you sure it is properly registered and that the \
236  containing library is built? Exception: %s", config.base_global_planner.c_str(), ex.what());
237  planner_ = old_planner;
238  config.base_global_planner = last_config_.base_global_planner;
239  }
240  }
241 
242  if(config.base_local_planner != last_config_.base_local_planner){
244  //create a local planner
245  try {
246  tc_ = blp_loader_.createInstance(config.base_local_planner);
247  // Clean up before initializing the new planner
248  planner_plan_->clear();
249  latest_plan_->clear();
250  controller_plan_->clear();
251  resetState();
252  tc_->initialize(blp_loader_.getName(config.base_local_planner), &tf_, controller_costmap_ros_);
253  } catch (const pluginlib::PluginlibException& ex) {
254  ROS_FATAL("Failed to create the %s planner, are you sure it is properly registered and that the \
255  containing library is built? Exception: %s", config.base_local_planner.c_str(), ex.what());
256  tc_ = old_planner;
257  config.base_local_planner = last_config_.base_local_planner;
258  }
259  }
260 
261  last_config_ = config;
262  }
263 
264  void MoveBase::goalCB(const geometry_msgs::PoseStamped::ConstPtr& goal){
265  ROS_DEBUG_NAMED("move_base","In ROS goal callback, wrapping the PoseStamped in the action message and re-sending to the server.");
266  move_base_msgs::MoveBaseActionGoal action_goal;
267  action_goal.header.stamp = ros::Time::now();
268  action_goal.goal.target_pose = *goal;
269 
270  action_goal_pub_.publish(action_goal);
271  }
272 
273  void MoveBase::clearCostmapWindows(double size_x, double size_y){
274  tf::Stamped<tf::Pose> global_pose;
275 
276  //clear the planner's costmap
277  getRobotPose(global_pose, planner_costmap_ros_);
278 
279  std::vector<geometry_msgs::Point> clear_poly;
280  double x = global_pose.getOrigin().x();
281  double y = global_pose.getOrigin().y();
282  geometry_msgs::Point pt;
283 
284  pt.x = x - size_x / 2;
285  pt.y = y - size_y / 2;
286  clear_poly.push_back(pt);
287 
288  pt.x = x + size_x / 2;
289  pt.y = y - size_y / 2;
290  clear_poly.push_back(pt);
291 
292  pt.x = x + size_x / 2;
293  pt.y = y + size_y / 2;
294  clear_poly.push_back(pt);
295 
296  pt.x = x - size_x / 2;
297  pt.y = y + size_y / 2;
298  clear_poly.push_back(pt);
299 
301 
302  //clear the controller's costmap
304 
305  clear_poly.clear();
306  x = global_pose.getOrigin().x();
307  y = global_pose.getOrigin().y();
308 
309  pt.x = x - size_x / 2;
310  pt.y = y - size_y / 2;
311  clear_poly.push_back(pt);
312 
313  pt.x = x + size_x / 2;
314  pt.y = y - size_y / 2;
315  clear_poly.push_back(pt);
316 
317  pt.x = x + size_x / 2;
318  pt.y = y + size_y / 2;
319  clear_poly.push_back(pt);
320 
321  pt.x = x - size_x / 2;
322  pt.y = y + size_y / 2;
323  clear_poly.push_back(pt);
324 
326  }
327 
328  bool MoveBase::clearCostmapsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp){
329  //clear the costmaps
330  boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock_controller(*(controller_costmap_ros_->getCostmap()->getMutex()));
332 
333  boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock_planner(*(planner_costmap_ros_->getCostmap()->getMutex()));
335  return true;
336  }
337 
338 
339  bool MoveBase::planService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp){
340  if(as_->isActive()){
341  ROS_ERROR("move_base must be in an inactive state to make a plan for an external user");
342  return false;
343  }
344  //make sure we have a costmap for our planner
345  if(planner_costmap_ros_ == NULL){
346  ROS_ERROR("move_base cannot make a plan for you because it doesn't have a costmap");
347  return false;
348  }
349 
350  geometry_msgs::PoseStamped start;
351  //if the user does not specify a start pose, identified by an empty frame id, then use the robot's pose
352  if(req.start.header.frame_id.empty())
353  {
354  tf::Stamped<tf::Pose> global_pose;
355  if(!planner_costmap_ros_->getRobotPose(global_pose)){
356  ROS_ERROR("move_base cannot make a plan for you because it could not get the start pose of the robot");
357  return false;
358  }
359  tf::poseStampedTFToMsg(global_pose, start);
360  }
361  else
362  {
363  start = req.start;
364  }
365 
366  //update the copy of the costmap the planner uses
368 
369  //first try to make a plan to the exact desired goal
370  std::vector<geometry_msgs::PoseStamped> global_plan;
371  if(!planner_->makePlan(start, req.goal, global_plan) || global_plan.empty()){
372  ROS_DEBUG_NAMED("move_base","Failed to find a plan to exact goal of (%.2f, %.2f), searching for a feasible goal within tolerance",
373  req.goal.pose.position.x, req.goal.pose.position.y);
374 
375  //search outwards for a feasible goal within the specified tolerance
376  geometry_msgs::PoseStamped p;
377  p = req.goal;
378  bool found_legal = false;
379  float resolution = planner_costmap_ros_->getCostmap()->getResolution();
380  float search_increment = resolution*3.0;
381  if(req.tolerance > 0.0 && req.tolerance < search_increment) search_increment = req.tolerance;
382  for(float max_offset = search_increment; max_offset <= req.tolerance && !found_legal; max_offset += search_increment) {
383  for(float y_offset = 0; y_offset <= max_offset && !found_legal; y_offset += search_increment) {
384  for(float x_offset = 0; x_offset <= max_offset && !found_legal; x_offset += search_increment) {
385 
386  //don't search again inside the current outer layer
387  if(x_offset < max_offset-1e-9 && y_offset < max_offset-1e-9) continue;
388 
389  //search to both sides of the desired goal
390  for(float y_mult = -1.0; y_mult <= 1.0 + 1e-9 && !found_legal; y_mult += 2.0) {
391 
392  //if one of the offsets is 0, -1*0 is still 0 (so get rid of one of the two)
393  if(y_offset < 1e-9 && y_mult < -1.0 + 1e-9) continue;
394 
395  for(float x_mult = -1.0; x_mult <= 1.0 + 1e-9 && !found_legal; x_mult += 2.0) {
396  if(x_offset < 1e-9 && x_mult < -1.0 + 1e-9) continue;
397 
398  p.pose.position.y = req.goal.pose.position.y + y_offset * y_mult;
399  p.pose.position.x = req.goal.pose.position.x + x_offset * x_mult;
400 
401  if(planner_->makePlan(start, p, global_plan)){
402  if(!global_plan.empty()){
403 
404  //adding the (unreachable) original goal to the end of the global plan, in case the local planner can get you there
405  //(the reachable goal should have been added by the global planner)
406  global_plan.push_back(req.goal);
407 
408  found_legal = true;
409  ROS_DEBUG_NAMED("move_base", "Found a plan to point (%.2f, %.2f)", p.pose.position.x, p.pose.position.y);
410  break;
411  }
412  }
413  else{
414  ROS_DEBUG_NAMED("move_base","Failed to find a plan to point (%.2f, %.2f)", p.pose.position.x, p.pose.position.y);
415  }
416  }
417  }
418  }
419  }
420  }
421  }
422 
423  //copy the plan into a message to send out
424  resp.plan.poses.resize(global_plan.size());
425  for(unsigned int i = 0; i < global_plan.size(); ++i){
426  resp.plan.poses[i] = global_plan[i];
427  }
428 
429  return true;
430  }
431 
433  recovery_behaviors_.clear();
434 
435  delete dsrv_;
436 
437  if(as_ != NULL)
438  delete as_;
439 
440  if(planner_costmap_ros_ != NULL)
441  delete planner_costmap_ros_;
442 
443  if(controller_costmap_ros_ != NULL)
445 
446  planner_thread_->interrupt();
447  planner_thread_->join();
448 
449  delete planner_thread_;
450 
451  delete planner_plan_;
452  delete latest_plan_;
453  delete controller_plan_;
454 
455  planner_.reset();
456  tc_.reset();
457  }
458 
459  bool MoveBase::makePlan(const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan){
460  boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(planner_costmap_ros_->getCostmap()->getMutex()));
461 
462  //make sure to set the plan to be empty initially
463  plan.clear();
464 
465  //since this gets called on handle activate
466  if(planner_costmap_ros_ == NULL) {
467  ROS_ERROR("Planner costmap ROS is NULL, unable to create global plan");
468  return false;
469  }
470 
471  //get the starting pose of the robot
472  tf::Stamped<tf::Pose> global_pose;
473  if(!getRobotPose(global_pose, planner_costmap_ros_)) {
474  ROS_WARN("Unable to get starting pose of robot, unable to create global plan");
475  return false;
476  }
477 
478  geometry_msgs::PoseStamped start;
479  tf::poseStampedTFToMsg(global_pose, start);
480 
481  //if the planner fails or returns a zero length plan, planning failed
482  if(!planner_->makePlan(start, goal, plan) || plan.empty()){
483  ROS_DEBUG_NAMED("move_base","Failed to find a plan to point (%.2f, %.2f)", goal.pose.position.x, goal.pose.position.y);
484  return false;
485  }
486 
487  return true;
488  }
489 
491  geometry_msgs::Twist cmd_vel;
492  cmd_vel.linear.x = 0.0;
493  cmd_vel.linear.y = 0.0;
494  cmd_vel.angular.z = 0.0;
495  vel_pub_.publish(cmd_vel);
496  }
497 
498  bool MoveBase::isQuaternionValid(const geometry_msgs::Quaternion& q){
499  //first we need to check if the quaternion has nan's or infs
500  if(!std::isfinite(q.x) || !std::isfinite(q.y) || !std::isfinite(q.z) || !std::isfinite(q.w)){
501  ROS_ERROR("Quaternion has nans or infs... discarding as a navigation goal");
502  return false;
503  }
504 
505  tf::Quaternion tf_q(q.x, q.y, q.z, q.w);
506 
507  //next, we need to check if the length of the quaternion is close to zero
508  if(tf_q.length2() < 1e-6){
509  ROS_ERROR("Quaternion has length close to zero... discarding as navigation goal");
510  return false;
511  }
512 
513  //next, we'll normalize the quaternion and check that it transforms the vertical vector correctly
514  tf_q.normalize();
515 
516  tf::Vector3 up(0, 0, 1);
517 
518  double dot = up.dot(up.rotate(tf_q.getAxis(), tf_q.getAngle()));
519 
520  if(fabs(dot - 1) > 1e-3){
521  ROS_ERROR("Quaternion is invalid... for navigation the z-axis of the quaternion must be close to vertical.");
522  return false;
523  }
524 
525  return true;
526  }
527 
528  geometry_msgs::PoseStamped MoveBase::goalToGlobalFrame(const geometry_msgs::PoseStamped& goal_pose_msg){
529  std::string global_frame = planner_costmap_ros_->getGlobalFrameID();
530  tf::Stamped<tf::Pose> goal_pose, global_pose;
531  poseStampedMsgToTF(goal_pose_msg, goal_pose);
532 
533  //just get the latest available transform... for accuracy they should send
534  //goals in the frame of the planner
535  goal_pose.stamp_ = ros::Time();
536 
537  try{
538  tf_.transformPose(global_frame, goal_pose, global_pose);
539  }
540  catch(tf::TransformException& ex){
541  ROS_WARN("Failed to transform the goal pose from %s into the %s frame: %s",
542  goal_pose.frame_id_.c_str(), global_frame.c_str(), ex.what());
543  return goal_pose_msg;
544  }
545 
546  geometry_msgs::PoseStamped global_pose_msg;
547  tf::poseStampedTFToMsg(global_pose, global_pose_msg);
548  return global_pose_msg;
549  }
550 
552  {
553  // we have slept long enough for rate
555  }
556 
558  ROS_DEBUG_NAMED("move_base_plan_thread","Starting planner thread...");
559  ros::NodeHandle n;
560  ros::Timer timer;
561  bool wait_for_wake = false;
562  boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
563  while(n.ok()){
564  //check if we should run the planner (the mutex is locked)
565  while(wait_for_wake || !runPlanner_){
566  //if we should not be running the planner then suspend this thread
567  ROS_DEBUG_NAMED("move_base_plan_thread","Planner thread is suspending");
568  planner_cond_.wait(lock);
569  wait_for_wake = false;
570  }
571  ros::Time start_time = ros::Time::now();
572 
573  //time to plan! get a copy of the goal and unlock the mutex
574  geometry_msgs::PoseStamped temp_goal = planner_goal_;
575  lock.unlock();
576  ROS_DEBUG_NAMED("move_base_plan_thread","Planning...");
577 
578  //run planner
579  planner_plan_->clear();
580  bool gotPlan = n.ok() && makePlan(temp_goal, *planner_plan_);
581 
582  if(gotPlan){
583  ROS_DEBUG_NAMED("move_base_plan_thread","Got Plan with %zu points!", planner_plan_->size());
584  //pointer swap the plans under mutex (the controller will pull from latest_plan_)
585  std::vector<geometry_msgs::PoseStamped>* temp_plan = planner_plan_;
586 
587  lock.lock();
589  latest_plan_ = temp_plan;
591  planning_retries_ = 0;
592  new_global_plan_ = true;
593 
594  ROS_DEBUG_NAMED("move_base_plan_thread","Generated a plan from the base_global_planner");
595 
596  //make sure we only start the controller if we still haven't reached the goal
597  if(runPlanner_)
599  if(planner_frequency_ <= 0)
600  runPlanner_ = false;
601  lock.unlock();
602  }
603  //if we didn't get a plan and we are in the planning state (the robot isn't moving)
604  else if(state_==PLANNING){
605  ROS_DEBUG_NAMED("move_base_plan_thread","No Plan...");
607 
608  //check if we've tried to make a plan for over our time limit or our maximum number of retries
609  //issue #496: we stop planning when one of the conditions is true, but if max_planning_retries_
610  //is negative (the default), it is just ignored and we have the same behavior as ever
611  lock.lock();
613  if(runPlanner_ &&
614  (ros::Time::now() > attempt_end || planning_retries_ > uint32_t(max_planning_retries_))){
615  //we'll move into our obstacle clearing mode
616  state_ = CLEARING;
617  runPlanner_ = false; // proper solution for issue #523
620  }
621 
622  lock.unlock();
623  }
624 
625  //take the mutex for the next iteration
626  lock.lock();
627 
628  //setup sleep interface if needed
629  if(planner_frequency_ > 0){
630  ros::Duration sleep_time = (start_time + ros::Duration(1.0/planner_frequency_)) - ros::Time::now();
631  if (sleep_time > ros::Duration(0.0)){
632  wait_for_wake = true;
633  timer = n.createTimer(sleep_time, &MoveBase::wakePlanner, this);
634  }
635  }
636  }
637  }
638 
639  void MoveBase::executeCb(const move_base_msgs::MoveBaseGoalConstPtr& move_base_goal)
640  {
641  if(!isQuaternionValid(move_base_goal->target_pose.pose.orientation)){
642  as_->setAborted(move_base_msgs::MoveBaseResult(), "Aborting on goal because it was sent with an invalid quaternion");
643  return;
644  }
645 
646  geometry_msgs::PoseStamped goal = goalToGlobalFrame(move_base_goal->target_pose);
647 
648  //we have a goal so start the planner
649  boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
650  planner_goal_ = goal;
651  runPlanner_ = true;
653  lock.unlock();
654 
656  std::vector<geometry_msgs::PoseStamped> global_plan;
657 
659  if(shutdown_costmaps_){
660  ROS_DEBUG_NAMED("move_base","Starting up costmaps that were shut down previously");
663  }
664 
665  //we want to make sure that we reset the last time we had a valid plan and control
669  planning_retries_ = 0;
670 
671  ros::NodeHandle n;
672  while(n.ok())
673  {
674  if(c_freq_change_)
675  {
676  ROS_INFO("Setting controller frequency to %.2f", controller_frequency_);
678  c_freq_change_ = false;
679  }
680 
681  if(as_->isPreemptRequested()){
682  if(as_->isNewGoalAvailable()){
683  //if we're active and a new goal is available, we'll accept it, but we won't shut anything down
684  move_base_msgs::MoveBaseGoal new_goal = *as_->acceptNewGoal();
685 
686  if(!isQuaternionValid(new_goal.target_pose.pose.orientation)){
687  as_->setAborted(move_base_msgs::MoveBaseResult(), "Aborting on goal because it was sent with an invalid quaternion");
688  return;
689  }
690 
691  goal = goalToGlobalFrame(new_goal.target_pose);
692 
693  //we'll make sure that we reset our state for the next execution cycle
694  recovery_index_ = 0;
695  state_ = PLANNING;
696 
697  //we have a new goal so make sure the planner is awake
698  lock.lock();
699  planner_goal_ = goal;
700  runPlanner_ = true;
702  lock.unlock();
703 
704  //publish the goal point to the visualizer
705  ROS_DEBUG_NAMED("move_base","move_base has received a goal of x: %.2f, y: %.2f", goal.pose.position.x, goal.pose.position.y);
707 
708  //make sure to reset our timeouts and counters
712  planning_retries_ = 0;
713  }
714  else {
715  //if we've been preempted explicitly we need to shut things down
716  resetState();
717 
718  //notify the ActionServer that we've successfully preempted
719  ROS_DEBUG_NAMED("move_base","Move base preempting the current goal");
720  as_->setPreempted();
721 
722  //we'll actually return from execute after preempting
723  return;
724  }
725  }
726 
727  //we also want to check if we've changed global frames because we need to transform our goal pose
728  if(goal.header.frame_id != planner_costmap_ros_->getGlobalFrameID()){
729  goal = goalToGlobalFrame(goal);
730 
731  //we want to go back to the planning state for the next execution cycle
732  recovery_index_ = 0;
733  state_ = PLANNING;
734 
735  //we have a new goal so make sure the planner is awake
736  lock.lock();
737  planner_goal_ = goal;
738  runPlanner_ = true;
740  lock.unlock();
741 
742  //publish the goal point to the visualizer
743  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);
745 
746  //make sure to reset our timeouts and counters
750  planning_retries_ = 0;
751  }
752 
753  //for timing that gives real time even in simulation
755 
756  //the real work on pursuing a goal is done here
757  bool done = executeCycle(goal, global_plan);
758 
759  //if we're done, then we'll return from execute
760  if(done)
761  return;
762 
763  //check if execution of the goal has completed in some way
764 
765  ros::WallDuration t_diff = ros::WallTime::now() - start;
766  ROS_DEBUG_NAMED("move_base","Full control cycle time: %.9f\n", t_diff.toSec());
767 
768  r.sleep();
769  //make sure to sleep for the remainder of our cycle time
771  ROS_WARN("Control loop missed its desired rate of %.4fHz... the loop actually took %.4f seconds", controller_frequency_, r.cycleTime().toSec());
772  }
773 
774  //wake up the planner thread so that it can exit cleanly
775  lock.lock();
776  runPlanner_ = true;
778  lock.unlock();
779 
780  //if the node is killed then we'll abort and return
781  as_->setAborted(move_base_msgs::MoveBaseResult(), "Aborting on the goal because the node has been killed");
782  return;
783  }
784 
785  double MoveBase::distance(const geometry_msgs::PoseStamped& p1, const geometry_msgs::PoseStamped& p2)
786  {
787  return hypot(p1.pose.position.x - p2.pose.position.x, p1.pose.position.y - p2.pose.position.y);
788  }
789 
790  bool MoveBase::executeCycle(geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& global_plan){
791  boost::recursive_mutex::scoped_lock ecl(configuration_mutex_);
792  //we need to be able to publish velocity commands
793  geometry_msgs::Twist cmd_vel;
794 
795  //update feedback to correspond to our curent position
796  tf::Stamped<tf::Pose> global_pose;
797  getRobotPose(global_pose, planner_costmap_ros_);
798  geometry_msgs::PoseStamped current_position;
799  tf::poseStampedTFToMsg(global_pose, current_position);
800 
801  //push the feedback out
802  move_base_msgs::MoveBaseFeedback feedback;
803  feedback.base_position = current_position;
804  as_->publishFeedback(feedback);
805 
806  //check to see if we've moved far enough to reset our oscillation timeout
807  if(distance(current_position, oscillation_pose_) >= oscillation_distance_)
808  {
810  oscillation_pose_ = current_position;
811 
812  //if our last recovery was caused by oscillation, we want to reset the recovery index
814  recovery_index_ = 0;
815  }
816 
817  //check that the observation buffers for the costmap are current, we don't want to drive blind
819  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());
821  return false;
822  }
823 
824  //if we have a new plan then grab it and give it to the controller
825  if(new_global_plan_){
826  //make sure to set the new plan flag to false
827  new_global_plan_ = false;
828 
829  ROS_DEBUG_NAMED("move_base","Got a new plan...swap pointers");
830 
831  //do a pointer swap under mutex
832  std::vector<geometry_msgs::PoseStamped>* temp_plan = controller_plan_;
833 
834  boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
836  latest_plan_ = temp_plan;
837  lock.unlock();
838  ROS_DEBUG_NAMED("move_base","pointers swapped!");
839 
840  if(!tc_->setPlan(*controller_plan_)){
841  //ABORT and SHUTDOWN COSTMAPS
842  ROS_ERROR("Failed to pass global plan to the controller, aborting.");
843  resetState();
844 
845  //disable the planner thread
846  lock.lock();
847  runPlanner_ = false;
848  lock.unlock();
849 
850  as_->setAborted(move_base_msgs::MoveBaseResult(), "Failed to pass global plan to the controller.");
851  return true;
852  }
853 
854  //make sure to reset recovery_index_ since we were able to find a valid plan
856  recovery_index_ = 0;
857  }
858 
859  //the move_base state machine, handles the control logic for navigation
860  switch(state_){
861  //if we are in a planning state, then we'll attempt to make a plan
862  case PLANNING:
863  {
864  boost::recursive_mutex::scoped_lock lock(planner_mutex_);
865  runPlanner_ = true;
867  }
868  ROS_DEBUG_NAMED("move_base","Waiting for plan, in the planning state.");
869  break;
870 
871  //if we're controlling, we'll attempt to find valid velocity commands
872  case CONTROLLING:
873  ROS_DEBUG_NAMED("move_base","In controlling state.");
874 
875  //check to see if we've reached our goal
876  if(tc_->isGoalReached()){
877  ROS_DEBUG_NAMED("move_base","Goal reached!");
878  resetState();
879 
880  //disable the planner thread
881  boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
882  runPlanner_ = false;
883  lock.unlock();
884 
885  as_->setSucceeded(move_base_msgs::MoveBaseResult(), "Goal reached.");
886  return true;
887  }
888 
889  //check for an oscillation condition
890  if(oscillation_timeout_ > 0.0 &&
892  {
894  state_ = CLEARING;
896  }
897 
898  {
899  boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(controller_costmap_ros_->getCostmap()->getMutex()));
900 
901  if(tc_->computeVelocityCommands(cmd_vel)){
902  ROS_DEBUG_NAMED( "move_base", "Got a valid command from the local planner: %.3lf, %.3lf, %.3lf",
903  cmd_vel.linear.x, cmd_vel.linear.y, cmd_vel.angular.z );
905  //make sure that we send the velocity command to the base
906  vel_pub_.publish(cmd_vel);
908  recovery_index_ = 0;
909  }
910  else {
911  ROS_DEBUG_NAMED("move_base", "The local planner could not find a valid plan.");
913 
914  //check if we've tried to find a valid control for longer than our time limit
915  if(ros::Time::now() > attempt_end){
916  //we'll move into our obstacle clearing mode
918  state_ = CLEARING;
920  }
921  else{
922  //otherwise, if we can't find a valid control, we'll go back to planning
924  planning_retries_ = 0;
925  state_ = PLANNING;
927 
928  //enable the planner thread in case it isn't running on a clock
929  boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
930  runPlanner_ = true;
932  lock.unlock();
933  }
934  }
935  }
936 
937  break;
938 
939  //we'll try to clear out space with any user-provided recovery behaviors
940  case CLEARING:
941  ROS_DEBUG_NAMED("move_base","In clearing/recovery state");
942  //we'll invoke whatever recovery behavior we're currently on if they're enabled
944  ROS_DEBUG_NAMED("move_base_recovery","Executing behavior %u of %zu", recovery_index_, recovery_behaviors_.size());
945  recovery_behaviors_[recovery_index_]->runBehavior();
946 
947  //we at least want to give the robot some time to stop oscillating after executing the behavior
949 
950  //we'll check if the recovery behavior actually worked
951  ROS_DEBUG_NAMED("move_base_recovery","Going back to planning state");
953  planning_retries_ = 0;
954  state_ = PLANNING;
955 
956  //update the index of the next recovery behavior that we'll try
957  recovery_index_++;
958  }
959  else{
960  ROS_DEBUG_NAMED("move_base_recovery","All recovery behaviors have failed, locking the planner and disabling it.");
961  //disable the planner thread
962  boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
963  runPlanner_ = false;
964  lock.unlock();
965 
966  ROS_DEBUG_NAMED("move_base_recovery","Something should abort after this.");
967 
969  ROS_ERROR("Aborting because a valid control could not be found. Even after executing all recovery behaviors");
970  as_->setAborted(move_base_msgs::MoveBaseResult(), "Failed to find a valid control. Even after executing recovery behaviors.");
971  }
972  else if(recovery_trigger_ == PLANNING_R){
973  ROS_ERROR("Aborting because a valid plan could not be found. Even after executing all recovery behaviors");
974  as_->setAborted(move_base_msgs::MoveBaseResult(), "Failed to find a valid plan. Even after executing recovery behaviors.");
975  }
976  else if(recovery_trigger_ == OSCILLATION_R){
977  ROS_ERROR("Aborting because the robot appears to be oscillating over and over. Even after executing all recovery behaviors");
978  as_->setAborted(move_base_msgs::MoveBaseResult(), "Robot is oscillating. Even after executing recovery behaviors.");
979  }
980  resetState();
981  return true;
982  }
983  break;
984  default:
985  ROS_ERROR("This case should never be reached, something is wrong, aborting");
986  resetState();
987  //disable the planner thread
988  boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
989  runPlanner_ = false;
990  lock.unlock();
991  as_->setAborted(move_base_msgs::MoveBaseResult(), "Reached a case that should not be hit in move_base. This is a bug, please report it.");
992  return true;
993  }
994 
995  //we aren't done yet
996  return false;
997  }
998 
1000  XmlRpc::XmlRpcValue behavior_list;
1001  if(node.getParam("recovery_behaviors", behavior_list)){
1002  if(behavior_list.getType() == XmlRpc::XmlRpcValue::TypeArray){
1003  for(int i = 0; i < behavior_list.size(); ++i){
1004  if(behavior_list[i].getType() == XmlRpc::XmlRpcValue::TypeStruct){
1005  if(behavior_list[i].hasMember("name") && behavior_list[i].hasMember("type")){
1006  //check for recovery behaviors with the same name
1007  for(int j = i + 1; j < behavior_list.size(); j++){
1008  if(behavior_list[j].getType() == XmlRpc::XmlRpcValue::TypeStruct){
1009  if(behavior_list[j].hasMember("name") && behavior_list[j].hasMember("type")){
1010  std::string name_i = behavior_list[i]["name"];
1011  std::string name_j = behavior_list[j]["name"];
1012  if(name_i == name_j){
1013  ROS_ERROR("A recovery behavior with the name %s already exists, this is not allowed. Using the default recovery behaviors instead.",
1014  name_i.c_str());
1015  return false;
1016  }
1017  }
1018  }
1019  }
1020  }
1021  else{
1022  ROS_ERROR("Recovery behaviors must have a name and a type and this does not. Using the default recovery behaviors instead.");
1023  return false;
1024  }
1025  }
1026  else{
1027  ROS_ERROR("Recovery behaviors must be specified as maps, but they are XmlRpcType %d. We'll use the default recovery behaviors instead.",
1028  behavior_list[i].getType());
1029  return false;
1030  }
1031  }
1032 
1033  //if we've made it to this point, we know that the list is legal so we'll create all the recovery behaviors
1034  for(int i = 0; i < behavior_list.size(); ++i){
1035  try{
1036  //check if a non fully qualified name has potentially been passed in
1037  if(!recovery_loader_.isClassAvailable(behavior_list[i]["type"])){
1038  std::vector<std::string> classes = recovery_loader_.getDeclaredClasses();
1039  for(unsigned int i = 0; i < classes.size(); ++i){
1040  if(behavior_list[i]["type"] == recovery_loader_.getName(classes[i])){
1041  //if we've found a match... we'll get the fully qualified name and break out of the loop
1042  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.",
1043  std::string(behavior_list[i]["type"]).c_str(), classes[i].c_str());
1044  behavior_list[i]["type"] = classes[i];
1045  break;
1046  }
1047  }
1048  }
1049 
1050  boost::shared_ptr<nav_core::RecoveryBehavior> behavior(recovery_loader_.createInstance(behavior_list[i]["type"]));
1051 
1052  //shouldn't be possible, but it won't hurt to check
1053  if(behavior.get() == NULL){
1054  ROS_ERROR("The ClassLoader returned a null pointer without throwing an exception. This should not happen");
1055  return false;
1056  }
1057 
1058  //initialize the recovery behavior with its name
1059  behavior->initialize(behavior_list[i]["name"], &tf_, planner_costmap_ros_, controller_costmap_ros_);
1060  recovery_behaviors_.push_back(behavior);
1061  }
1062  catch(pluginlib::PluginlibException& ex){
1063  ROS_ERROR("Failed to load a plugin. Using default recovery behaviors. Error: %s", ex.what());
1064  return false;
1065  }
1066  }
1067  }
1068  else{
1069  ROS_ERROR("The recovery behavior specification must be a list, but is of XmlRpcType %d. We'll use the default recovery behaviors instead.",
1070  behavior_list.getType());
1071  return false;
1072  }
1073  }
1074  else{
1075  //if no recovery_behaviors are specified, we'll just load the defaults
1076  return false;
1077  }
1078 
1079  //if we've made it here... we've constructed a recovery behavior list successfully
1080  return true;
1081  }
1082 
1083  //we'll load our default recovery behaviors here
1085  recovery_behaviors_.clear();
1086  try{
1087  //we need to set some parameters based on what's been passed in to us to maintain backwards compatibility
1088  ros::NodeHandle n("~");
1089  n.setParam("conservative_reset/reset_distance", conservative_reset_dist_);
1090  n.setParam("aggressive_reset/reset_distance", circumscribed_radius_ * 4);
1091 
1092  //first, we'll load a recovery behavior to clear the costmap
1093  boost::shared_ptr<nav_core::RecoveryBehavior> cons_clear(recovery_loader_.createInstance("clear_costmap_recovery/ClearCostmapRecovery"));
1094  cons_clear->initialize("conservative_reset", &tf_, planner_costmap_ros_, controller_costmap_ros_);
1095  recovery_behaviors_.push_back(cons_clear);
1096 
1097  //next, we'll load a recovery behavior to rotate in place
1098  boost::shared_ptr<nav_core::RecoveryBehavior> rotate(recovery_loader_.createInstance("rotate_recovery/RotateRecovery"));
1100  rotate->initialize("rotate_recovery", &tf_, planner_costmap_ros_, controller_costmap_ros_);
1101  recovery_behaviors_.push_back(rotate);
1102  }
1103 
1104  //next, we'll load a recovery behavior that will do an aggressive reset of the costmap
1105  boost::shared_ptr<nav_core::RecoveryBehavior> ags_clear(recovery_loader_.createInstance("clear_costmap_recovery/ClearCostmapRecovery"));
1106  ags_clear->initialize("aggressive_reset", &tf_, planner_costmap_ros_, controller_costmap_ros_);
1107  recovery_behaviors_.push_back(ags_clear);
1108 
1109  //we'll rotate in-place one more time
1111  recovery_behaviors_.push_back(rotate);
1112  }
1113  catch(pluginlib::PluginlibException& ex){
1114  ROS_FATAL("Failed to load a plugin. This should not happen on default recovery behaviors. Error: %s", ex.what());
1115  }
1116 
1117  return;
1118  }
1119 
1121  // Disable the planner thread
1122  boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
1123  runPlanner_ = false;
1124  lock.unlock();
1125 
1126  // Reset statemachine
1127  state_ = PLANNING;
1128  recovery_index_ = 0;
1131 
1132  //if we shutdown our costmaps when we're deactivated... we'll do that now
1133  if(shutdown_costmaps_){
1134  ROS_DEBUG_NAMED("move_base","Stopping costmaps");
1137  }
1138  }
1139 
1141  {
1142  global_pose.setIdentity();
1143  tf::Stamped < tf::Pose > robot_pose;
1144  robot_pose.setIdentity();
1145  robot_pose.frame_id_ = robot_base_frame_;
1146  robot_pose.stamp_ = ros::Time(); // latest available
1147  ros::Time current_time = ros::Time::now(); // save time for checking tf delay later
1148 
1149  // get robot pose on the given costmap frame
1150  try
1151  {
1152  tf_.transformPose(costmap->getGlobalFrameID(), robot_pose, global_pose);
1153  }
1154  catch (tf::LookupException& ex)
1155  {
1156  ROS_ERROR_THROTTLE(1.0, "No Transform available Error looking up robot pose: %s\n", ex.what());
1157  return false;
1158  }
1159  catch (tf::ConnectivityException& ex)
1160  {
1161  ROS_ERROR_THROTTLE(1.0, "Connectivity Error looking up robot pose: %s\n", ex.what());
1162  return false;
1163  }
1164  catch (tf::ExtrapolationException& ex)
1165  {
1166  ROS_ERROR_THROTTLE(1.0, "Extrapolation Error looking up robot pose: %s\n", ex.what());
1167  return false;
1168  }
1169 
1170  // check if global_pose time stamp is within costmap transform tolerance
1171  if (current_time.toSec() - global_pose.stamp_.toSec() > costmap->getTransformTolerance())
1172  {
1173  ROS_WARN_THROTTLE(1.0, "Transform timeout for %s. " \
1174  "Current time: %.4f, pose stamp: %.4f, tolerance: %.4f", costmap->getName().c_str(),
1175  current_time.toSec(), global_pose.stamp_.toSec(), costmap->getTransformTolerance());
1176  return false;
1177  }
1178 
1179  return true;
1180  }
1181 };
void executeCb(const move_base_msgs::MoveBaseGoalConstPtr &move_base_goal)
Definition: move_base.cpp:639
boost::condition_variable_any planner_cond_
Definition: move_base.h:220
boost::thread * planner_thread_
Definition: move_base.h:222
void wakePlanner(const ros::TimerEvent &event)
This is used to wake the planner at periodic intervals.
Definition: move_base.cpp:551
ros::ServiceServer make_plan_srv_
Definition: move_base.h:199
double distance(const geometry_msgs::PoseStamped &p1, const geometry_msgs::PoseStamped &p2)
Definition: move_base.cpp:785
boost::shared_ptr< const Goal > acceptNewGoal()
void publishFeedback(const FeedbackConstPtr &feedback)
pluginlib::ClassLoader< nav_core::BaseLocalPlanner > blp_loader_
Definition: move_base.h:209
MoveBaseActionServer * as_
Definition: move_base.h:180
#define ROS_FATAL(...)
tfScalar getAngle() const
bool isQuaternionValid(const geometry_msgs::Quaternion &q)
Definition: move_base.cpp:498
void publish(const boost::shared_ptr< M > &message) const
costmap_2d::Costmap2DROS * controller_costmap_ros_
Definition: move_base.h:183
int32_t max_planning_retries_
Definition: move_base.h:194
bool getRobotPose(tf::Stamped< tf::Pose > &global_pose) const
bool planService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp)
A service call that can be made when the action is inactive that will return a plan.
Definition: move_base.cpp:339
double clearing_radius_
Definition: move_base.h:196
pluginlib::ClassLoader< nav_core::BaseGlobalPlanner > bgp_loader_
Definition: move_base.h:208
tfScalar length2() const
boost::recursive_mutex configuration_mutex_
Definition: move_base.h:225
double planner_frequency_
Definition: move_base.h:192
int size() const
static void poseStampedTFToMsg(const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
Duration cycleTime() const
std::string getGlobalFrameID()
double inscribed_radius_
Definition: move_base.h:192
void notify_one() BOOST_NOEXCEPT
ros::Publisher action_goal_pub_
Definition: move_base.h:197
virtual ~MoveBase()
Destructor - Cleans up.
Definition: move_base.cpp:432
ROSCPP_DECL const std::string & getName()
ros::Time last_oscillation_reset_
Definition: move_base.h:206
Quaternion & normalize()
bool getRobotPose(tf::Stamped< tf::Pose > &global_posee, costmap_2d::Costmap2DROS *costmap)
Definition: move_base.cpp:1140
bool recovery_behavior_enabled_
Definition: move_base.h:200
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ros::Publisher vel_pub_
Definition: move_base.h:197
actionlib::SimpleActionServer< move_base_msgs::MoveBaseAction > MoveBaseActionServer
Definition: move_base.h:64
std::string global_frame_
Definition: move_base.h:186
tf::TransformListener * tf_
Type const & getType() const
TFSIMD_FORCE_INLINE const tfScalar & y() const
static const unsigned char FREE_SPACE
#define ROS_WARN(...)
std::vector< geometry_msgs::PoseStamped > * planner_plan_
Definition: move_base.h:213
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
boost::shared_ptr< nav_core::BaseGlobalPlanner > planner_
Definition: move_base.h:185
std::string getName() const
double planner_patience_
Definition: move_base.h:193
bool clearing_rotation_allowed_
Definition: move_base.h:200
#define ROS_DEBUG_NAMED(name,...)
unsigned int recovery_index_
Definition: move_base.h:189
dynamic_reconfigure::Server< move_base::MoveBaseConfig > * dsrv_
Definition: move_base.h:226
RecoveryTrigger recovery_trigger_
Definition: move_base.h:204
TFSIMD_FORCE_INLINE tfScalar dot(const Vector3 &v) const
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
TFSIMD_FORCE_INLINE Vector3 rotate(const Vector3 &wAxis, const tfScalar angle) const
ros::ServiceServer clear_costmaps_srv_
Definition: move_base.h:199
#define ROS_WARN_THROTTLE(period,...)
move_base::MoveBaseConfig default_config_
Definition: move_base.h:231
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
std::vector< std::string > getDeclaredClasses()
#define ROS_ERROR_THROTTLE(period,...)
ros::Time last_valid_plan_
Definition: move_base.h:206
void loadDefaultRecoveryBehaviors()
Loads the default recovery behaviors for the navigation stack.
Definition: move_base.cpp:1084
std::vector< boost::shared_ptr< nav_core::RecoveryBehavior > > recovery_behaviors_
Definition: move_base.h:188
bool loadRecoveryBehaviors(ros::NodeHandle node)
Load the recovery behaviors for the navigation stack from the parameter server.
Definition: move_base.cpp:999
Vector3 getAxis() const
void reconfigureCB(move_base::MoveBaseConfig &config, uint32_t level)
Definition: move_base.cpp:174
double controller_patience_
Definition: move_base.h:193
double getTransformTolerance() const
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
void goalCB(const geometry_msgs::PoseStamped::ConstPtr &goal)
Definition: move_base.cpp:264
pluginlib::ClassLoader< nav_core::RecoveryBehavior > recovery_loader_
Definition: move_base.h:210
TFSIMD_FORCE_INLINE const tfScalar & x() const
double controller_frequency_
Definition: move_base.h:192
bool setConvexPolygonCost(const std::vector< geometry_msgs::Point > &polygon, unsigned char cost_value)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
costmap_2d::Costmap2DROS * planner_costmap_ros_
Definition: move_base.h:183
boost::recursive_mutex planner_mutex_
Definition: move_base.h:219
virtual std::string getName(const std::string &lookup_name)
void publishZeroVelocity()
Publishes a velocity command of zero to the base.
Definition: move_base.cpp:490
geometry_msgs::PoseStamped goalToGlobalFrame(const geometry_msgs::PoseStamped &goal_pose_msg)
Definition: move_base.cpp:528
TFSIMD_FORCE_INLINE tfScalar dot(const Quaternion &q1, const Quaternion &q2)
double oscillation_distance_
Definition: move_base.h:201
boost::shared_ptr< nav_core::BaseLocalPlanner > tc_
Definition: move_base.h:182
bool sleep()
void resetState()
Reset the state of the move_base action and send a zero velocity command to the base.
Definition: move_base.cpp:1120
ros::Time stamp_
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
bool hasMember(const std::string &name) const
ros::Publisher current_goal_pub_
Definition: move_base.h:197
geometry_msgs::PoseStamped planner_goal_
Definition: move_base.h:221
MoveBaseState state_
Definition: move_base.h:203
std::string frame_id_
static WallTime now()
ros::Subscriber goal_sub_
Definition: move_base.h:198
void transformPose(const std::string &target_frame, const geometry_msgs::PoseStamped &stamped_in, geometry_msgs::PoseStamped &stamped_out) const
tf::TransformListener & tf_
Definition: move_base.h:178
TFSIMD_FORCE_INLINE Vector3 rotate(const Vector3 &wAxis, const tfScalar angle) const
bool getParam(const std::string &key, std::string &s) const
std::vector< geometry_msgs::PoseStamped > * latest_plan_
Definition: move_base.h:214
move_base::MoveBaseConfig last_config_
Definition: move_base.h:230
MoveBase(tf::TransformListener &tf)
Constructor for the actions.
Definition: move_base.cpp:48
static Time now()
bool clearCostmapsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
A service call that clears the costmaps of obstacles.
Definition: move_base.cpp:328
uint32_t planning_retries_
Definition: move_base.h:195
bool ok() const
double circumscribed_radius_
Definition: move_base.h:192
double getResolution() const
Costmap2D * getCostmap()
std::string robot_base_frame_
Definition: move_base.h:186
bool makePlan(const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)
Make a new global plan.
Definition: move_base.cpp:459
double conservative_reset_dist_
Definition: move_base.h:196
bool executeCycle(geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &global_plan)
Performs a control cycle.
Definition: move_base.cpp:790
virtual bool isClassAvailable(const std::string &lookup_name)
ros::Time last_valid_control_
Definition: move_base.h:206
double oscillation_timeout_
Definition: move_base.h:201
#define ROS_ERROR(...)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
geometry_msgs::PoseStamped oscillation_pose_
Definition: move_base.h:207
void clearCostmapWindows(double size_x, double size_y)
Clears obstacles within a window around the robot.
Definition: move_base.cpp:273
std::vector< geometry_msgs::PoseStamped > * controller_plan_
Definition: move_base.h:215


move_base
Author(s): Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:44:48