Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
smac_planner_hybrid.cpp
1 // Copyright (c) 2020, Samsung Research America
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License. Reserved.
14 
15 #include <string>
16 #include <memory>
17 #include <vector>
18 #include <algorithm>
19 #include <limits>
20 
21 #include "Eigen/Core"
22 #include "nav2_smac_planner/smac_planner_hybrid.hpp"
23 
24 // #define BENCHMARK_TESTING
25 
26 namespace nav2_smac_planner
27 {
28 
29 using namespace std::chrono; // NOLINT
30 using rcl_interfaces::msg::ParameterType;
31 using std::placeholders::_1;
32 
34 : _a_star(nullptr),
35  _collision_checker(nullptr, 1, nullptr),
36  _smoother(nullptr),
37  _costmap(nullptr),
38  _costmap_downsampler(nullptr)
39 {
40 }
41 
43 {
44  RCLCPP_INFO(
45  _logger, "Destroying plugin %s of type SmacPlannerHybrid",
46  _name.c_str());
47 }
48 
50  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
51  std::string name, std::shared_ptr<tf2_ros::Buffer>/*tf*/,
52  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
53 {
54  _node = parent;
55  auto node = parent.lock();
56  _logger = node->get_logger();
57  _clock = node->get_clock();
58  _costmap = costmap_ros->getCostmap();
59  _costmap_ros = costmap_ros;
60  _name = name;
61  _global_frame = costmap_ros->getGlobalFrameID();
62 
63  RCLCPP_INFO(_logger, "Configuring %s of type SmacPlannerHybrid", name.c_str());
64 
65  int angle_quantizations;
66  double analytic_expansion_max_length_m;
67  bool smooth_path;
68 
69  // General planner params
70  nav2_util::declare_parameter_if_not_declared(
71  node, name + ".downsample_costmap", rclcpp::ParameterValue(false));
72  node->get_parameter(name + ".downsample_costmap", _downsample_costmap);
73  nav2_util::declare_parameter_if_not_declared(
74  node, name + ".downsampling_factor", rclcpp::ParameterValue(1));
75  node->get_parameter(name + ".downsampling_factor", _downsampling_factor);
76 
77  nav2_util::declare_parameter_if_not_declared(
78  node, name + ".angle_quantization_bins", rclcpp::ParameterValue(72));
79  node->get_parameter(name + ".angle_quantization_bins", angle_quantizations);
80  _angle_bin_size = 2.0 * M_PI / angle_quantizations;
81  _angle_quantizations = static_cast<unsigned int>(angle_quantizations);
82 
83  nav2_util::declare_parameter_if_not_declared(
84  node, name + ".tolerance", rclcpp::ParameterValue(0.25));
85  _tolerance = static_cast<float>(node->get_parameter(name + ".tolerance").as_double());
86  nav2_util::declare_parameter_if_not_declared(
87  node, name + ".allow_unknown", rclcpp::ParameterValue(true));
88  node->get_parameter(name + ".allow_unknown", _allow_unknown);
89  nav2_util::declare_parameter_if_not_declared(
90  node, name + ".max_iterations", rclcpp::ParameterValue(1000000));
91  node->get_parameter(name + ".max_iterations", _max_iterations);
92  nav2_util::declare_parameter_if_not_declared(
93  node, name + ".max_on_approach_iterations", rclcpp::ParameterValue(1000));
94  node->get_parameter(name + ".max_on_approach_iterations", _max_on_approach_iterations);
95  nav2_util::declare_parameter_if_not_declared(
96  node, name + ".smooth_path", rclcpp::ParameterValue(true));
97  node->get_parameter(name + ".smooth_path", smooth_path);
98 
99  nav2_util::declare_parameter_if_not_declared(
100  node, name + ".minimum_turning_radius", rclcpp::ParameterValue(0.4));
101  node->get_parameter(name + ".minimum_turning_radius", _minimum_turning_radius_global_coords);
102  nav2_util::declare_parameter_if_not_declared(
103  node, name + ".cache_obstacle_heuristic", rclcpp::ParameterValue(false));
104  node->get_parameter(name + ".cache_obstacle_heuristic", _search_info.cache_obstacle_heuristic);
105  nav2_util::declare_parameter_if_not_declared(
106  node, name + ".reverse_penalty", rclcpp::ParameterValue(2.0));
107  node->get_parameter(name + ".reverse_penalty", _search_info.reverse_penalty);
108  nav2_util::declare_parameter_if_not_declared(
109  node, name + ".change_penalty", rclcpp::ParameterValue(0.0));
110  node->get_parameter(name + ".change_penalty", _search_info.change_penalty);
111  nav2_util::declare_parameter_if_not_declared(
112  node, name + ".non_straight_penalty", rclcpp::ParameterValue(1.2));
113  node->get_parameter(name + ".non_straight_penalty", _search_info.non_straight_penalty);
114  nav2_util::declare_parameter_if_not_declared(
115  node, name + ".cost_penalty", rclcpp::ParameterValue(2.0));
116  node->get_parameter(name + ".cost_penalty", _search_info.cost_penalty);
117  nav2_util::declare_parameter_if_not_declared(
118  node, name + ".retrospective_penalty", rclcpp::ParameterValue(0.015));
119  node->get_parameter(name + ".retrospective_penalty", _search_info.retrospective_penalty);
120  nav2_util::declare_parameter_if_not_declared(
121  node, name + ".analytic_expansion_ratio", rclcpp::ParameterValue(3.5));
122  node->get_parameter(name + ".analytic_expansion_ratio", _search_info.analytic_expansion_ratio);
123  nav2_util::declare_parameter_if_not_declared(
124  node, name + ".analytic_expansion_max_length", rclcpp::ParameterValue(3.0));
125  node->get_parameter(name + ".analytic_expansion_max_length", analytic_expansion_max_length_m);
126  _search_info.analytic_expansion_max_length =
127  analytic_expansion_max_length_m / _costmap->getResolution();
128 
129  nav2_util::declare_parameter_if_not_declared(
130  node, name + ".max_planning_time", rclcpp::ParameterValue(5.0));
131  node->get_parameter(name + ".max_planning_time", _max_planning_time);
132  nav2_util::declare_parameter_if_not_declared(
133  node, name + ".lookup_table_size", rclcpp::ParameterValue(20.0));
134  node->get_parameter(name + ".lookup_table_size", _lookup_table_size);
135 
136  nav2_util::declare_parameter_if_not_declared(
137  node, name + ".motion_model_for_search", rclcpp::ParameterValue(std::string("DUBIN")));
138  node->get_parameter(name + ".motion_model_for_search", _motion_model_for_search);
139  _motion_model = fromString(_motion_model_for_search);
140  if (_motion_model == MotionModel::UNKNOWN) {
141  RCLCPP_WARN(
142  _logger,
143  "Unable to get MotionModel search type. Given '%s', "
144  "valid options are MOORE, VON_NEUMANN, DUBIN, REEDS_SHEPP, STATE_LATTICE.",
145  _motion_model_for_search.c_str());
146  }
147 
148  if (_max_on_approach_iterations <= 0) {
149  RCLCPP_INFO(
150  _logger, "On approach iteration selected as <= 0, "
151  "disabling tolerance and on approach iterations.");
152  _max_on_approach_iterations = std::numeric_limits<int>::max();
153  }
154 
155  if (_max_iterations <= 0) {
156  RCLCPP_INFO(
157  _logger, "maximum iteration selected as <= 0, "
158  "disabling maximum iterations.");
159  _max_iterations = std::numeric_limits<int>::max();
160  }
161 
162  // convert to grid coordinates
163  if (!_downsample_costmap) {
164  _downsampling_factor = 1;
165  }
166  _search_info.minimum_turning_radius =
167  _minimum_turning_radius_global_coords / (_costmap->getResolution() * _downsampling_factor);
168  _lookup_table_dim =
169  static_cast<float>(_lookup_table_size) /
170  static_cast<float>(_costmap->getResolution() * _downsampling_factor);
171 
172  // Make sure its a whole number
173  _lookup_table_dim = static_cast<float>(static_cast<int>(_lookup_table_dim));
174 
175  // Make sure its an odd number
176  if (static_cast<int>(_lookup_table_dim) % 2 == 0) {
177  RCLCPP_INFO(
178  _logger,
179  "Even sized heuristic lookup table size set %f, increasing size by 1 to make odd",
180  _lookup_table_dim);
181  _lookup_table_dim += 1.0;
182  }
183 
184  // Initialize collision checker
185  _collision_checker = GridCollisionChecker(_costmap, _angle_quantizations, node);
186  _collision_checker.setFootprint(
187  _costmap_ros->getRobotFootprint(),
188  _costmap_ros->getUseRadius(),
189  findCircumscribedCost(_costmap_ros));
190 
191  // Initialize A* template
192  _a_star = std::make_unique<AStarAlgorithm<NodeHybrid>>(_motion_model, _search_info);
193  _a_star->initialize(
194  _allow_unknown,
195  _max_iterations,
196  _max_on_approach_iterations,
197  _max_planning_time,
198  _lookup_table_dim,
199  _angle_quantizations);
200 
201  // Initialize path smoother
202  if (smooth_path) {
203  SmootherParams params;
204  params.get(node, name);
205  _smoother = std::make_unique<Smoother>(params);
206  _smoother->initialize(_minimum_turning_radius_global_coords);
207  }
208 
209  // Initialize costmap downsampler
210  if (_downsample_costmap && _downsampling_factor > 1) {
211  _costmap_downsampler = std::make_unique<CostmapDownsampler>();
212  std::string topic_name = "downsampled_costmap";
213  _costmap_downsampler->on_configure(
214  node, _global_frame, topic_name, _costmap, _downsampling_factor);
215  }
216 
217  _raw_plan_publisher = node->create_publisher<nav_msgs::msg::Path>("unsmoothed_plan", 1);
218 
219  RCLCPP_INFO(
220  _logger, "Configured plugin %s of type SmacPlannerHybrid with "
221  "maximum iterations %i, max on approach iterations %i, and %s. Tolerance %.2f."
222  "Using motion model: %s.",
223  _name.c_str(), _max_iterations, _max_on_approach_iterations,
224  _allow_unknown ? "allowing unknown traversal" : "not allowing unknown traversal",
225  _tolerance, toString(_motion_model).c_str());
226 }
227 
229 {
230  RCLCPP_INFO(
231  _logger, "Activating plugin %s of type SmacPlannerHybrid",
232  _name.c_str());
233  _raw_plan_publisher->on_activate();
234  if (_costmap_downsampler) {
235  _costmap_downsampler->on_activate();
236  }
237  auto node = _node.lock();
238  // Add callback for dynamic parameters
239  _dyn_params_handler = node->add_on_set_parameters_callback(
240  std::bind(&SmacPlannerHybrid::dynamicParametersCallback, this, _1));
241 }
242 
244 {
245  RCLCPP_INFO(
246  _logger, "Deactivating plugin %s of type SmacPlannerHybrid",
247  _name.c_str());
248  _raw_plan_publisher->on_deactivate();
249  if (_costmap_downsampler) {
250  _costmap_downsampler->on_deactivate();
251  }
252  _dyn_params_handler.reset();
253 }
254 
256 {
257  RCLCPP_INFO(
258  _logger, "Cleaning up plugin %s of type SmacPlannerHybrid",
259  _name.c_str());
260  _a_star.reset();
261  _smoother.reset();
262  if (_costmap_downsampler) {
263  _costmap_downsampler->on_cleanup();
264  _costmap_downsampler.reset();
265  }
266  _raw_plan_publisher.reset();
267 }
268 
269 nav_msgs::msg::Path SmacPlannerHybrid::createPlan(
270  const geometry_msgs::msg::PoseStamped & start,
271  const geometry_msgs::msg::PoseStamped & goal)
272 {
273  std::lock_guard<std::mutex> lock_reinit(_mutex);
274  steady_clock::time_point a = steady_clock::now();
275 
276  std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(_costmap->getMutex()));
277 
278  // Downsample costmap, if required
279  nav2_costmap_2d::Costmap2D * costmap = _costmap;
280  if (_costmap_downsampler) {
281  costmap = _costmap_downsampler->downsample(_downsampling_factor);
282  _collision_checker.setCostmap(costmap);
283  }
284 
285  // Set collision checker and costmap information
286  _collision_checker.setFootprint(
287  _costmap_ros->getRobotFootprint(),
288  _costmap_ros->getUseRadius(),
289  findCircumscribedCost(_costmap_ros));
290  _a_star->setCollisionChecker(&_collision_checker);
291 
292  // Set starting point, in A* bin search coordinates
293  unsigned int mx, my;
294  if (!costmap->worldToMap(start.pose.position.x, start.pose.position.y, mx, my)) {
295  throw std::runtime_error("Start pose is out of costmap!");
296  }
297 
298  double orientation_bin = std::round(tf2::getYaw(start.pose.orientation) / _angle_bin_size);
299  while (orientation_bin < 0.0) {
300  orientation_bin += static_cast<float>(_angle_quantizations);
301  }
302  // This is needed to handle precision issues
303  if (orientation_bin >= static_cast<float>(_angle_quantizations)) {
304  orientation_bin -= static_cast<float>(_angle_quantizations);
305  }
306  _a_star->setStart(mx, my, static_cast<unsigned int>(orientation_bin));
307 
308  // Set goal point, in A* bin search coordinates
309  if (!costmap->worldToMap(goal.pose.position.x, goal.pose.position.y, mx, my)) {
310  throw std::runtime_error("Goal pose is out of costmap!");
311  }
312  orientation_bin = std::round(tf2::getYaw(goal.pose.orientation) / _angle_bin_size);
313  while (orientation_bin < 0.0) {
314  orientation_bin += static_cast<float>(_angle_quantizations);
315  }
316  // This is needed to handle precision issues
317  if (orientation_bin >= static_cast<float>(_angle_quantizations)) {
318  orientation_bin -= static_cast<float>(_angle_quantizations);
319  }
320  _a_star->setGoal(mx, my, static_cast<unsigned int>(orientation_bin));
321 
322  // Setup message
323  nav_msgs::msg::Path plan;
324  plan.header.stamp = _clock->now();
325  plan.header.frame_id = _global_frame;
326  geometry_msgs::msg::PoseStamped pose;
327  pose.header = plan.header;
328  pose.pose.position.z = 0.0;
329  pose.pose.orientation.x = 0.0;
330  pose.pose.orientation.y = 0.0;
331  pose.pose.orientation.z = 0.0;
332  pose.pose.orientation.w = 1.0;
333 
334  // Compute plan
335  NodeHybrid::CoordinateVector path;
336  int num_iterations = 0;
337  std::string error;
338  try {
339  if (!_a_star->createPath(
340  path, num_iterations, _tolerance / static_cast<float>(costmap->getResolution())))
341  {
342  if (num_iterations < _a_star->getMaxIterations()) {
343  error = std::string("no valid path found");
344  } else {
345  error = std::string("exceeded maximum iterations");
346  }
347  }
348  } catch (const std::runtime_error & e) {
349  error = "invalid use: ";
350  error += e.what();
351  }
352 
353  if (!error.empty()) {
354  RCLCPP_WARN(
355  _logger,
356  "%s: failed to create plan, %s.",
357  _name.c_str(), error.c_str());
358  return plan;
359  }
360 
361  // Convert to world coordinates
362  plan.poses.reserve(path.size());
363  for (int i = path.size() - 1; i >= 0; --i) {
364  pose.pose = getWorldCoords(path[i].x, path[i].y, costmap);
365  pose.pose.orientation = getWorldOrientation(path[i].theta);
366  plan.poses.push_back(pose);
367  }
368 
369  // Publish raw path for debug
370  if (_raw_plan_publisher->get_subscription_count() > 0) {
371  _raw_plan_publisher->publish(plan);
372  }
373 
374  // Find how much time we have left to do smoothing
375  steady_clock::time_point b = steady_clock::now();
376  duration<double> time_span = duration_cast<duration<double>>(b - a);
377  double time_remaining = _max_planning_time - static_cast<double>(time_span.count());
378 
379 #ifdef BENCHMARK_TESTING
380  std::cout << "It took " << time_span.count() * 1000 <<
381  " milliseconds with " << num_iterations << " iterations." << std::endl;
382 #endif
383 
384  // Smooth plan
385  if (_smoother && num_iterations > 1) {
386  _smoother->smooth(plan, costmap, time_remaining);
387  }
388 
389 #ifdef BENCHMARK_TESTING
390  steady_clock::time_point c = steady_clock::now();
391  duration<double> time_span2 = duration_cast<duration<double>>(c - b);
392  std::cout << "It took " << time_span2.count() * 1000 <<
393  " milliseconds to smooth path." << std::endl;
394 #endif
395 
396  return plan;
397 }
398 
399 rcl_interfaces::msg::SetParametersResult
400 SmacPlannerHybrid::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
401 {
402  rcl_interfaces::msg::SetParametersResult result;
403  std::lock_guard<std::mutex> lock_reinit(_mutex);
404 
405  bool reinit_collision_checker = false;
406  bool reinit_a_star = false;
407  bool reinit_downsampler = false;
408  bool reinit_smoother = false;
409 
410  for (auto parameter : parameters) {
411  const auto & type = parameter.get_type();
412  const auto & name = parameter.get_name();
413 
414  if (type == ParameterType::PARAMETER_DOUBLE) {
415  if (name == _name + ".max_planning_time") {
416  reinit_a_star = true;
417  _max_planning_time = parameter.as_double();
418  } else if (name == _name + ".tolerance") {
419  _tolerance = static_cast<float>(parameter.as_double());
420  } else if (name == _name + ".lookup_table_size") {
421  reinit_a_star = true;
422  _lookup_table_size = parameter.as_double();
423  } else if (name == _name + ".minimum_turning_radius") {
424  reinit_a_star = true;
425  if (_smoother) {
426  reinit_smoother = true;
427  }
428  _minimum_turning_radius_global_coords = static_cast<float>(parameter.as_double());
429  } else if (name == _name + ".reverse_penalty") {
430  reinit_a_star = true;
431  _search_info.reverse_penalty = static_cast<float>(parameter.as_double());
432  } else if (name == _name + ".change_penalty") {
433  reinit_a_star = true;
434  _search_info.change_penalty = static_cast<float>(parameter.as_double());
435  } else if (name == _name + ".non_straight_penalty") {
436  reinit_a_star = true;
437  _search_info.non_straight_penalty = static_cast<float>(parameter.as_double());
438  } else if (name == _name + ".cost_penalty") {
439  reinit_a_star = true;
440  _search_info.cost_penalty = static_cast<float>(parameter.as_double());
441  } else if (name == _name + ".analytic_expansion_ratio") {
442  reinit_a_star = true;
443  _search_info.analytic_expansion_ratio = static_cast<float>(parameter.as_double());
444  } else if (name == _name + ".analytic_expansion_max_length") {
445  reinit_a_star = true;
446  _search_info.analytic_expansion_max_length =
447  static_cast<float>(parameter.as_double()) / _costmap->getResolution();
448  }
449  } else if (type == ParameterType::PARAMETER_BOOL) {
450  if (name == _name + ".downsample_costmap") {
451  reinit_downsampler = true;
452  _downsample_costmap = parameter.as_bool();
453  } else if (name == _name + ".allow_unknown") {
454  reinit_a_star = true;
455  _allow_unknown = parameter.as_bool();
456  } else if (name == _name + ".cache_obstacle_heuristic") {
457  reinit_a_star = true;
458  _search_info.cache_obstacle_heuristic = parameter.as_bool();
459  } else if (name == _name + ".smooth_path") {
460  if (parameter.as_bool()) {
461  reinit_smoother = true;
462  } else {
463  _smoother.reset();
464  }
465  }
466  } else if (type == ParameterType::PARAMETER_INTEGER) {
467  if (name == _name + ".downsampling_factor") {
468  reinit_a_star = true;
469  reinit_downsampler = true;
470  _downsampling_factor = parameter.as_int();
471  } else if (name == _name + ".max_iterations") {
472  reinit_a_star = true;
473  _max_iterations = parameter.as_int();
474  if (_max_iterations <= 0) {
475  RCLCPP_INFO(
476  _logger, "maximum iteration selected as <= 0, "
477  "disabling maximum iterations.");
478  _max_iterations = std::numeric_limits<int>::max();
479  }
480  } else if (name == _name + ".max_on_approach_iterations") {
481  reinit_a_star = true;
482  _max_on_approach_iterations = parameter.as_int();
483  if (_max_on_approach_iterations <= 0) {
484  RCLCPP_INFO(
485  _logger, "On approach iteration selected as <= 0, "
486  "disabling tolerance and on approach iterations.");
487  _max_on_approach_iterations = std::numeric_limits<int>::max();
488  }
489  } else if (name == _name + ".angle_quantization_bins") {
490  reinit_collision_checker = true;
491  reinit_a_star = true;
492  int angle_quantizations = parameter.as_int();
493  _angle_bin_size = 2.0 * M_PI / angle_quantizations;
494  _angle_quantizations = static_cast<unsigned int>(angle_quantizations);
495  }
496  } else if (type == ParameterType::PARAMETER_STRING) {
497  if (name == _name + ".motion_model_for_search") {
498  reinit_a_star = true;
499  _motion_model = fromString(parameter.as_string());
500  if (_motion_model == MotionModel::UNKNOWN) {
501  RCLCPP_WARN(
502  _logger,
503  "Unable to get MotionModel search type. Given '%s', "
504  "valid options are MOORE, VON_NEUMANN, DUBIN, REEDS_SHEPP.",
505  _motion_model_for_search.c_str());
506  }
507  }
508  }
509  }
510 
511  // Re-init if needed with mutex lock (to avoid re-init while creating a plan)
512  if (reinit_a_star || reinit_downsampler || reinit_collision_checker || reinit_smoother) {
513  // convert to grid coordinates
514  if (!_downsample_costmap) {
515  _downsampling_factor = 1;
516  }
517  _search_info.minimum_turning_radius =
518  _minimum_turning_radius_global_coords / (_costmap->getResolution() * _downsampling_factor);
519  _lookup_table_dim =
520  static_cast<float>(_lookup_table_size) /
521  static_cast<float>(_costmap->getResolution() * _downsampling_factor);
522 
523  // Make sure its a whole number
524  _lookup_table_dim = static_cast<float>(static_cast<int>(_lookup_table_dim));
525 
526  // Make sure its an odd number
527  if (static_cast<int>(_lookup_table_dim) % 2 == 0) {
528  RCLCPP_INFO(
529  _logger,
530  "Even sized heuristic lookup table size set %f, increasing size by 1 to make odd",
531  _lookup_table_dim);
532  _lookup_table_dim += 1.0;
533  }
534 
535  auto node = _node.lock();
536 
537  // Re-Initialize A* template
538  if (reinit_a_star) {
539  _a_star = std::make_unique<AStarAlgorithm<NodeHybrid>>(_motion_model, _search_info);
540  _a_star->initialize(
541  _allow_unknown,
542  _max_iterations,
543  _max_on_approach_iterations,
544  _max_planning_time,
545  _lookup_table_dim,
546  _angle_quantizations);
547  }
548 
549  // Re-Initialize costmap downsampler
550  if (reinit_downsampler) {
551  if (_downsample_costmap && _downsampling_factor > 1) {
552  std::string topic_name = "downsampled_costmap";
553  _costmap_downsampler = std::make_unique<CostmapDownsampler>();
554  _costmap_downsampler->on_configure(
555  node, _global_frame, topic_name, _costmap, _downsampling_factor);
556  }
557  }
558 
559  // Re-Initialize collision checker
560  if (reinit_collision_checker) {
561  _collision_checker = GridCollisionChecker(_costmap, _angle_quantizations, node);
562  _collision_checker.setFootprint(
563  _costmap_ros->getRobotFootprint(),
564  _costmap_ros->getUseRadius(),
565  findCircumscribedCost(_costmap_ros));
566  }
567 
568  // Re-Initialize smoother
569  if (reinit_smoother) {
570  SmootherParams params;
571  params.get(node, _name);
572  _smoother = std::make_unique<Smoother>(params);
573  _smoother->initialize(_minimum_turning_radius_global_coords);
574  }
575  }
576  result.successful = true;
577  return result;
578 }
579 
580 } // namespace nav2_smac_planner
581 
582 #include "pluginlib/class_list_macros.hpp"
Abstract interface for global planners to adhere to with pluginlib.
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:68
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
Definition: costmap_2d.cpp:287
double getResolution() const
Accessor for the resolution of the costmap.
Definition: costmap_2d.cpp:531
void setCostmap(CostmapT costmap)
Set the current costmap object to use for collision detection.
A costmap grid collision checker.
void setFootprint(const nav2_costmap_2d::Footprint &footprint, const bool &radius, const double &possible_inscribed_cost)
A constructor for nav2_smac_planner::GridCollisionChecker for use when irregular bin intervals are ap...
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
Configuring plugin.
void activate() override
Activate lifecycle node.
void cleanup() override
Cleanup lifecycle node.
void deactivate() override
Deactivate lifecycle node.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a paramter change is detected.
nav_msgs::msg::Path createPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal) override
Creating a plan from start and goal poses.
Parameters for the smoother cost function.
void get(std::shared_ptr< rclcpp_lifecycle::LifecycleNode > node, const std::string &name)
Get params from ROS parameter.
Definition: types.hpp:70