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


move_base
Author(s): Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Thu Jan 21 2021 04:06:13