locomove_base.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
38 #include <nav_2d_utils/path_ops.h>
39 #include <string>
40 #include <vector>
41 
42 namespace locomove_base
43 {
49 std::string getNamespace(const std::string& s)
50 {
51  std::vector<std::string> split;
52  boost::split(split, s, boost::is_any_of("/:"));
53  return split.back();
54 }
55 
66 {
67  // Double check robot_base_frame parameters for backwards compatibility
68  if (!nh.hasParam("robot_base_frame"))
69  {
70  // If robot_base_frame was not set, use one of the values from the costmaps
71  std::string planner_frame, controller_frame, value_to_use;
72  nh.param("global_costmap/robot_base_frame", planner_frame, std::string(""));
73  nh.param("local_costmap/robot_base_frame", controller_frame, std::string(""));
74  if (planner_frame != controller_frame)
75  {
76  if (planner_frame.length() == 0)
77  {
78  value_to_use = controller_frame;
79  }
80  else if (controller_frame.length() == 0)
81  {
82  value_to_use = planner_frame;
83  }
84  else
85  {
86  ROS_WARN_NAMED("LocoMoveBase", "Two different robot_base_frames set for global and local planner. "
87  "This could be problematic. Using the global base frame.");
88  value_to_use = planner_frame;
89  }
90  }
91  else
92  {
93  value_to_use = planner_frame;
94  }
95  nh.setParam("robot_base_frame", value_to_use);
96  }
97 
98  // Set the Global Planner Parameters
99  std::string planner_class, planner_namespace;
100  std::vector<std::string> plugin_namespaces;
101 
102  // Load the name of the nav_core1 global planner
103  nh.param("base_global_planner", planner_class, std::string("navfn/NavfnROS"));
104  planner_namespace = getNamespace(planner_class);
105  if (planner_class == "nav_core_adapter::GlobalPlannerAdapter2")
106  {
107  // If the planner class is the adapter, then get and use the nav_core2 planner
108  nh.param(planner_namespace + "/planner_name", planner_class, std::string("global_planner::GlobalPlanner"));
109  planner_namespace = getNamespace(planner_class);
110  nh.setParam(planner_namespace + "/plugin_class", planner_class);
111  plugin_namespaces.push_back(planner_namespace);
112  nh.setParam("global_planner_namespaces", plugin_namespaces);
113  }
114  else
115  {
116  // Otherwise, we need to inject the routing through the adapter
117  std::string adapter_namespace = "global_planner_adapter";
118  plugin_namespaces.push_back(adapter_namespace);
119  nh.setParam("global_planner_namespaces", plugin_namespaces);
120  nh.setParam(adapter_namespace + "/planner_name", planner_class);
121  nh.setParam(adapter_namespace + "/plugin_class", "nav_core_adapter::GlobalPlannerAdapter2");
122  }
123  plugin_namespaces.clear();
124 
125  // Since the nav_core1 local planners are not compatible with nav_core2, we either need to load the
126  // class that is being adapted, or we just load DWB instead
127  nh.param("base_local_planner", planner_class, std::string("base_local_planner/TrajectoryPlannerROS"));
128  planner_namespace = getNamespace(planner_class);
129  if (planner_namespace == "LocalPlannerAdapter")
130  {
131  nh.param(planner_namespace + "/planner_name", planner_class, std::string("dwb_local_planner::DWBLocalPlanner"));
132  planner_namespace = getNamespace(planner_class);
133  nh.setParam(planner_namespace + "/plugin_class", planner_class);
134  plugin_namespaces.push_back(planner_namespace);
135  nh.setParam("local_planner_namespaces", plugin_namespaces);
136  }
137  else if (planner_namespace == "DWAPlannerROS")
138  {
139  ROS_WARN_NAMED("LocoMoveBase", "Using DWB as the local planner instead of DWA.");
140  nh.setParam(planner_namespace + "/plugin_class", "dwb_local_planner::DWBLocalPlanner");
141  plugin_namespaces.push_back(planner_namespace);
142  nh.setParam("local_planner_namespaces", plugin_namespaces);
143  }
144  else
145  {
146  ROS_FATAL_NAMED("LocoMoveBase", "%s is unsupported in LocoMoveBase because it is not forwards compatible.",
147  planner_class.c_str());
148  }
149 
150  return nh;
151 }
152 
154  private_nh_(nh), locomotor_(loadBackwardsCompatibleParameters(nh)),
155  server_(ros::NodeHandle(), "move_base", false),
156  recovery_loader_("nav_core", "nav_core::RecoveryBehavior"),
157  local_planning_ex_(private_nh_, false), global_planning_ex_(private_nh_)
158 {
160  if (planner_frequency_ > 0.0)
161  {
164  this, false, false); // one_shot=false(default), auto_start=false
165  }
166 
171  this, false, false); // one_shot=false(default), auto_start=false
176 
179 
180  goal_pub_ = private_nh_.advertise<geometry_msgs::PoseStamped>("current_goal", 1);
181 
183 
184  // load any user specified recovery behaviors, and if that fails load the defaults
186  {
188  }
189 
190  // Patience
194 
195  // Oscillation
198 
199  // we'll provide a mechanism for some people to send goals as PoseStamped messages over a topic
200  // they won't get any useful information back about its status, but this is useful for tools
201  // like nav_view and rviz
202  ros::NodeHandle simple_nh("move_base_simple");
203  goal_sub_ = simple_nh.subscribe<geometry_msgs::PoseStamped>("goal", 1, boost::bind(&LocoMoveBase::goalCB, this, _1));
204 
206  server_.start();
207 
208  resetState();
209 }
210 
211 void LocoMoveBase::setGoal(nav_2d_msgs::Pose2DStamped goal)
212 {
213  resetState();
214  locomotor_.setGoal(goal);
216  if (planner_frequency_ > 0.0)
217  {
219  }
220  else
221  {
223  }
224 }
225 
227 {
228  std::shared_ptr<nav_core_adapter::CostmapAdapter> ptr =
229  std::dynamic_pointer_cast<nav_core_adapter::CostmapAdapter>(costmap);
230 
231  if (!ptr)
232  {
233  ROS_FATAL_NAMED("LocoMoveBase", "LocoMoveBase can only be used with the CostmapAdapter, not other Costmaps!");
234  exit(-1);
235  }
236  return ptr->getCostmap2DROS();
237 }
238 
240 {
241  // we'll start executing recovery behaviors at the beginning of our list
242  recovery_index_ = 0;
244 
245  // we want to make sure that we reset the last time we had a valid plan and control
249  planning_retries_ = 0;
250  has_global_plan_ = false;
251 }
252 
254 {
255  locomotor_.publishTwist(nav_2d_msgs::Twist2DStamped());
256 }
257 
258 void LocoMoveBase::requestNavigationFailure(const locomotor_msgs::ResultCode& result)
259 {
261  std::bind(&LocoMoveBase::onNavigationFailure, this, std::placeholders::_1));
262 }
263 
265 {
267 }
268 
270 {
272  std::bind(&LocoMoveBase::onGlobalCostmapUpdate, this, std::placeholders::_1),
273  std::bind(&LocoMoveBase::onGlobalCostmapException, this, std::placeholders::_1, std::placeholders::_2));
274 }
275 
277 {
278  // Run the global planning on the separate executor, but put the result on the main executor
280  std::bind(&LocoMoveBase::onNewGlobalPlan, this, std::placeholders::_1, std::placeholders::_2),
281  std::bind(&LocoMoveBase::onGlobalPlanningException, this, std::placeholders::_1, std::placeholders::_2));
282 }
283 
285 {
286  // If the planner_frequency is non-zero, the costmap will attempt to update again on its own (via the Timer).
287  // If it is zero, then we manually request a new update
288  if (planner_frequency_ == 0.0)
289  {
291  }
292 }
293 
294 void LocoMoveBase::onNewGlobalPlan(nav_2d_msgs::Path2D new_global_plan, const ros::Duration& planning_time)
295 {
296  has_global_plan_ = true;
298  planning_retries_ = 0;
299  locomotor_.publishPath(new_global_plan);
300  locomotor_.getCurrentLocalPlanner().setPlan(new_global_plan);
301  if (planning_time > desired_plan_duration_)
302  {
303  ROS_WARN_NAMED("locomotor", "Global planning missed its desired rate of %.4fHz... "
304  "the loop actually took %.4f seconds (>%.4f).",
306  }
308  {
309  recovery_index_ = 0;
310  }
312 }
313 
315 {
316  if (has_global_plan_)
317  {
318  // If we have a global plan already, we can ignore this exception for the time being
319  return;
320  }
321 
325  {
328  recovery();
329  }
330 }
331 
333 {
335  std::bind(&LocoMoveBase::onLocalCostmapUpdate, this, std::placeholders::_1),
336  std::bind(&LocoMoveBase::onLocalCostmapException, this, std::placeholders::_1, std::placeholders::_2));
337 }
338 
340 {
341  // check for an oscillation condition
343  {
346  recovery();
347  return;
348  }
350  std::bind(&LocoMoveBase::onNewLocalPlan, this, std::placeholders::_1, std::placeholders::_2),
351  std::bind(&LocoMoveBase::onLocalPlanningException, this, std::placeholders::_1, std::placeholders::_2),
352  std::bind(&LocoMoveBase::onNavigationCompleted, this));
353 }
354 
356 {
357  ROS_WARN_NAMED("LocoMoveBase",
358  "Sensor data is out of date, we're not going to allow commanding of the base for safety");
360 }
361 
362 void LocoMoveBase::onNewLocalPlan(nav_2d_msgs::Twist2DStamped new_command, const ros::Duration& planning_time)
363 {
365  {
366  recovery_index_ = 0;
367  }
369  locomotor_.publishTwist(new_command);
370 
371  nav_2d_msgs::Pose2DStamped current_pose = locomotor_.getLocalRobotPose();
372 
373  // check to see if we've moved far enough to reset our oscillation timeout
375  {
377  oscillation_pose_ = current_pose.pose;
378 
379  // if our last recovery was caused by oscillation, we want to reset the recovery index
381  {
382  recovery_index_ = 0;
383  }
384  }
385 
386  if (!server_.isActive())
387  {
388  return;
389  }
390 
391  // publish feedback
392  move_base_msgs::MoveBaseFeedback feedback;
393  feedback.base_position = nav_2d_utils::pose2DToPoseStamped(current_pose);
394  server_.publishFeedback(feedback);
395 }
396 
398 {
399  // check if we've tried to find a valid control for longer than our time limit
401  {
403  recovery();
404  }
405  else
406  {
407  ROS_WARN_NAMED("Locomotor", "Local planning error. Creating new global plan.");
410  planning_retries_ = 0;
412  }
413 }
414 
416 {
417  ROS_INFO_NAMED("Locomotor", "Plan completed! Stopping.");
418  if (server_.isActive())
419  {
421  }
424 }
425 
426 void LocoMoveBase::onNavigationFailure(const locomotor_msgs::ResultCode result)
427 {
428  if (server_.isActive())
429  {
431  }
434 }
435 
437 {
438  ROS_DEBUG_NAMED("locomotor", "In clearing/recovery state");
439 
440  // we'll invoke whatever recovery behavior we're currently on if they're enabled
442  {
443  ROS_DEBUG_NAMED("locomotor_recovery", "Executing behavior %u of %zu",
445  recovery_behaviors_[recovery_index_]->runBehavior();
446 
447  // we'll check if the recovery behavior actually worked
448  // ROS_DEBUG_NAMED("locomotor_recovery","Going back to planning state");
451 
452  // we at least want to give the robot some time to stop oscillating after executing the behavior
455  planning_retries_ = 0;
456 
457  // update the index of the next recovery behavior that we'll try
458  recovery_index_++;
459  }
460  else
461  {
462  ROS_DEBUG_NAMED("locomotor_recovery",
463  "All recovery behaviors have failed, locking the planner and disabling it.");
464 
466  {
467  ROS_ERROR("Aborting because a valid control could not be found."
468  "Even after executing all recovery behaviors");
469  requestNavigationFailure(locomotor::makeResultCode(locomotor_msgs::ResultCode::LOCAL_PLANNER, CONTROLLING_R,
470  "Failed to find a valid control. Even after executing recovery behaviors."));
471  }
472  else if (recovery_trigger_ == PLANNING_R)
473  {
474  ROS_ERROR("Aborting because a valid plan could not be found. Even after executing all recovery behaviors");
475  requestNavigationFailure(locomotor::makeResultCode(locomotor_msgs::ResultCode::GLOBAL_PLANNER, PLANNING_R,
476  "Failed to find a valid plan. Even after executing recovery behaviors."));
477  }
478  else if (recovery_trigger_ == OSCILLATION_R)
479  {
480  ROS_ERROR("Aborting because the robot appears to be oscillating over and over."
481  "Even after executing all recovery behaviors");
482  requestNavigationFailure(locomotor::makeResultCode(locomotor_msgs::ResultCode::LOCAL_PLANNER, OSCILLATION_R,
483  "Robot is oscillating. Even after executing recovery behaviors."));
484  }
485  }
486 }
487 
489 {
490  XmlRpc::XmlRpcValue behavior_list;
491  if (!node.getParam("recovery_behaviors", behavior_list))
492  {
493  // if no recovery_behaviors are specified, we'll just load the defaults
494  return false;
495  }
496 
497  if (behavior_list.getType() != XmlRpc::XmlRpcValue::TypeArray)
498  {
499  ROS_ERROR("The recovery behavior specification must be a list, but is of XmlRpcType %d. "
500  "We'll use the default recovery behaviors instead.",
501  behavior_list.getType());
502  return false;
503  }
504 
505  for (int i = 0; i < behavior_list.size(); ++i)
506  {
507  if (behavior_list[i].getType() != XmlRpc::XmlRpcValue::TypeStruct)
508  {
509  ROS_ERROR("Recovery behaviors must be specified as maps, but they are XmlRpcType %d. "
510  "We'll use the default recovery behaviors instead.",
511  behavior_list[i].getType());
512  return false;
513  }
514 
515  if (!behavior_list[i].hasMember("name") || !behavior_list[i].hasMember("type"))
516  {
517  ROS_ERROR("Recovery behaviors must have a name and a type and this does not. "
518  "Using the default recovery behaviors instead.");
519  return false;
520  }
521 
522  // check for recovery behaviors with the same name
523  std::string name_i = behavior_list[i]["name"];
524  for (int j = i + 1; j < behavior_list.size(); j++)
525  {
526  if (behavior_list[j].getType() != XmlRpc::XmlRpcValue::TypeStruct || !behavior_list[j].hasMember("name"))
527  {
528  continue;
529  }
530 
531  std::string name_j = behavior_list[j]["name"];
532  if (name_i == name_j)
533  {
534  ROS_ERROR("A recovery behavior with the name %s already exists, "
535  "this is not allowed. Using the default recovery behaviors instead.",
536  name_i.c_str());
537  return false;
538  }
539  }
540  }
541 
543  // if we've made it to this point, we know that the list is legal so we'll create all the recovery behaviors
544  for (int i = 0; i < behavior_list.size(); ++i)
545  {
546  try
547  {
548  boost::shared_ptr<nav_core::RecoveryBehavior> behavior(recovery_loader_.createInstance(behavior_list[i]["type"]));
549 
550  // shouldn't be possible, but it won't hurt to check
551  if (behavior.get() == nullptr)
552  {
553  ROS_ERROR("The ClassLoader returned a null pointer without throwing an exception. "
554  "This should not happen");
555  return false;
556  }
557 
558  // initialize the recovery behavior with its name
559  behavior->initialize(behavior_list[i]["name"], tf.get(), planner_costmap_ros_, controller_costmap_ros_);
560  recovery_behaviors_.push_back(behavior);
561  }
563  {
564  ROS_ERROR("Failed to load a plugin. Using default recovery behaviors. Error: %s", ex.what());
565  return false;
566  }
567  }
568  // if we've made it here... we've constructed a recovery behavior list successfully
569  return true;
570 }
571 
572 // we'll load our default recovery behaviors here
574 {
575  recovery_behaviors_.clear();
576  // Transform shared pointers to raw pointers for backwards compatibility with the recovery behaviors
578  try
579  {
580  // we need to set some parameters based on what's been passed in to us to maintain backwards compatibility
581  ros::NodeHandle n("~");
582 
583  // first, we'll load a recovery behavior to clear the costmap
585  recovery_loader_.createInstance("clear_costmap_recovery/ClearCostmapRecovery"));
586  cons_clear->initialize("conservative_reset", tf.get(), planner_costmap_ros_, controller_costmap_ros_);
587  recovery_behaviors_.push_back(cons_clear);
588 
589  // next, we'll load a recovery behavior to rotate in place
590  bool clearing_rotation_allowed;
591  n.param("clearing_rotation_allowed", clearing_rotation_allowed, true);
592 
594  recovery_loader_.createInstance("rotate_recovery/RotateRecovery"));
595  if (clearing_rotation_allowed)
596  {
597  rotate->initialize("rotate_recovery", tf.get(), planner_costmap_ros_, controller_costmap_ros_);
598  recovery_behaviors_.push_back(rotate);
599  }
600 
601  // next, we'll load a recovery behavior that will do an aggressive reset of the costmap
603  recovery_loader_.createInstance("clear_costmap_recovery/ClearCostmapRecovery"));
604  ags_clear->initialize("aggressive_reset", tf.get(), planner_costmap_ros_, controller_costmap_ros_);
605  recovery_behaviors_.push_back(ags_clear);
606 
607  // we'll rotate in-place one more time
608  if (clearing_rotation_allowed)
609  recovery_behaviors_.push_back(rotate);
610  }
612  {
613  ROS_FATAL("Failed to load a plugin. This should not happen on default recovery behaviors. Error: %s",
614  ex.what());
615  }
616 
617  return;
618 }
619 
620 void LocoMoveBase::goalCB(const geometry_msgs::PoseStamped::ConstPtr& goal)
621 {
623 }
624 
626 {
627  auto move_base_goal = server_.acceptNewGoal();
628  setGoal(nav_2d_utils::poseStampedToPose2D(move_base_goal->target_pose));
629 }
630 
631 } // namespace locomove_base
632 
633 int main(int argc, char** argv)
634 {
635  ros::init(argc, argv, "move_base");
636  ros::NodeHandle nh("~");
638  ros::spin();
639  return 0;
640 }
virtual void setPlan(const nav_2d_msgs::Path2D &path)=0
nav_2d_msgs::Pose2DStamped getLocalRobotPose() const
boost::shared_ptr< const Goal > acceptNewGoal()
void publishTwist(const nav_2d_msgs::Twist2DStamped &command)
void publishFeedback(const FeedbackConstPtr &feedback)
ros::NodeHandle private_nh_
Definition: locomove_base.h:97
#define ROS_FATAL(...)
nav_core2::LocalPlanner & getCurrentLocalPlanner()
#define ROS_INFO_NAMED(name,...)
int main(int argc, char **argv)
void publish(const boost::shared_ptr< M > &message) const
#define ROS_WARN_NAMED(name,...)
locomotor::Locomotor locomotor_
Definition: locomove_base.h:98
void controlLoopCallback(const ros::TimerEvent &event)
locomotor_msgs::ResultCode makeResultCode(int component=-1, int result_code=-1, const std::string &message="")
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
costmap_2d::Costmap2DROS * planner_costmap_ros_
locomotor::Executor local_planning_ex_
int size() const
void stop()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void requestLocalCostmapUpdate(Executor &work_ex, Executor &result_ex, CostmapUpdateCallback cb=nullptr, CostmapUpdateExceptionCallback fail_cb=nullptr)
void start()
void onLocalCostmapUpdate(const ros::Duration &planning_time)
void initializeGlobalPlanners(Executor &ex)
void onGlobalCostmapUpdate(const ros::Duration &planning_time)
Type const & getType() const
geometry_msgs::Pose2D oscillation_pose_
virtual void setGoal(nav_2d_msgs::Pose2DStamped goal)
bool loadRecoveryBehaviors(ros::NodeHandle node)
Load the recovery behaviors for the navigation stack from the parameter server.
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
void onNewLocalPlan(nav_2d_msgs::Twist2DStamped new_command, const ros::Duration &planning_time)
actionlib::SimpleActionServer< move_base_msgs::MoveBaseAction > server_
std::exception_ptr NavCore2ExceptionPtr
void loadDefaultRecoveryBehaviors()
Loads the default recovery behaviors for the navigation stack.
ROSCPP_DECL void spin(Spinner &spinner)
void onNavigationFailure(const locomotor_msgs::ResultCode result)
costmap_2d::Costmap2DROS * getCostmapPointer(const nav_core2::Costmap::Ptr &costmap)
nav_2d_msgs::Pose2DStamped poseStampedToPose2D(const geometry_msgs::PoseStamped &pose)
#define ROS_DEBUG_NAMED(name,...)
void publishPath(const nav_2d_msgs::Path2D &global_plan)
double poseDistance(const geometry_msgs::Pose2D &pose0, const geometry_msgs::Pose2D &pose1)
geometry_msgs::PoseStamped pose2DToPoseStamped(const nav_2d_msgs::Pose2DStamped &pose2d)
void goalCB(const geometry_msgs::PoseStamped::ConstPtr &goal)
void onLocalPlanningException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration &planning_time)
void setGoal(nav_2d_msgs::Pose2DStamped goal)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ros::Duration desired_plan_duration_
void requestNavigationFailure(const locomotor_msgs::ResultCode &result)
void initializeLocalCostmap(Executor &ex)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
LocoMoveBase(const ros::NodeHandle &nh)
void initializeGlobalCostmap(Executor &ex)
ros::Duration desired_control_duration_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::string getNamespace(const std::string &s)
Reimplementation of ClassLoader::getName without needing a ClassLoader.
TFListenerPtr getTFListener() const
void initializeLocalPlanners(Executor &ex)
pluginlib::ClassLoader< nav_core::RecoveryBehavior > recovery_loader_
void requestNavigationFailure(Executor &result_ex, const locomotor_msgs::ResultCode &result, NavigationFailureCallback cb=nullptr)
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
bool hasMember(const std::string &name) const
void planLoopCallback(const ros::TimerEvent &event)
std::vector< boost::shared_ptr< nav_core::RecoveryBehavior > > recovery_behaviors_
TFSIMD_FORCE_INLINE Vector3 rotate(const Vector3 &wAxis, const tfScalar angle) const
bool getParam(const std::string &key, std::string &s) const
#define ROS_FATAL_NAMED(name,...)
static Time now()
nav_core2::Costmap::Ptr getLocalCostmap() const
void onLocalCostmapException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration &planning_time)
std::shared_ptr< Costmap > Ptr
void onNewGlobalPlan(nav_2d_msgs::Path2D new_global_plan, const ros::Duration &planning_time)
bool hasParam(const std::string &key) const
std::shared_ptr< tf::TransformListener > TFListenerPtr
void registerGoalCallback(boost::function< void()> cb)
void onGlobalCostmapException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration &planning_time)
nav_core2::Costmap::Ptr getGlobalCostmap() const
costmap_2d::Costmap2DROS * controller_costmap_ros_
RecoveryTrigger recovery_trigger_
const ros::NodeHandle & loadBackwardsCompatibleParameters(const ros::NodeHandle &nh)
Copy parameter values to get backwards compatibility.
#define ROS_ERROR(...)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
void requestGlobalCostmapUpdate(Executor &work_ex, Executor &result_ex, CostmapUpdateCallback cb=nullptr, CostmapUpdateExceptionCallback fail_cb=nullptr)
void onGlobalPlanningException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration &planning_time)
locomotor::Executor global_planning_ex_
void requestGlobalPlan(Executor &work_ex, Executor &result_ex, GlobalPlanCallback cb=nullptr, PlannerExceptionCallback fail_cb=nullptr)
void requestLocalPlan(Executor &work_ex, Executor &result_ex, LocalPlanCallback cb=nullptr, PlannerExceptionCallback fail_cb=nullptr, NavigationCompleteCallback complete_cb=nullptr)


locomove_base
Author(s):
autogenerated on Wed Jun 26 2019 20:06:27