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 <memory>
40 #include <string>
41 #include <vector>
42 
43 namespace locomove_base
44 {
50 std::string getNamespace(const std::string& s)
51 {
52  std::vector<std::string> split;
53  boost::split(split, s, boost::is_any_of("/:"));
54  return split.back();
55 }
56 
67 {
68  // Double check robot_base_frame parameters for backwards compatibility
69  if (!nh.hasParam("robot_base_frame"))
70  {
71  // If robot_base_frame was not set, use one of the values from the costmaps
72  std::string planner_frame, controller_frame, value_to_use;
73  nh.param("global_costmap/robot_base_frame", planner_frame, std::string(""));
74  nh.param("local_costmap/robot_base_frame", controller_frame, std::string(""));
75  if (planner_frame != controller_frame)
76  {
77  if (planner_frame.length() == 0)
78  {
79  value_to_use = controller_frame;
80  }
81  else if (controller_frame.length() == 0)
82  {
83  value_to_use = planner_frame;
84  }
85  else
86  {
87  ROS_WARN_NAMED("LocoMoveBase", "Two different robot_base_frames set for global and local planner. "
88  "This could be problematic. Using the global base frame.");
89  value_to_use = planner_frame;
90  }
91  }
92  else
93  {
94  value_to_use = planner_frame;
95  }
96  nh.setParam("robot_base_frame", value_to_use);
97  }
98 
99  // Set the Global Planner Parameters
100  std::string planner_class, planner_namespace;
101  std::vector<std::string> plugin_namespaces;
102 
103  // Load the name of the nav_core1 global planner
104  nh.param("base_global_planner", planner_class, std::string("navfn/NavfnROS"));
105  planner_namespace = getNamespace(planner_class);
106  if (planner_class == "nav_core_adapter::GlobalPlannerAdapter2")
107  {
108  // If the planner class is the adapter, then get and use the nav_core2 planner
109  nh.param(planner_namespace + "/planner_name", planner_class, std::string("global_planner::GlobalPlanner"));
110  planner_namespace = getNamespace(planner_class);
111  nh.setParam(planner_namespace + "/plugin_class", planner_class);
112  plugin_namespaces.push_back(planner_namespace);
113  nh.setParam("global_planner_namespaces", plugin_namespaces);
114  }
115  else
116  {
117  // Otherwise, we need to inject the routing through the adapter
118  std::string adapter_namespace = "global_planner_adapter";
119  plugin_namespaces.push_back(adapter_namespace);
120  nh.setParam("global_planner_namespaces", plugin_namespaces);
121  nh.setParam(adapter_namespace + "/planner_name", planner_class);
122  nh.setParam(adapter_namespace + "/plugin_class", "nav_core_adapter::GlobalPlannerAdapter2");
123  }
124  plugin_namespaces.clear();
125 
126  // Since the nav_core1 local planners are not compatible with nav_core2, we either need to load the
127  // class that is being adapted, or we just load DWB instead
128  nh.param("base_local_planner", planner_class, std::string("base_local_planner/TrajectoryPlannerROS"));
129  planner_namespace = getNamespace(planner_class);
130  if (planner_namespace == "LocalPlannerAdapter")
131  {
132  nh.param(planner_namespace + "/planner_name", planner_class, std::string("dwb_local_planner::DWBLocalPlanner"));
133  planner_namespace = getNamespace(planner_class);
134  nh.setParam(planner_namespace + "/plugin_class", planner_class);
135  plugin_namespaces.push_back(planner_namespace);
136  nh.setParam("local_planner_namespaces", plugin_namespaces);
137  }
138  else if (planner_namespace == "DWAPlannerROS")
139  {
140  ROS_WARN_NAMED("LocoMoveBase", "Using DWB as the local planner instead of DWA.");
141  nh.setParam(planner_namespace + "/plugin_class", "dwb_local_planner::DWBLocalPlanner");
142  plugin_namespaces.push_back(planner_namespace);
143  nh.setParam("local_planner_namespaces", plugin_namespaces);
144  }
145  else
146  {
147  ROS_FATAL_NAMED("LocoMoveBase", "%s is unsupported in LocoMoveBase because it is not forwards compatible.",
148  planner_class.c_str());
149  }
150 
151  return nh;
152 }
153 
155  private_nh_(nh), locomotor_(loadBackwardsCompatibleParameters(nh)),
156  server_(ros::NodeHandle(), "move_base", false),
157  recovery_loader_("nav_core", "nav_core::RecoveryBehavior"),
158  local_planning_ex_(private_nh_, false), global_planning_ex_(private_nh_)
159 {
161  if (planner_frequency_ > 0.0)
162  {
165  this, false, false); // one_shot=false(default), auto_start=false
166  }
167 
172  this, false, false); // one_shot=false(default), auto_start=false
177 
180 
181  goal_pub_ = private_nh_.advertise<geometry_msgs::PoseStamped>("current_goal", 1);
182 
184 
185  // load any user specified recovery behaviors, and if that fails load the defaults
187  {
189  }
190 
191  // Patience
195 
196  // Oscillation
199 
200  // we'll provide a mechanism for some people to send goals as PoseStamped messages over a topic
201  // they won't get any useful information back about its status, but this is useful for tools
202  // like nav_view and rviz
203  ros::NodeHandle simple_nh("move_base_simple");
204  goal_sub_ = simple_nh.subscribe<geometry_msgs::PoseStamped>("goal", 1,
205  std::bind(&LocoMoveBase::goalCB, this,
206  std::placeholders::_1));
207 
210  server_.start();
211 
212  resetState();
213 }
214 
215 void LocoMoveBase::setGoal(nav_2d_msgs::Pose2DStamped goal)
216 {
217  resetState();
220  if (planner_frequency_ > 0.0)
221  {
223  }
224  else
225  {
227  }
228 }
229 
231 {
232  std::shared_ptr<nav_core_adapter::CostmapAdapter> ptr =
233  std::dynamic_pointer_cast<nav_core_adapter::CostmapAdapter>(costmap);
234 
235  if (!ptr)
236  {
237  ROS_FATAL_NAMED("LocoMoveBase", "LocoMoveBase can only be used with the CostmapAdapter, not other Costmaps!");
238  exit(-1);
239  }
240  return ptr->getCostmap2DROS();
241 }
242 
244 {
245  // we'll start executing recovery behaviors at the beginning of our list
246  recovery_index_ = 0;
248 
249  // we want to make sure that we reset the last time we had a valid plan and control
253  planning_retries_ = 0;
254  has_global_plan_ = false;
255 }
256 
258 {
259  locomotor_.publishTwist(nav_2d_msgs::Twist2DStamped());
260 }
261 
262 void LocoMoveBase::requestNavigationFailure(const locomotor_msgs::ResultCode& result)
263 {
265  std::bind(&LocoMoveBase::onNavigationFailure, this, std::placeholders::_1));
266 }
267 
269 {
271 }
272 
274 {
276  std::bind(&LocoMoveBase::onGlobalCostmapUpdate, this, std::placeholders::_1),
277  std::bind(&LocoMoveBase::onGlobalCostmapException, this, std::placeholders::_1, std::placeholders::_2));
278 }
279 
281 {
282  // Run the global planning on the separate executor, but put the result on the main executor
284  std::bind(&LocoMoveBase::onNewGlobalPlan, this, std::placeholders::_1, std::placeholders::_2),
285  std::bind(&LocoMoveBase::onGlobalPlanningException, this, std::placeholders::_1, std::placeholders::_2));
286 }
287 
289 {
290  // If the planner_frequency is non-zero, the costmap will attempt to update again on its own (via the Timer).
291  // If it is zero, then we manually request a new update
292  if (planner_frequency_ == 0.0)
293  {
295  }
296 }
297 
298 void LocoMoveBase::onNewGlobalPlan(nav_2d_msgs::Path2D new_global_plan, const ros::Duration& planning_time)
299 {
300  has_global_plan_ = true;
302  planning_retries_ = 0;
303  locomotor_.publishPath(new_global_plan);
304  locomotor_.getCurrentLocalPlanner().setPlan(new_global_plan);
305  if (planning_time > desired_plan_duration_)
306  {
307  ROS_WARN_NAMED("locomotor", "Global planning missed its desired rate of %.4fHz... "
308  "the loop actually took %.4f seconds (>%.4f).",
310  }
312  {
313  recovery_index_ = 0;
314  }
316 }
317 
319 {
320  if (has_global_plan_)
321  {
322  // If we have a global plan already, we can ignore this exception for the time being
323  return;
324  }
325 
329  {
332  recovery();
333  }
334 }
335 
337 {
339  std::bind(&LocoMoveBase::onLocalCostmapUpdate, this, std::placeholders::_1),
340  std::bind(&LocoMoveBase::onLocalCostmapException, this, std::placeholders::_1, std::placeholders::_2));
341 }
342 
344 {
345  // check for an oscillation condition
347  {
350  recovery();
351  return;
352  }
354  std::bind(&LocoMoveBase::onNewLocalPlan, this, std::placeholders::_1, std::placeholders::_2),
355  std::bind(&LocoMoveBase::onLocalPlanningException, this, std::placeholders::_1, std::placeholders::_2),
356  std::bind(&LocoMoveBase::onNavigationCompleted, this));
357 }
358 
360 {
361  ROS_WARN_NAMED("LocoMoveBase",
362  "Sensor data is out of date, we're not going to allow commanding of the base for safety");
364 }
365 
366 void LocoMoveBase::onNewLocalPlan(nav_2d_msgs::Twist2DStamped new_command, const ros::Duration& planning_time)
367 {
369  {
370  recovery_index_ = 0;
371  }
373  locomotor_.publishTwist(new_command);
374 
375  nav_2d_msgs::Pose2DStamped current_pose = locomotor_.getLocalRobotPose();
376 
377  // check to see if we've moved far enough to reset our oscillation timeout
379  {
381  oscillation_pose_ = current_pose.pose;
382 
383  // if our last recovery was caused by oscillation, we want to reset the recovery index
385  {
386  recovery_index_ = 0;
387  }
388  }
389 
390  if (!server_.isActive())
391  {
392  return;
393  }
394 
395  // publish feedback
396  move_base_msgs::MoveBaseFeedback feedback;
397  feedback.base_position = nav_2d_utils::pose2DToPoseStamped(current_pose);
398  server_.publishFeedback(feedback);
399 }
400 
402 {
403  // check if we've tried to find a valid control for longer than our time limit
405  {
407  recovery();
408  }
409  else
410  {
411  ROS_WARN_NAMED("Locomotor", "Local planning error. Creating new global plan.");
414  planning_retries_ = 0;
416  }
417 }
418 
420 {
421  ROS_INFO_NAMED("Locomotor", "Plan completed! Stopping.");
422  if (server_.isActive())
423  {
425  }
428 }
429 
430 void LocoMoveBase::onNavigationFailure(const locomotor_msgs::ResultCode result)
431 {
432  if (server_.isActive())
433  {
435  }
438 }
439 
441 {
442  ROS_DEBUG_NAMED("locomotor", "In clearing/recovery state");
443 
444  // we'll invoke whatever recovery behavior we're currently on if they're enabled
446  {
447  ROS_DEBUG_NAMED("locomotor_recovery", "Executing behavior %u of %zu",
449  recovery_behaviors_[recovery_index_]->runBehavior();
450 
451  // we'll check if the recovery behavior actually worked
452  // ROS_DEBUG_NAMED("locomotor_recovery","Going back to planning state");
455 
456  // we at least want to give the robot some time to stop oscillating after executing the behavior
459  planning_retries_ = 0;
460 
461  // update the index of the next recovery behavior that we'll try
462  recovery_index_++;
463  }
464  else
465  {
466  ROS_DEBUG_NAMED("locomotor_recovery",
467  "All recovery behaviors have failed, locking the planner and disabling it.");
468 
470  {
471  ROS_ERROR("Aborting because a valid control could not be found."
472  "Even after executing all recovery behaviors");
473  requestNavigationFailure(locomotor::makeResultCode(locomotor_msgs::ResultCode::LOCAL_PLANNER, CONTROLLING_R,
474  "Failed to find a valid control. Even after executing recovery behaviors."));
475  }
476  else if (recovery_trigger_ == PLANNING_R)
477  {
478  ROS_ERROR("Aborting because a valid plan could not be found. Even after executing all recovery behaviors");
479  requestNavigationFailure(locomotor::makeResultCode(locomotor_msgs::ResultCode::GLOBAL_PLANNER, PLANNING_R,
480  "Failed to find a valid plan. Even after executing recovery behaviors."));
481  }
482  else if (recovery_trigger_ == OSCILLATION_R)
483  {
484  ROS_ERROR("Aborting because the robot appears to be oscillating over and over."
485  "Even after executing all recovery behaviors");
486  requestNavigationFailure(locomotor::makeResultCode(locomotor_msgs::ResultCode::LOCAL_PLANNER, OSCILLATION_R,
487  "Robot is oscillating. Even after executing recovery behaviors."));
488  }
489  }
490 }
491 
493 {
494  XmlRpc::XmlRpcValue behavior_list;
495  if (!node.getParam("recovery_behaviors", behavior_list))
496  {
497  // if no recovery_behaviors are specified, we'll just load the defaults
498  return false;
499  }
500 
501  if (behavior_list.getType() != XmlRpc::XmlRpcValue::TypeArray)
502  {
503  ROS_ERROR("The recovery behavior specification must be a list, but is of XmlRpcType %d. "
504  "We'll use the default recovery behaviors instead.",
505  behavior_list.getType());
506  return false;
507  }
508 
509  for (int i = 0; i < behavior_list.size(); ++i)
510  {
511  if (behavior_list[i].getType() != XmlRpc::XmlRpcValue::TypeStruct)
512  {
513  ROS_ERROR("Recovery behaviors must be specified as maps, but they are XmlRpcType %d. "
514  "We'll use the default recovery behaviors instead.",
515  behavior_list[i].getType());
516  return false;
517  }
518 
519  if (!behavior_list[i].hasMember("name") || !behavior_list[i].hasMember("type"))
520  {
521  ROS_ERROR("Recovery behaviors must have a name and a type and this does not. "
522  "Using the default recovery behaviors instead.");
523  return false;
524  }
525 
526  // check for recovery behaviors with the same name
527  std::string name_i = behavior_list[i]["name"];
528  for (int j = i + 1; j < behavior_list.size(); j++)
529  {
530  if (behavior_list[j].getType() != XmlRpc::XmlRpcValue::TypeStruct || !behavior_list[j].hasMember("name"))
531  {
532  continue;
533  }
534 
535  std::string name_j = behavior_list[j]["name"];
536  if (name_i == name_j)
537  {
538  ROS_ERROR("A recovery behavior with the name %s already exists, "
539  "this is not allowed. Using the default recovery behaviors instead.",
540  name_i.c_str());
541  return false;
542  }
543  }
544  }
545 
547  // if we've made it to this point, we know that the list is legal so we'll create all the recovery behaviors
548  for (int i = 0; i < behavior_list.size(); ++i)
549  {
550  try
551  {
553 
554  // shouldn't be possible, but it won't hurt to check
555  if (behavior.get() == nullptr)
556  {
557  ROS_ERROR("The ClassLoader returned a null pointer without throwing an exception. "
558  "This should not happen");
559  return false;
560  }
561 
562  // initialize the recovery behavior with its name
563  behavior->initialize(behavior_list[i]["name"], tf.get(), planner_costmap_ros_, controller_costmap_ros_);
564  recovery_behaviors_.push_back(behavior);
565  }
567  {
568  ROS_ERROR("Failed to load a plugin. Using default recovery behaviors. Error: %s", ex.what());
569  return false;
570  }
571  }
572  // if we've made it here... we've constructed a recovery behavior list successfully
573  return true;
574 }
575 
576 // we'll load our default recovery behaviors here
578 {
579  recovery_behaviors_.clear();
580  // Transform shared pointers to raw pointers for backwards compatibility with the recovery behaviors
582  try
583  {
584  // we need to set some parameters based on what's been passed in to us to maintain backwards compatibility
585  ros::NodeHandle n("~");
586 
587  // first, we'll load a recovery behavior to clear the costmap
589  recovery_loader_.createInstance("clear_costmap_recovery/ClearCostmapRecovery"));
590  cons_clear->initialize("conservative_reset", tf.get(), planner_costmap_ros_, controller_costmap_ros_);
591  recovery_behaviors_.push_back(cons_clear);
592 
593  // next, we'll load a recovery behavior to rotate in place
594  bool clearing_rotation_allowed;
595  n.param("clearing_rotation_allowed", clearing_rotation_allowed, true);
596 
598  recovery_loader_.createInstance("rotate_recovery/RotateRecovery"));
599  if (clearing_rotation_allowed)
600  {
601  rotate->initialize("rotate_recovery", tf.get(), planner_costmap_ros_, controller_costmap_ros_);
602  recovery_behaviors_.push_back(rotate);
603  }
604 
605  // next, we'll load a recovery behavior that will do an aggressive reset of the costmap
607  recovery_loader_.createInstance("clear_costmap_recovery/ClearCostmapRecovery"));
608  ags_clear->initialize("aggressive_reset", tf.get(), planner_costmap_ros_, controller_costmap_ros_);
609  recovery_behaviors_.push_back(ags_clear);
610 
611  // we'll rotate in-place one more time
612  if (clearing_rotation_allowed)
613  recovery_behaviors_.push_back(rotate);
614  }
616  {
617  ROS_FATAL("Failed to load a plugin. This should not happen on default recovery behaviors. Error: %s",
618  ex.what());
619  }
620 
621  return;
622 }
623 
624 void LocoMoveBase::goalCB(const geometry_msgs::PoseStamped::ConstPtr& goal)
625 {
627 }
628 
630 {
631  auto move_base_goal = server_.acceptNewGoal();
632  setGoal(nav_2d_utils::poseStampedToPose2D(move_base_goal->target_pose));
633 }
634 
636 {
637  ROS_INFO("Preempting goal");
640  resetState();
642 }
643 
644 } // namespace locomove_base
645 
646 int main(int argc, char** argv)
647 {
648  ros::init(argc, argv, "move_base");
649  ros::NodeHandle nh("~");
651  ros::spin();
652  return 0;
653 }
locomove_base::LocoMoveBase::desired_control_duration_
ros::Duration desired_control_duration_
Definition: locomove_base.h:118
XmlRpc::XmlRpcValue::size
int size() const
locomove_base
Definition: locomove_base.h:45
locomotor::Locomotor::initializeLocalPlanners
void initializeLocalPlanners(Executor &ex)
locomove_base::PLANNING_R
@ PLANNING_R
Definition: locomove_base.h:49
ros::NodeHandle::setParam
void setParam(const std::string &key, bool b) const
locomove_base::LocoMoveBase::onNewLocalPlan
void onNewLocalPlan(nav_2d_msgs::Twist2DStamped new_command, const ros::Duration &planning_time)
Definition: locomove_base.cpp:366
locomove_base::LocoMoveBase::plan_loop_timer_
ros::Timer plan_loop_timer_
Definition: locomove_base.h:119
locomove_base::LocoMoveBase::LocoMoveBase
LocoMoveBase(const ros::NodeHandle &nh)
Definition: locomove_base.cpp:154
locomotor::Locomotor::getTFListener
TFListenerPtr getTFListener() const
boost::shared_ptr
locomove_base::LocoMoveBase::recovery
void recovery()
Definition: locomove_base.cpp:440
locomove_base::LocoMoveBase::loadRecoveryBehaviors
bool loadRecoveryBehaviors(ros::NodeHandle node)
Load the recovery behaviors for the navigation stack from the parameter server.
Definition: locomove_base.cpp:492
locomove_base::LocoMoveBase::controller_frequency_
double controller_frequency_
Definition: locomove_base.h:117
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
locomove_base::LocoMoveBase::planner_costmap_ros_
costmap_2d::Costmap2DROS * planner_costmap_ros_
Definition: locomove_base.h:138
actionlib::SimpleActionServer::start
void start()
locomotor::Locomotor::requestLocalPlan
void requestLocalPlan(Executor &work_ex, Executor &result_ex, LocalPlanCallback cb=nullptr, PlannerExceptionCallback fail_cb=nullptr, NavigationCompleteCallback complete_cb=nullptr)
locomove_base::LocoMoveBase::oscillation_distance_
double oscillation_distance_
Definition: locomove_base.h:132
locomotor::Locomotor::initializeGlobalPlanners
void initializeGlobalPlanners(Executor &ex)
s
XmlRpcServer s
ros
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
locomotor::Locomotor::setGoal
virtual void setGoal(nav_2d_msgs::Pose2DStamped goal)
locomove_base::LocoMoveBase::goal_sub_
ros::Subscriber goal_sub_
Definition: locomove_base.h:102
locomove_base::LocoMoveBase::planner_frequency_
double planner_frequency_
Definition: locomove_base.h:117
locomove_base::LocoMoveBase::loadDefaultRecoveryBehaviors
void loadDefaultRecoveryBehaviors()
Loads the default recovery behaviors for the navigation stack.
Definition: locomove_base.cpp:577
locomotor
locomove_base::LocoMoveBase::planLoopCallback
void planLoopCallback(const ros::TimerEvent &event)
Definition: locomove_base.cpp:268
locomove_base::loadBackwardsCompatibleParameters
const ros::NodeHandle & loadBackwardsCompatibleParameters(const ros::NodeHandle &nh)
Copy parameter values to get backwards compatibility.
Definition: locomove_base.cpp:66
locomotor::Locomotor::getLocalRobotPose
nav_2d_msgs::Pose2DStamped getLocalRobotPose() const
locomove_base::LocoMoveBase::recovery_behaviors_
std::vector< boost::shared_ptr< nav_core::RecoveryBehavior > > recovery_behaviors_
Definition: locomove_base.h:112
locomotor::Locomotor::requestLocalCostmapUpdate
void requestLocalCostmapUpdate(Executor &work_ex, Executor &result_ex, CostmapUpdateCallback cb=nullptr, CostmapUpdateExceptionCallback fail_cb=nullptr)
ros::Timer::stop
void stop()
locomove_base::LocoMoveBase::getCostmapPointer
costmap_2d::Costmap2DROS * getCostmapPointer(const nav_core2::Costmap::Ptr &costmap)
Definition: locomove_base.cpp:230
locomove_base::LocoMoveBase::control_loop_timer_
ros::Timer control_loop_timer_
Definition: locomove_base.h:119
locomove_base::LocoMoveBase::onLocalCostmapUpdate
void onLocalCostmapUpdate(const ros::Duration &planning_time)
Definition: locomove_base.cpp:343
locomove_base::LocoMoveBase::last_valid_plan_
ros::Time last_valid_plan_
Definition: locomove_base.h:127
locomove_base::LocoMoveBase::executeCB
void executeCB()
Definition: locomove_base.cpp:629
locomove_base::LocoMoveBase::requestNavigationFailure
void requestNavigationFailure(const locomotor_msgs::ResultCode &result)
Definition: locomove_base.cpp:262
locomove_base::LocoMoveBase::onNavigationCompleted
void onNavigationCompleted()
Definition: locomove_base.cpp:419
locomove_base::LocoMoveBase::global_planning_ex_
locomotor::Executor global_planning_ex_
Definition: locomove_base.h:122
locomove_base::LocoMoveBase::oscillation_timeout_
double oscillation_timeout_
Definition: locomove_base.h:132
locomove_base::LocoMoveBase::resetState
void resetState()
Definition: locomove_base.cpp:243
ROS_FATAL_NAMED
#define ROS_FATAL_NAMED(name,...)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
actionlib::SimpleActionServer::publishFeedback
void publishFeedback(const Feedback &feedback)
actionlib::SimpleActionServer::setSucceeded
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
locomove_base::LocoMoveBase::server_
actionlib::SimpleActionServer< move_base_msgs::MoveBaseAction > server_
Definition: locomove_base.h:107
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
locomove_base::LocoMoveBase::onNavigationFailure
void onNavigationFailure(const locomotor_msgs::ResultCode result)
Definition: locomove_base.cpp:430
locomove_base::LocoMoveBase::recovery_loader_
pluginlib::ClassLoader< nav_core::RecoveryBehavior > recovery_loader_
Definition: locomove_base.h:111
XmlRpc::XmlRpcValue::TypeStruct
TypeStruct
locomotor::Locomotor::initializeLocalCostmap
void initializeLocalCostmap(Executor &ex)
locomotor::Locomotor::initializeGlobalCostmap
void initializeGlobalCostmap(Executor &ex)
locomotor::Locomotor::getLocalCostmap
nav_core2::Costmap::Ptr getLocalCostmap() const
nav_2d_utils::pose2DToPoseStamped
geometry_msgs::PoseStamped pose2DToPoseStamped(const geometry_msgs::Pose2D &pose2d, const std::string &frame, const ros::Time &stamp)
pluginlib::PluginlibException
nav_core2::NavCore2ExceptionPtr
std::exception_ptr NavCore2ExceptionPtr
locomotor::Locomotor::publishTwist
void publishTwist(const nav_2d_msgs::Twist2DStamped &command)
locomove_base::LocoMoveBase::last_valid_control_
ros::Time last_valid_control_
Definition: locomove_base.h:127
locomove_base::LocoMoveBase::controller_costmap_ros_
costmap_2d::Costmap2DROS * controller_costmap_ros_
Definition: locomove_base.h:139
nav_2d_utils::poseStampedToPose2D
nav_2d_msgs::Pose2DStamped poseStampedToPose2D(const geometry_msgs::PoseStamped &pose)
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
locomove_base::LocoMoveBase::onGlobalCostmapUpdate
void onGlobalCostmapUpdate(const ros::Duration &planning_time)
Definition: locomove_base.cpp:280
locomove_base::LocoMoveBase::onGlobalCostmapException
void onGlobalCostmapException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration &planning_time)
Definition: locomove_base.cpp:288
locomove_base::LocoMoveBase::controlLoopCallback
void controlLoopCallback(const ros::TimerEvent &event)
Definition: locomove_base.cpp:336
locomove_base::LocoMoveBase::onNewGlobalPlan
void onNewGlobalPlan(nav_2d_msgs::Path2D new_global_plan, const ros::Duration &planning_time)
Definition: locomove_base.cpp:298
locomotor::Locomotor::publishPath
void publishPath(const nav_2d_msgs::Path2D &global_plan)
locomove_base::LocoMoveBase::max_planning_retries_
int max_planning_retries_
Definition: locomove_base.h:128
locomove_base::LocoMoveBase::has_global_plan_
bool has_global_plan_
Definition: locomove_base.h:125
nav_core2::LocalPlanner::setPlan
virtual void setPlan(const nav_2d_msgs::Path2D &path)=0
locomove_base::LocoMoveBase::goal_pub_
ros::Publisher goal_pub_
Definition: locomove_base.h:142
actionlib::SimpleActionServer::isActive
bool isActive()
locomove_base::LocoMoveBase::local_planning_ex_
locomotor::Executor local_planning_ex_
Definition: locomove_base.h:122
locomove_base::getNamespace
std::string getNamespace(const std::string &s)
Reimplementation of ClassLoader::getName without needing a ClassLoader.
Definition: locomove_base.cpp:50
locomove_base::LocoMoveBase::onGlobalPlanningException
void onGlobalPlanningException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration &planning_time)
Definition: locomove_base.cpp:318
locomotor::Locomotor::requestNavigationFailure
void requestNavigationFailure(Executor &result_ex, const locomotor_msgs::ResultCode &result, NavigationFailureCallback cb=nullptr)
locomove_base::LocoMoveBase::recovery_index_
unsigned int recovery_index_
Definition: locomove_base.h:113
locomove_base::LocoMoveBase::preemptCB
void preemptCB()
Definition: locomove_base.cpp:635
locomove_base::LocoMoveBase::planner_patience_
double planner_patience_
Definition: locomove_base.h:126
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
actionlib::SimpleActionServer::registerPreemptCallback
void registerPreemptCallback(boost::function< void()> cb)
goal
goal
nav_2d_utils::poseDistance
double poseDistance(const geometry_msgs::Pose2D &pose0, const geometry_msgs::Pose2D &pose1)
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ros::TimerEvent
locomove_base::LocoMoveBase::last_oscillation_reset_
ros::Time last_oscillation_reset_
Definition: locomove_base.h:133
actionlib::SimpleActionServer::setPreempted
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
XmlRpc::XmlRpcValue::getType
const Type & getType() const
locomove_base::LocoMoveBase::requestGlobalCostmapUpdate
void requestGlobalCostmapUpdate()
Definition: locomove_base.cpp:273
ROS_FATAL
#define ROS_FATAL(...)
main
int main(int argc, char **argv)
Definition: locomove_base.cpp:646
XmlRpc::XmlRpcValue::TypeArray
TypeArray
locomove_base::LocoMoveBase::recovery_behavior_enabled_
bool recovery_behavior_enabled_
Definition: locomove_base.h:114
locomotor::Locomotor::getCurrentLocalPlanner
nav_core2::LocalPlanner & getCurrentLocalPlanner()
locomove_base::LocoMoveBase::controller_patience_
double controller_patience_
Definition: locomove_base.h:126
actionlib::SimpleActionServer::registerGoalCallback
void registerGoalCallback(boost::function< void()> cb)
locomove_base::LocoMoveBase::oscillation_pose_
geometry_msgs::Pose2D oscillation_pose_
Definition: locomove_base.h:134
nav_core2::Costmap::Ptr
std::shared_ptr< Costmap > Ptr
locomove_base::LocoMoveBase::recovery_trigger_
RecoveryTrigger recovery_trigger_
Definition: locomove_base.h:110
pluginlib::ClassLoader::createInstance
boost::shared_ptr< T > createInstance(const std::string &lookup_name)
actionlib::SimpleActionServer::setAborted
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
locomotor::Locomotor::getGlobalCostmap
nav_core2::Costmap::Ptr getGlobalCostmap() const
actionlib::SimpleActionServer::acceptNewGoal
boost::shared_ptr< const Goal > acceptNewGoal()
TFListenerPtr
std::shared_ptr< tf2_ros::Buffer > TFListenerPtr
locomotor::Locomotor::requestGlobalCostmapUpdate
void requestGlobalCostmapUpdate(Executor &work_ex, Executor &result_ex, CostmapUpdateCallback cb=nullptr, CostmapUpdateExceptionCallback fail_cb=nullptr)
ROS_ERROR
#define ROS_ERROR(...)
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
locomove_base::LocoMoveBase::planning_retries_
int planning_retries_
Definition: locomove_base.h:129
conversions.h
locomove_base::LocoMoveBase::desired_plan_duration_
ros::Duration desired_plan_duration_
Definition: locomove_base.h:118
ros::spin
ROSCPP_DECL void spin()
tf
locomove_base::LocoMoveBase::locomotor_
locomotor::Locomotor locomotor_
Definition: locomove_base.h:98
locomove_base::LocoMoveBase::setGoal
void setGoal(nav_2d_msgs::Pose2DStamped goal)
Definition: locomove_base.cpp:215
DurationBase< Duration >::toSec
double toSec() const
ros::Timer::start
void start()
locomove_base::LocoMoveBase::private_nh_
ros::NodeHandle private_nh_
Definition: locomove_base.h:97
locomove_base.h
ROS_INFO
#define ROS_INFO(...)
locomove_base::LocoMoveBase::onLocalCostmapException
void onLocalCostmapException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration &planning_time)
Definition: locomove_base.cpp:359
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
locomotor::makeResultCode
locomotor_msgs::ResultCode makeResultCode(int component=-1, int result_code=-1, const std::string &message="")
ros::Duration
locomotor::Locomotor::requestGlobalPlan
void requestGlobalPlan(Executor &work_ex, Executor &result_ex, GlobalPlanCallback cb=nullptr, PlannerExceptionCallback fail_cb=nullptr)
locomove_base::LocoMoveBase::onLocalPlanningException
void onLocalPlanningException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration &planning_time)
Definition: locomove_base.cpp:401
locomove_base::CONTROLLING_R
@ CONTROLLING_R
Definition: locomove_base.h:49
costmap_2d::Costmap2DROS
locomove_base::LocoMoveBase::goalCB
void goalCB(const geometry_msgs::PoseStamped::ConstPtr &goal)
Definition: locomove_base.cpp:624
locomove_base::LocoMoveBase::publishZeroVelocity
void publishZeroVelocity()
Definition: locomove_base.cpp:257
XmlRpc::XmlRpcValue
locomove_base::OSCILLATION_R
@ OSCILLATION_R
Definition: locomove_base.h:49
ros::NodeHandle
ros::Time::now
static Time now()
costmap_adapter.h
path_ops.h
locomove_base::LocoMoveBase
Definition: locomove_base.h:52


locomove_base
Author(s):
autogenerated on Sun May 18 2025 02:47:39