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.header.stamp = pose.header.stamp;
294  goal_pose.pose = global_plan_.poses.back().pose;
295  nav2_util::transformPoseInTargetFrame(
296  goal_pose, goal_pose, *tf_,
297  costmap_ros_->getGlobalFrameID(), transform_tolerance_);
298 }
299 
300 nav_2d_msgs::msg::Twist2DStamped
302  const geometry_msgs::msg::PoseStamped & pose,
303  const nav_2d_msgs::msg::Twist2D & velocity,
304  std::shared_ptr<dwb_msgs::msg::LocalPlanEvaluation> & results)
305 {
306  if (results) {
307  results->header.frame_id = pose.header.frame_id;
308  results->header.stamp = clock_->now();
309  }
310 
311  nav_msgs::msg::Path transformed_plan;
312  geometry_msgs::msg::PoseStamped goal_pose;
313 
314  prepareGlobalPlan(pose, transformed_plan, goal_pose);
315 
316  nav2_costmap_2d::Costmap2D * costmap = costmap_ros_->getCostmap();
317  std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));
318 
319  for (TrajectoryCritic::Ptr & critic : critics_) {
320  if (!critic->prepare(pose.pose, velocity, goal_pose.pose, transformed_plan)) {
321  RCLCPP_WARN(rclcpp::get_logger("DWBLocalPlanner"), "A scoring function failed to prepare");
322  }
323  }
324 
325  try {
326  dwb_msgs::msg::TrajectoryScore best = coreScoringAlgorithm(pose.pose, velocity, results);
327 
328  // Return Value
329  nav_2d_msgs::msg::Twist2DStamped cmd_vel;
330  cmd_vel.header.stamp = clock_->now();
331  cmd_vel.velocity = best.traj.velocity;
332 
333  // debrief stateful scoring functions
334  for (TrajectoryCritic::Ptr & critic : critics_) {
335  critic->debrief(cmd_vel.velocity);
336  }
337 
338  lock.unlock();
339 
340  pub_->publishLocalPlan(pose.header, best.traj);
341  pub_->publishCostGrid(costmap_ros_, critics_);
342 
343  return cmd_vel;
344  } catch (const dwb_core::NoLegalTrajectoriesException & e) {
345  nav_2d_msgs::msg::Twist2D empty_cmd;
346  dwb_msgs::msg::Trajectory2D empty_traj;
347  // debrief stateful scoring functions
348  for (TrajectoryCritic::Ptr & critic : critics_) {
349  critic->debrief(empty_cmd);
350  }
351 
352  lock.unlock();
353 
354  pub_->publishLocalPlan(pose.header, empty_traj);
355  pub_->publishCostGrid(costmap_ros_, critics_);
356 
358  "Could not find a legal trajectory: " +
359  std::string(e.what()));
360  }
361 }
362 
363 dwb_msgs::msg::TrajectoryScore
365  const geometry_msgs::msg::Pose & pose,
366  const nav_2d_msgs::msg::Twist2D velocity,
367  std::shared_ptr<dwb_msgs::msg::LocalPlanEvaluation> & results)
368 {
369  nav_2d_msgs::msg::Twist2D twist;
370  dwb_msgs::msg::Trajectory2D traj;
371  dwb_msgs::msg::TrajectoryScore best, worst;
372  best.total = -1;
373  worst.total = -1;
374  IllegalTrajectoryTracker tracker;
375 
376  traj_generator_->startNewIteration(velocity);
377  while (traj_generator_->hasMoreTwists()) {
378  twist = traj_generator_->nextTwist();
379  traj = traj_generator_->generateTrajectory(pose, velocity, twist);
380 
381  try {
382  dwb_msgs::msg::TrajectoryScore score = scoreTrajectory(traj, best.total);
383  tracker.addLegalTrajectory();
384  if (results) {
385  results->twists.push_back(score);
386  }
387  if (best.total < 0 || score.total < best.total) {
388  best = score;
389  if (results) {
390  results->best_index = results->twists.size() - 1;
391  }
392  }
393  if (worst.total < 0 || score.total > worst.total) {
394  worst = score;
395  if (results) {
396  results->worst_index = results->twists.size() - 1;
397  }
398  }
399  } catch (const dwb_core::IllegalTrajectoryException & e) {
400  if (results) {
401  dwb_msgs::msg::TrajectoryScore failed_score;
402  failed_score.traj = traj;
403 
404  dwb_msgs::msg::CriticScore cs;
405  cs.name = e.getCriticName();
406  cs.raw_score = -1.0;
407  failed_score.scores.push_back(cs);
408  failed_score.total = -1.0;
409  results->twists.push_back(failed_score);
410  }
411  tracker.addIllegalTrajectory(e);
412  }
413  }
414 
415  if (best.total < 0) {
416  if (debug_trajectory_details_) {
417  RCLCPP_ERROR(rclcpp::get_logger("DWBLocalPlanner"), "%s", tracker.getMessage().c_str());
418  for (auto const & x : tracker.getPercentages()) {
419  RCLCPP_ERROR(
420  rclcpp::get_logger(
421  "DWBLocalPlanner"), "%.2f: %10s/%s", x.second,
422  x.first.first.c_str(), x.first.second.c_str());
423  }
424  }
425  throw NoLegalTrajectoriesException(tracker);
426  }
427 
428  return best;
429 }
430 
431 dwb_msgs::msg::TrajectoryScore
433  const dwb_msgs::msg::Trajectory2D & traj,
434  double best_score)
435 {
436  dwb_msgs::msg::TrajectoryScore score;
437  score.traj = traj;
438 
439  for (TrajectoryCritic::Ptr & critic : critics_) {
440  dwb_msgs::msg::CriticScore cs;
441  cs.name = critic->getName();
442  cs.scale = critic->getScale();
443 
444  if (cs.scale == 0.0) {
445  score.scores.push_back(cs);
446  continue;
447  }
448 
449  double critic_score = critic->scoreTrajectory(traj);
450  cs.raw_score = critic_score;
451  score.scores.push_back(cs);
452  score.total += critic_score * cs.scale;
453  if (short_circuit_trajectory_evaluation_ && best_score > 0 && score.total > best_score) {
454  // since we keep adding positives, once we are worse than the best, we will stay worse
455  break;
456  }
457  }
458 
459  return score;
460 }
461 
462 nav_msgs::msg::Path
464  const geometry_msgs::msg::PoseStamped & pose)
465 {
466  if (global_plan_.poses.empty()) {
467  throw nav2_core::InvalidPath("Received plan with zero length");
468  }
469 
470  // let's get the pose of the robot in the frame of the plan
471  geometry_msgs::msg::PoseStamped robot_pose;
472  if (!nav2_util::transformPoseInTargetFrame(
473  pose, robot_pose, *tf_,
474  global_plan_.header.frame_id, transform_tolerance_))
475  {
476  throw nav2_core::
477  ControllerTFError("Unable to transform robot pose into global plan's frame");
478  }
479 
480  // we'll discard points on the plan that are outside the local costmap
481  nav2_costmap_2d::Costmap2D * costmap = costmap_ros_->getCostmap();
482  double dist_threshold = std::max(costmap->getSizeInCellsX(), costmap->getSizeInCellsY()) *
483  costmap->getResolution() / 2.0;
484 
485  // If prune_plan is enabled (it is by default) then we want to restrict the
486  // plan to distances within that range as well.
487  double prune_dist = prune_distance_;
488 
489  // Set the maximum distance we'll include points before getting to the part
490  // of the path where the robot is located (the start of the plan). Basically,
491  // these are the points the robot has already passed.
492  double transform_start_threshold;
493  if (prune_plan_) {
494  transform_start_threshold = std::min(dist_threshold, prune_dist);
495  } else {
496  transform_start_threshold = dist_threshold;
497  }
498 
499  // Set the maximum distance we'll include points after the part of the plan
500  // near the robot (the end of the plan). This determines the amount of the
501  // plan passed on to the critics
502  double transform_end_threshold;
503  double forward_prune_dist = forward_prune_distance_;
504  if (shorten_transformed_plan_) {
505  transform_end_threshold = std::min(dist_threshold, forward_prune_dist);
506  } else {
507  transform_end_threshold = dist_threshold;
508  }
509 
510  // Find the first pose in the global plan that's further than forward prune distance
511  // from the robot using integrated distance
512  auto prune_point = nav2_util::geometry_utils::first_after_integrated_distance(
513  global_plan_.poses.begin(), global_plan_.poses.end(), forward_prune_distance_);
514 
515  // Find the first pose in the plan (up to prune_point) that's less than transform_start_threshold
516  // from the robot.
517  auto transformation_begin = std::find_if(
518  begin(global_plan_.poses), prune_point,
519  [&](const auto & global_plan_pose) {
520  return euclidean_distance(robot_pose, global_plan_pose) < transform_start_threshold;
521  });
522 
523  // Find the first pose in the end of the plan that's further than transform_end_threshold
524  // from the robot using integrated distance
525  auto transformation_end = std::find_if(
526  transformation_begin, global_plan_.poses.end(),
527  [&](const auto & global_plan_pose) {
528  return euclidean_distance(global_plan_pose, robot_pose) > transform_end_threshold;
529  });
530 
531  // Transform the near part of the global plan into the robot's frame of reference.
532  nav_msgs::msg::Path transformed_plan;
533  transformed_plan.header.frame_id = costmap_ros_->getGlobalFrameID();
534  transformed_plan.header.stamp = pose.header.stamp;
535 
536  // Helper function for the transform below. Converts a pose2D from global
537  // frame to local
538  auto transformGlobalPoseToLocal = [&](const auto & global_plan_pose) {
539  geometry_msgs::msg::PoseStamped stamped_pose, transformed_pose;
540  stamped_pose.header.frame_id = global_plan_.header.frame_id;
541  stamped_pose.header.stamp = robot_pose.header.stamp;
542  stamped_pose.pose = global_plan_pose.pose;
543  if (!nav2_util::transformPoseInTargetFrame(
544  stamped_pose, transformed_pose, *tf_,
545  transformed_plan.header.frame_id, transform_tolerance_))
546  {
547  throw nav2_core::ControllerTFError("Unable to transform plan pose into local frame");
548  }
549  transformed_pose.pose.position.z = 0.0;
550  return transformed_pose;
551  };
552 
553  std::transform(
554  transformation_begin, transformation_end,
555  std::back_inserter(transformed_plan.poses),
556  transformGlobalPoseToLocal);
557 
558  // Remove the portion of the global plan that we've already passed so we don't
559  // process it on the next iteration.
560  if (prune_plan_) {
561  global_plan_.poses.erase(begin(global_plan_.poses), transformation_begin);
562  pub_->publishGlobalPlan(global_plan_);
563  }
564 
565  if (transformed_plan.poses.empty()) {
566  throw nav2_core::InvalidPath("Resulting plan has 0 poses in it.");
567  }
568  return transformed_plan;
569 }
570 
571 } // namespace dwb_core
572 
573 // Register this controller as a nav2_core plugin
574 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:578
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:548
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:553