Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
dwb_local_planner.cpp
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 
35 #include <algorithm>
36 #include <memory>
37 #include <string>
38 #include <utility>
39 #include <vector>
40 
41 #include "dwb_core/dwb_local_planner.hpp"
42 #include "dwb_core/exceptions.hpp"
43 #include "dwb_core/illegal_trajectory_tracker.hpp"
44 #include "dwb_msgs/msg/critic_score.hpp"
45 #include "nav_2d_msgs/msg/twist2_d.hpp"
46 #include "nav_2d_utils/conversions.hpp"
47 #include "nav_2d_utils/parameters.hpp"
48 #include "nav_2d_utils/tf_help.hpp"
49 #include "nav2_util/geometry_utils.hpp"
50 #include "nav2_util/lifecycle_node.hpp"
51 #include "nav2_util/node_utils.hpp"
52 #include "pluginlib/class_list_macros.hpp"
53 #include "nav_msgs/msg/path.hpp"
54 #include "geometry_msgs/msg/twist_stamped.hpp"
55 
56 using nav2_util::declare_parameter_if_not_declared;
57 using nav2_util::geometry_utils::euclidean_distance;
58 
59 namespace dwb_core
60 {
61 
63 : traj_gen_loader_("dwb_core", "dwb_core::TrajectoryGenerator"),
64  critic_loader_("dwb_core", "dwb_core::TrajectoryCritic")
65 {
66 }
67 
69  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
70  std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
71  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
72 {
73  node_ = parent;
74  auto node = node_.lock();
75 
76  logger_ = node->get_logger();
77  clock_ = node->get_clock();
78  costmap_ros_ = costmap_ros;
79  tf_ = tf;
80  dwb_plugin_name_ = name;
81  declare_parameter_if_not_declared(
82  node, dwb_plugin_name_ + ".critics",
83  rclcpp::PARAMETER_STRING_ARRAY);
84  declare_parameter_if_not_declared(
85  node, dwb_plugin_name_ + ".default_critic_namespaces",
86  rclcpp::ParameterValue(std::vector<std::string>()));
87  declare_parameter_if_not_declared(
88  node, dwb_plugin_name_ + ".prune_plan",
89  rclcpp::ParameterValue(true));
90  declare_parameter_if_not_declared(
91  node, dwb_plugin_name_ + ".prune_distance",
92  rclcpp::ParameterValue(2.0));
93  declare_parameter_if_not_declared(
94  node, dwb_plugin_name_ + ".forward_prune_distance",
95  rclcpp::ParameterValue(2.0));
96  declare_parameter_if_not_declared(
97  node, dwb_plugin_name_ + ".debug_trajectory_details",
98  rclcpp::ParameterValue(false));
99  declare_parameter_if_not_declared(
100  node, dwb_plugin_name_ + ".trajectory_generator_name",
101  rclcpp::ParameterValue(std::string("dwb_plugins::StandardTrajectoryGenerator")));
102  declare_parameter_if_not_declared(
103  node, dwb_plugin_name_ + ".transform_tolerance",
104  rclcpp::ParameterValue(0.1));
105  declare_parameter_if_not_declared(
106  node, dwb_plugin_name_ + ".shorten_transformed_plan",
107  rclcpp::ParameterValue(true));
108  declare_parameter_if_not_declared(
109  node, dwb_plugin_name_ + ".short_circuit_trajectory_evaluation",
110  rclcpp::ParameterValue(true));
111 
112  std::string traj_generator_name;
113 
114  double transform_tolerance;
115  node->get_parameter(dwb_plugin_name_ + ".transform_tolerance", transform_tolerance);
116  transform_tolerance_ = rclcpp::Duration::from_seconds(transform_tolerance);
117  RCLCPP_INFO(logger_, "Setting transform_tolerance to %f", transform_tolerance);
118 
119  node->get_parameter(dwb_plugin_name_ + ".prune_plan", prune_plan_);
120  node->get_parameter(dwb_plugin_name_ + ".prune_distance", prune_distance_);
121  node->get_parameter(dwb_plugin_name_ + ".forward_prune_distance", forward_prune_distance_);
122  node->get_parameter(dwb_plugin_name_ + ".debug_trajectory_details", debug_trajectory_details_);
123  node->get_parameter(dwb_plugin_name_ + ".trajectory_generator_name", traj_generator_name);
124  node->get_parameter(
125  dwb_plugin_name_ + ".short_circuit_trajectory_evaluation",
126  short_circuit_trajectory_evaluation_);
127  node->get_parameter(dwb_plugin_name_ + ".shorten_transformed_plan", shorten_transformed_plan_);
128 
129  pub_ = std::make_unique<DWBPublisher>(node, dwb_plugin_name_);
130  pub_->on_configure();
131 
132  traj_generator_ = traj_gen_loader_.createUniqueInstance(traj_generator_name);
133 
134  traj_generator_->initialize(node, dwb_plugin_name_);
135 
136  try {
137  loadCritics();
138  } catch (const std::exception & e) {
139  RCLCPP_ERROR(logger_, "Couldn't load critics! Caught exception: %s", e.what());
140  throw;
141  }
142 }
143 
144 void
146 {
147  pub_->on_activate();
148 }
149 
150 void
152 {
153  pub_->on_deactivate();
154 }
155 
156 void
158 {
159  pub_->on_cleanup();
160 
161  traj_generator_.reset();
162 }
163 
164 std::string
166 {
167  if (base_name.find("Critic") == std::string::npos) {
168  base_name = base_name + "Critic";
169  }
170 
171  if (base_name.find("::") == std::string::npos) {
172  for (unsigned int j = 0; j < default_critic_namespaces_.size(); j++) {
173  std::string full_name = default_critic_namespaces_[j] + "::" + base_name;
174  if (critic_loader_.isClassAvailable(full_name)) {
175  return full_name;
176  }
177  }
178  }
179  return base_name;
180 }
181 
182 void
184 {
185  auto node = node_.lock();
186  if (!node) {
187  throw std::runtime_error{"Failed to lock node"};
188  }
189 
190  node->get_parameter(dwb_plugin_name_ + ".default_critic_namespaces", default_critic_namespaces_);
191  if (default_critic_namespaces_.empty()) {
192  default_critic_namespaces_.emplace_back("dwb_critics");
193  }
194 
195  std::vector<std::string> critic_names;
196  if (!node->get_parameter(dwb_plugin_name_ + ".critics", critic_names)) {
197  throw std::runtime_error("No critics defined for " + dwb_plugin_name_);
198  }
199 
200  node->get_parameter(dwb_plugin_name_ + ".critics", critic_names);
201  for (unsigned int i = 0; i < critic_names.size(); i++) {
202  std::string critic_plugin_name = critic_names[i];
203  std::string plugin_class;
204 
205  declare_parameter_if_not_declared(
206  node, dwb_plugin_name_ + "." + critic_plugin_name + ".class",
207  rclcpp::ParameterValue(critic_plugin_name));
208  node->get_parameter(dwb_plugin_name_ + "." + critic_plugin_name + ".class", plugin_class);
209 
210  plugin_class = resolveCriticClassName(plugin_class);
211 
212  TrajectoryCritic::Ptr plugin = critic_loader_.createUniqueInstance(plugin_class);
213  RCLCPP_INFO(
214  logger_,
215  "Using critic \"%s\" (%s)", critic_plugin_name.c_str(), plugin_class.c_str());
216  critics_.push_back(plugin);
217  try {
218  plugin->initialize(node, critic_plugin_name, dwb_plugin_name_, costmap_ros_);
219  } catch (const std::exception & e) {
220  RCLCPP_ERROR(logger_, "Couldn't initialize critic plugin!");
221  throw;
222  }
223  RCLCPP_INFO(logger_, "Critic plugin initialized");
224  }
225 }
226 
227 void
228 DWBLocalPlanner::setPlan(const nav_msgs::msg::Path & path)
229 {
230  auto path2d = nav_2d_utils::pathToPath2D(path);
231  for (TrajectoryCritic::Ptr & critic : critics_) {
232  critic->reset();
233  }
234 
235  traj_generator_->reset();
236 
237  pub_->publishGlobalPlan(path2d);
238  global_plan_ = path2d;
239 }
240 
241 geometry_msgs::msg::TwistStamped
243  const geometry_msgs::msg::PoseStamped & pose,
244  const geometry_msgs::msg::Twist & velocity,
245  nav2_core::GoalChecker * /*goal_checker*/)
246 {
247  std::shared_ptr<dwb_msgs::msg::LocalPlanEvaluation> results = nullptr;
248  if (pub_->shouldRecordEvaluation()) {
249  results = std::make_shared<dwb_msgs::msg::LocalPlanEvaluation>();
250  }
251 
252  try {
253  nav_2d_msgs::msg::Twist2DStamped cmd_vel2d = computeVelocityCommands(
254  nav_2d_utils::poseStampedToPose2D(pose),
255  nav_2d_utils::twist3Dto2D(velocity), results);
256  pub_->publishEvaluation(results);
257  geometry_msgs::msg::TwistStamped cmd_vel;
258  cmd_vel.twist = nav_2d_utils::twist2Dto3D(cmd_vel2d.velocity);
259  return cmd_vel;
260  } catch (const nav2_core::PlannerException & e) {
261  pub_->publishEvaluation(results);
262  throw;
263  }
264 }
265 
266 void
268  const nav_2d_msgs::msg::Pose2DStamped & pose, nav_2d_msgs::msg::Path2D & transformed_plan,
269  nav_2d_msgs::msg::Pose2DStamped & goal_pose, bool publish_plan)
270 {
271  transformed_plan = transformGlobalPlan(pose);
272  if (publish_plan) {
273  pub_->publishTransformedPlan(transformed_plan);
274  }
275 
276  goal_pose.header.frame_id = global_plan_.header.frame_id;
277  goal_pose.pose = global_plan_.poses.back();
278  nav_2d_utils::transformPose(
279  tf_, costmap_ros_->getGlobalFrameID(), goal_pose,
280  goal_pose, transform_tolerance_);
281 }
282 
283 nav_2d_msgs::msg::Twist2DStamped
285  const nav_2d_msgs::msg::Pose2DStamped & pose,
286  const nav_2d_msgs::msg::Twist2D & velocity,
287  std::shared_ptr<dwb_msgs::msg::LocalPlanEvaluation> & results)
288 {
289  if (results) {
290  results->header.frame_id = pose.header.frame_id;
291  results->header.stamp = clock_->now();
292  }
293 
294  nav_2d_msgs::msg::Path2D transformed_plan;
295  nav_2d_msgs::msg::Pose2DStamped goal_pose;
296 
297  prepareGlobalPlan(pose, transformed_plan, goal_pose);
298 
299  nav2_costmap_2d::Costmap2D * costmap = costmap_ros_->getCostmap();
300  std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));
301 
302  for (TrajectoryCritic::Ptr & critic : critics_) {
303  if (!critic->prepare(pose.pose, velocity, goal_pose.pose, transformed_plan)) {
304  RCLCPP_WARN(rclcpp::get_logger("DWBLocalPlanner"), "A scoring function failed to prepare");
305  }
306  }
307 
308  try {
309  dwb_msgs::msg::TrajectoryScore best = coreScoringAlgorithm(pose.pose, velocity, results);
310 
311  // Return Value
312  nav_2d_msgs::msg::Twist2DStamped cmd_vel;
313  cmd_vel.header.stamp = clock_->now();
314  cmd_vel.velocity = best.traj.velocity;
315 
316  // debrief stateful scoring functions
317  for (TrajectoryCritic::Ptr & critic : critics_) {
318  critic->debrief(cmd_vel.velocity);
319  }
320 
321  lock.unlock();
322 
323  pub_->publishLocalPlan(pose.header, best.traj);
324  pub_->publishCostGrid(costmap_ros_, critics_);
325 
326  return cmd_vel;
327  } catch (const dwb_core::NoLegalTrajectoriesException & e) {
328  nav_2d_msgs::msg::Twist2D empty_cmd;
329  dwb_msgs::msg::Trajectory2D empty_traj;
330  // debrief stateful scoring functions
331  for (TrajectoryCritic::Ptr & critic : critics_) {
332  critic->debrief(empty_cmd);
333  }
334 
335  lock.unlock();
336 
337  pub_->publishLocalPlan(pose.header, empty_traj);
338  pub_->publishCostGrid(costmap_ros_, critics_);
339 
340  throw;
341  }
342 }
343 
344 dwb_msgs::msg::TrajectoryScore
346  const geometry_msgs::msg::Pose2D & pose,
347  const nav_2d_msgs::msg::Twist2D velocity,
348  std::shared_ptr<dwb_msgs::msg::LocalPlanEvaluation> & results)
349 {
350  nav_2d_msgs::msg::Twist2D twist;
351  dwb_msgs::msg::Trajectory2D traj;
352  dwb_msgs::msg::TrajectoryScore best, worst;
353  best.total = -1;
354  worst.total = -1;
355  IllegalTrajectoryTracker tracker;
356 
357  traj_generator_->startNewIteration(velocity);
358  while (traj_generator_->hasMoreTwists()) {
359  twist = traj_generator_->nextTwist();
360  traj = traj_generator_->generateTrajectory(pose, velocity, twist);
361 
362  try {
363  dwb_msgs::msg::TrajectoryScore score = scoreTrajectory(traj, best.total);
364  tracker.addLegalTrajectory();
365  if (results) {
366  results->twists.push_back(score);
367  }
368  if (best.total < 0 || score.total < best.total) {
369  best = score;
370  if (results) {
371  results->best_index = results->twists.size() - 1;
372  }
373  }
374  if (worst.total < 0 || score.total > worst.total) {
375  worst = score;
376  if (results) {
377  results->worst_index = results->twists.size() - 1;
378  }
379  }
380  } catch (const dwb_core::IllegalTrajectoryException & e) {
381  if (results) {
382  dwb_msgs::msg::TrajectoryScore failed_score;
383  failed_score.traj = traj;
384 
385  dwb_msgs::msg::CriticScore cs;
386  cs.name = e.getCriticName();
387  cs.raw_score = -1.0;
388  failed_score.scores.push_back(cs);
389  failed_score.total = -1.0;
390  results->twists.push_back(failed_score);
391  }
392  tracker.addIllegalTrajectory(e);
393  }
394  }
395 
396  if (best.total < 0) {
397  if (debug_trajectory_details_) {
398  RCLCPP_ERROR(rclcpp::get_logger("DWBLocalPlanner"), "%s", tracker.getMessage().c_str());
399  for (auto const & x : tracker.getPercentages()) {
400  RCLCPP_ERROR(
401  rclcpp::get_logger(
402  "DWBLocalPlanner"), "%.2f: %10s/%s", x.second,
403  x.first.first.c_str(), x.first.second.c_str());
404  }
405  }
406  throw NoLegalTrajectoriesException(tracker);
407  }
408 
409  return best;
410 }
411 
412 dwb_msgs::msg::TrajectoryScore
414  const dwb_msgs::msg::Trajectory2D & traj,
415  double best_score)
416 {
417  dwb_msgs::msg::TrajectoryScore score;
418  score.traj = traj;
419 
420  for (TrajectoryCritic::Ptr & critic : critics_) {
421  dwb_msgs::msg::CriticScore cs;
422  cs.name = critic->getName();
423  cs.scale = critic->getScale();
424 
425  if (cs.scale == 0.0) {
426  score.scores.push_back(cs);
427  continue;
428  }
429 
430  double critic_score = critic->scoreTrajectory(traj);
431  cs.raw_score = critic_score;
432  score.scores.push_back(cs);
433  score.total += critic_score * cs.scale;
434  if (short_circuit_trajectory_evaluation_ && best_score > 0 && score.total > best_score) {
435  // since we keep adding positives, once we are worse than the best, we will stay worse
436  break;
437  }
438  }
439 
440  return score;
441 }
442 
443 nav_2d_msgs::msg::Path2D
445  const nav_2d_msgs::msg::Pose2DStamped & pose)
446 {
447  if (global_plan_.poses.empty()) {
448  throw nav2_core::PlannerException("Received plan with zero length");
449  }
450 
451  // let's get the pose of the robot in the frame of the plan
452  nav_2d_msgs::msg::Pose2DStamped robot_pose;
453  if (!nav_2d_utils::transformPose(
454  tf_, global_plan_.header.frame_id, pose,
455  robot_pose, transform_tolerance_))
456  {
457  throw dwb_core::
458  PlannerTFException("Unable to transform robot pose into global plan's frame");
459  }
460 
461  // we'll discard points on the plan that are outside the local costmap
462  nav2_costmap_2d::Costmap2D * costmap = costmap_ros_->getCostmap();
463  double dist_threshold = std::max(costmap->getSizeInCellsX(), costmap->getSizeInCellsY()) *
464  costmap->getResolution() / 2.0;
465 
466  // If prune_plan is enabled (it is by default) then we want to restrict the
467  // plan to distances within that range as well.
468  double prune_dist = prune_distance_;
469 
470  // Set the maximum distance we'll include points before getting to the part
471  // of the path where the robot is located (the start of the plan). Basically,
472  // these are the points the robot has already passed.
473  double transform_start_threshold;
474  if (prune_plan_) {
475  transform_start_threshold = std::min(dist_threshold, prune_dist);
476  } else {
477  transform_start_threshold = dist_threshold;
478  }
479 
480  // Set the maximum distance we'll include points after the part of the plan
481  // near the robot (the end of the plan). This determines the amount of the
482  // plan passed on to the critics
483  double transform_end_threshold;
484  double forward_prune_dist = forward_prune_distance_;
485  if (shorten_transformed_plan_) {
486  transform_end_threshold = std::min(dist_threshold, forward_prune_dist);
487  } else {
488  transform_end_threshold = dist_threshold;
489  }
490 
491  // Find the first pose in the global plan that's further than prune distance
492  // from the robot using integrated distance
493  auto prune_point = nav2_util::geometry_utils::first_after_integrated_distance(
494  global_plan_.poses.begin(), global_plan_.poses.end(), prune_dist);
495 
496  // Find the first pose in the plan (upto prune_point) that's less than transform_start_threshold
497  // from the robot.
498  auto transformation_begin = std::find_if(
499  begin(global_plan_.poses), prune_point,
500  [&](const auto & global_plan_pose) {
501  return euclidean_distance(robot_pose.pose, global_plan_pose) < transform_start_threshold;
502  });
503 
504  // Find the first pose in the end of the plan that's further than transform_end_threshold
505  // from the robot using integrated distance
506  auto transformation_end = std::find_if(
507  transformation_begin, global_plan_.poses.end(),
508  [&](const auto & pose) {
509  return euclidean_distance(pose, robot_pose.pose) > transform_end_threshold;
510  });
511 
512  // Transform the near part of the global plan into the robot's frame of reference.
513  nav_2d_msgs::msg::Path2D transformed_plan;
514  transformed_plan.header.frame_id = costmap_ros_->getGlobalFrameID();
515  transformed_plan.header.stamp = pose.header.stamp;
516 
517  // Helper function for the transform below. Converts a pose2D from global
518  // frame to local
519  auto transformGlobalPoseToLocal = [&](const auto & global_plan_pose) {
520  nav_2d_msgs::msg::Pose2DStamped stamped_pose, transformed_pose;
521  stamped_pose.header.frame_id = global_plan_.header.frame_id;
522  stamped_pose.pose = global_plan_pose;
523  nav_2d_utils::transformPose(
524  tf_, transformed_plan.header.frame_id,
525  stamped_pose, transformed_pose, transform_tolerance_);
526  return transformed_pose.pose;
527  };
528 
529  std::transform(
530  transformation_begin, transformation_end,
531  std::back_inserter(transformed_plan.poses),
532  transformGlobalPoseToLocal);
533 
534  // Remove the portion of the global plan that we've already passed so we don't
535  // process it on the next iteration.
536  if (prune_plan_) {
537  global_plan_.poses.erase(begin(global_plan_.poses), transformation_begin);
538  pub_->publishGlobalPlan(global_plan_);
539  }
540 
541  if (transformed_plan.poses.empty()) {
542  throw nav2_core::PlannerException("Resulting plan has 0 poses in it.");
543  }
544  return transformed_plan;
545 }
546 
547 } // namespace dwb_core
548 
549 // Register this controller as a nav2_core plugin
550 PLUGINLIB_EXPORT_CLASS(
Plugin-based flexible controller.
void cleanup() override
Cleanup lifecycle node.
void setPlan(const nav_msgs::msg::Path &path) override
nav2_core setPlan - Sets the global plan
std::string resolveCriticClassName(std::string base_name)
try to resolve a possibly shortened critic name with the default namespaces and the suffix "Critic"
void deactivate() override
Deactivate lifecycle node.
void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros) override
DWBLocalPlanner()
Constructor that brings up pluginlib loaders.
virtual dwb_msgs::msg::TrajectoryScore coreScoringAlgorithm(const geometry_msgs::msg::Pose2D &pose, const nav_2d_msgs::msg::Twist2D velocity, std::shared_ptr< dwb_msgs::msg::LocalPlanEvaluation > &results)
Iterate through all the twists and find the best one.
virtual dwb_msgs::msg::TrajectoryScore scoreTrajectory(const dwb_msgs::msg::Trajectory2D &traj, double best_score=-1)
Score a given command. Can be used for testing.
void prepareGlobalPlan(const nav_2d_msgs::msg::Pose2DStamped &pose, nav_2d_msgs::msg::Path2D &transformed_plan, nav_2d_msgs::msg::Pose2DStamped &goal_pose, bool publish_plan=true)
Helper method for two common operations for the operating on the global_plan.
geometry_msgs::msg::TwistStamped computeVelocityCommands(const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::Twist &velocity, nav2_core::GoalChecker *) override
nav2_core computeVelocityCommands - calculates the best command given the current pose and velocity
virtual void loadCritics()
Load the critic parameters from the namespace.
void activate() override
Activate lifecycle node.
nav_2d_msgs::msg::Path2D global_plan_
Saved Global Plan.
virtual nav_2d_msgs::msg::Path2D transformGlobalPlan(const nav_2d_msgs::msg::Pose2DStamped &pose)
Transforms global plan into same frame as pose, clips far away poses and possibly prunes passed poses...
Thrown when one of the critics encountered a fatal error.
Definition: exceptions.hpp:62
Thrown when all the trajectories explored are illegal.
controller interface that acts as a virtual base class for all controller plugins
Definition: controller.hpp:61
Function-object for checking whether a goal has been reached.
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:68
double getResolution() const
Accessor for the resolution of the costmap.
Definition: costmap_2d.cpp:531
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:501
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:506