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