Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
smac_planner_hybrid.cpp
1 // Copyright (c) 2020, Samsung Research America
2 // Copyright (c) 2023, Open Navigation LLC
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License. Reserved.
15 
16 #include <string>
17 #include <memory>
18 #include <vector>
19 #include <algorithm>
20 #include <limits>
21 
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_ros(nullptr),
39  _costmap_downsampler(nullptr)
40 {
41 }
42 
44 {
45  RCLCPP_INFO(
46  _logger, "Destroying plugin %s of type SmacPlannerHybrid",
47  _name.c_str());
48 }
49 
51  const nav2::LifecycleNode::WeakPtr & parent,
52  std::string name, std::shared_ptr<tf2_ros::Buffer>/*tf*/,
53  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
54 {
55  _node = parent;
56  auto node = parent.lock();
57  _logger = node->get_logger();
58  _clock = node->get_clock();
59  _costmap = costmap_ros->getCostmap();
60  _costmap_ros = costmap_ros;
61  _name = name;
62  _global_frame = costmap_ros->getGlobalFrameID();
63 
64  RCLCPP_INFO(_logger, "Configuring %s of type SmacPlannerHybrid", name.c_str());
65 
66  int angle_quantizations;
67  double analytic_expansion_max_length_m;
68  bool smooth_path;
69 
70  // General planner params
71  nav2::declare_parameter_if_not_declared(
72  node, name + ".downsample_costmap", rclcpp::ParameterValue(false));
73  node->get_parameter(name + ".downsample_costmap", _downsample_costmap);
74  nav2::declare_parameter_if_not_declared(
75  node, name + ".downsampling_factor", rclcpp::ParameterValue(1));
76  node->get_parameter(name + ".downsampling_factor", _downsampling_factor);
77 
78  nav2::declare_parameter_if_not_declared(
79  node, name + ".angle_quantization_bins", rclcpp::ParameterValue(72));
80  node->get_parameter(name + ".angle_quantization_bins", angle_quantizations);
81  _angle_bin_size = 2.0 * M_PI / angle_quantizations;
82  _angle_quantizations = static_cast<unsigned int>(angle_quantizations);
83 
84  nav2::declare_parameter_if_not_declared(
85  node, name + ".tolerance", rclcpp::ParameterValue(0.25));
86  _tolerance = static_cast<float>(node->get_parameter(name + ".tolerance").as_double());
87  nav2::declare_parameter_if_not_declared(
88  node, name + ".allow_unknown", rclcpp::ParameterValue(true));
89  node->get_parameter(name + ".allow_unknown", _allow_unknown);
90  nav2::declare_parameter_if_not_declared(
91  node, name + ".max_iterations", rclcpp::ParameterValue(1000000));
92  node->get_parameter(name + ".max_iterations", _max_iterations);
93  nav2::declare_parameter_if_not_declared(
94  node, name + ".max_on_approach_iterations", rclcpp::ParameterValue(1000));
95  node->get_parameter(name + ".max_on_approach_iterations", _max_on_approach_iterations);
96  nav2::declare_parameter_if_not_declared(
97  node, name + ".terminal_checking_interval", rclcpp::ParameterValue(5000));
98  node->get_parameter(name + ".terminal_checking_interval", _terminal_checking_interval);
99  nav2::declare_parameter_if_not_declared(
100  node, name + ".smooth_path", rclcpp::ParameterValue(true));
101  node->get_parameter(name + ".smooth_path", smooth_path);
102 
103  nav2::declare_parameter_if_not_declared(
104  node, name + ".minimum_turning_radius", rclcpp::ParameterValue(0.4));
105  node->get_parameter(name + ".minimum_turning_radius", _minimum_turning_radius_global_coords);
106  nav2::declare_parameter_if_not_declared(
107  node, name + ".allow_primitive_interpolation", rclcpp::ParameterValue(false));
108  node->get_parameter(
109  name + ".allow_primitive_interpolation", _search_info.allow_primitive_interpolation);
110  nav2::declare_parameter_if_not_declared(
111  node, name + ".cache_obstacle_heuristic", rclcpp::ParameterValue(false));
112  node->get_parameter(name + ".cache_obstacle_heuristic", _search_info.cache_obstacle_heuristic);
113  nav2::declare_parameter_if_not_declared(
114  node, name + ".reverse_penalty", rclcpp::ParameterValue(2.0));
115  node->get_parameter(name + ".reverse_penalty", _search_info.reverse_penalty);
116  nav2::declare_parameter_if_not_declared(
117  node, name + ".change_penalty", rclcpp::ParameterValue(0.0));
118  node->get_parameter(name + ".change_penalty", _search_info.change_penalty);
119  nav2::declare_parameter_if_not_declared(
120  node, name + ".non_straight_penalty", rclcpp::ParameterValue(1.2));
121  node->get_parameter(name + ".non_straight_penalty", _search_info.non_straight_penalty);
122  nav2::declare_parameter_if_not_declared(
123  node, name + ".cost_penalty", rclcpp::ParameterValue(2.0));
124  node->get_parameter(name + ".cost_penalty", _search_info.cost_penalty);
125  nav2::declare_parameter_if_not_declared(
126  node, name + ".retrospective_penalty", rclcpp::ParameterValue(0.015));
127  node->get_parameter(name + ".retrospective_penalty", _search_info.retrospective_penalty);
128  nav2::declare_parameter_if_not_declared(
129  node, name + ".analytic_expansion_ratio", rclcpp::ParameterValue(3.5));
130  node->get_parameter(name + ".analytic_expansion_ratio", _search_info.analytic_expansion_ratio);
131  nav2::declare_parameter_if_not_declared(
132  node, name + ".analytic_expansion_max_cost", rclcpp::ParameterValue(200.0));
133  node->get_parameter(
134  name + ".analytic_expansion_max_cost", _search_info.analytic_expansion_max_cost);
135  nav2::declare_parameter_if_not_declared(
136  node, name + ".analytic_expansion_max_cost_override", rclcpp::ParameterValue(false));
137  node->get_parameter(
138  name + ".analytic_expansion_max_cost_override",
139  _search_info.analytic_expansion_max_cost_override);
140  nav2::declare_parameter_if_not_declared(
141  node, name + ".use_quadratic_cost_penalty", rclcpp::ParameterValue(false));
142  node->get_parameter(
143  name + ".use_quadratic_cost_penalty", _search_info.use_quadratic_cost_penalty);
144  nav2::declare_parameter_if_not_declared(
145  node, name + ".downsample_obstacle_heuristic", rclcpp::ParameterValue(true));
146  node->get_parameter(
147  name + ".downsample_obstacle_heuristic", _search_info.downsample_obstacle_heuristic);
148 
149  nav2::declare_parameter_if_not_declared(
150  node, name + ".analytic_expansion_max_length", rclcpp::ParameterValue(3.0));
151  node->get_parameter(name + ".analytic_expansion_max_length", analytic_expansion_max_length_m);
152  _search_info.analytic_expansion_max_length =
153  analytic_expansion_max_length_m / _costmap->getResolution();
154 
155  nav2::declare_parameter_if_not_declared(
156  node, name + ".max_planning_time", rclcpp::ParameterValue(5.0));
157  node->get_parameter(name + ".max_planning_time", _max_planning_time);
158  nav2::declare_parameter_if_not_declared(
159  node, name + ".lookup_table_size", rclcpp::ParameterValue(20.0));
160  node->get_parameter(name + ".lookup_table_size", _lookup_table_size);
161 
162  nav2::declare_parameter_if_not_declared(
163  node, name + ".debug_visualizations", rclcpp::ParameterValue(false));
164  node->get_parameter(name + ".debug_visualizations", _debug_visualizations);
165 
166  nav2::declare_parameter_if_not_declared(
167  node, name + ".motion_model_for_search", rclcpp::ParameterValue(std::string("DUBIN")));
168  node->get_parameter(name + ".motion_model_for_search", _motion_model_for_search);
169  // Note that we need to declare it here to prevent the parameter from being declared in the
170  // dynamic reconfigure callback
171  nav2::declare_parameter_if_not_declared(
172  node, "introspection_mode", rclcpp::ParameterValue("disabled"));
173 
174  std::string goal_heading_type;
175  nav2::declare_parameter_if_not_declared(
176  node, name + ".goal_heading_mode", rclcpp::ParameterValue("DEFAULT"));
177  node->get_parameter(name + ".goal_heading_mode", goal_heading_type);
178  _goal_heading_mode = fromStringToGH(goal_heading_type);
179 
180  nav2::declare_parameter_if_not_declared(
181  node, name + ".coarse_search_resolution", rclcpp::ParameterValue(1));
182  node->get_parameter(name + ".coarse_search_resolution", _coarse_search_resolution);
183 
184  if (_goal_heading_mode == GoalHeadingMode::UNKNOWN) {
185  std::string error_msg = "Unable to get GoalHeader type. Given '" + goal_heading_type + "' "
186  "Valid options are DEFAULT, BIDIRECTIONAL, ALL_DIRECTION. ";
187  throw nav2_core::PlannerException(error_msg);
188  }
189 
190  _motion_model = fromString(_motion_model_for_search);
191 
192  if (_motion_model == MotionModel::UNKNOWN) {
193  RCLCPP_WARN(
194  _logger,
195  "Unable to get MotionModel search type. Given '%s', "
196  "valid options are MOORE, VON_NEUMANN, DUBIN, REEDS_SHEPP, STATE_LATTICE.",
197  _motion_model_for_search.c_str());
198  }
199 
200  if (_max_on_approach_iterations <= 0) {
201  RCLCPP_WARN(
202  _logger, "On approach iteration selected as <= 0, "
203  "disabling tolerance and on approach iterations.");
204  _max_on_approach_iterations = std::numeric_limits<int>::max();
205  }
206 
207  if (_max_iterations <= 0) {
208  RCLCPP_WARN(
209  _logger, "maximum iteration selected as <= 0, "
210  "disabling maximum iterations.");
211  _max_iterations = std::numeric_limits<int>::max();
212  }
213 
214  if (_coarse_search_resolution <= 0) {
215  RCLCPP_WARN(
216  _logger, "coarse iteration resolution selected as <= 0, "
217  "disabling coarse iteration resolution search for goal heading"
218  );
219 
220  _coarse_search_resolution = 1;
221  }
222 
223  if (_angle_quantizations % _coarse_search_resolution != 0) {
224  std::string error_msg = "coarse iteration should be an increment"
225  " of the number of angular bins configured";
226  throw nav2_core::PlannerException(error_msg);
227  }
228 
229  if (_minimum_turning_radius_global_coords < _costmap->getResolution() * _downsampling_factor) {
230  RCLCPP_WARN(
231  _logger, "Min turning radius cannot be less than the search grid cell resolution!");
232  _minimum_turning_radius_global_coords = _costmap->getResolution() * _downsampling_factor;
233  }
234 
235  // convert to grid coordinates
236  if (!_downsample_costmap) {
237  _downsampling_factor = 1;
238  }
239  _search_info.minimum_turning_radius =
240  _minimum_turning_radius_global_coords / (_costmap->getResolution() * _downsampling_factor);
241  _lookup_table_dim =
242  static_cast<float>(_lookup_table_size) /
243  static_cast<float>(_costmap->getResolution() * _downsampling_factor);
244 
245  // Make sure its a whole number
246  _lookup_table_dim = static_cast<float>(static_cast<int>(_lookup_table_dim));
247 
248  // Make sure its an odd number
249  if (static_cast<int>(_lookup_table_dim) % 2 == 0) {
250  RCLCPP_INFO(
251  _logger,
252  "Even sized heuristic lookup table size set %f, increasing size by 1 to make odd",
253  _lookup_table_dim);
254  _lookup_table_dim += 1.0;
255  }
256 
257  // Initialize collision checker
258  _collision_checker = GridCollisionChecker(_costmap_ros, _angle_quantizations, node);
259  _collision_checker.setFootprint(
260  _costmap_ros->getRobotFootprint(),
261  _costmap_ros->getUseRadius(),
262  findCircumscribedCost(_costmap_ros));
263 
264  // Initialize A* template
265  _a_star = std::make_unique<AStarAlgorithm<NodeHybrid>>(_motion_model, _search_info);
266  _a_star->initialize(
267  _allow_unknown,
268  _max_iterations,
269  _max_on_approach_iterations,
270  _terminal_checking_interval,
271  _max_planning_time,
272  _lookup_table_dim,
273  _angle_quantizations);
274 
275  // Initialize path smoother
276  if (smooth_path) {
277  SmootherParams params;
278  params.get(node, name);
279  _smoother = std::make_unique<Smoother>(params);
280  _smoother->initialize(_minimum_turning_radius_global_coords);
281  }
282 
283  // Initialize costmap downsampler
284  _costmap_downsampler = std::make_unique<CostmapDownsampler>();
285  std::string topic_name = "downsampled_costmap";
286  _costmap_downsampler->on_configure(
287  node, _global_frame, topic_name, _costmap, _downsampling_factor);
288 
289  _raw_plan_publisher = node->create_publisher<nav_msgs::msg::Path>("unsmoothed_plan");
290 
291  if (_debug_visualizations) {
292  _expansions_publisher = node->create_publisher<geometry_msgs::msg::PoseArray>("expansions");
293  _planned_footprints_publisher = node->create_publisher<visualization_msgs::msg::MarkerArray>(
294  "planned_footprints");
295  _smoothed_footprints_publisher =
296  node->create_publisher<visualization_msgs::msg::MarkerArray>(
297  "smoothed_footprints");
298  }
299 
300  RCLCPP_INFO(
301  _logger, "Configured plugin %s of type SmacPlannerHybrid with "
302  "maximum iterations %i, max on approach iterations %i, and %s. Tolerance %.2f."
303  "Using motion model: %s.",
304  _name.c_str(), _max_iterations, _max_on_approach_iterations,
305  _allow_unknown ? "allowing unknown traversal" : "not allowing unknown traversal",
306  _tolerance, toString(_motion_model).c_str());
307 }
308 
310 {
311  RCLCPP_INFO(
312  _logger, "Activating plugin %s of type SmacPlannerHybrid",
313  _name.c_str());
314  _raw_plan_publisher->on_activate();
315  if (_debug_visualizations) {
316  _expansions_publisher->on_activate();
317  _planned_footprints_publisher->on_activate();
318  _smoothed_footprints_publisher->on_activate();
319  }
320  if (_costmap_downsampler) {
321  _costmap_downsampler->on_activate();
322  }
323  auto node = _node.lock();
324  // Add callback for dynamic parameters
325  _dyn_params_handler = node->add_on_set_parameters_callback(
326  std::bind(&SmacPlannerHybrid::dynamicParametersCallback, this, _1));
327 
328  // Special case handling to obtain resolution changes in global costmap
329  auto resolution_remote_cb = [this](const rclcpp::Parameter & p) {
331  {rclcpp::Parameter("resolution", rclcpp::ParameterValue(p.as_double()))});
332  };
333  _remote_param_subscriber = std::make_shared<rclcpp::ParameterEventHandler>(_node.lock());
334  _remote_resolution_handler = _remote_param_subscriber->add_parameter_callback(
335  "resolution", resolution_remote_cb, "global_costmap/global_costmap");
336 }
337 
339 {
340  RCLCPP_INFO(
341  _logger, "Deactivating plugin %s of type SmacPlannerHybrid",
342  _name.c_str());
343  _raw_plan_publisher->on_deactivate();
344  if (_debug_visualizations) {
345  _expansions_publisher->on_deactivate();
346  _planned_footprints_publisher->on_deactivate();
347  _smoothed_footprints_publisher->on_deactivate();
348  }
349  if (_costmap_downsampler) {
350  _costmap_downsampler->on_deactivate();
351  }
352  // shutdown dyn_param_handler
353  auto node = _node.lock();
354  if (_dyn_params_handler && node) {
355  node->remove_on_set_parameters_callback(_dyn_params_handler.get());
356  }
357  _dyn_params_handler.reset();
358 }
359 
361 {
362  RCLCPP_INFO(
363  _logger, "Cleaning up plugin %s of type SmacPlannerHybrid",
364  _name.c_str());
366  _a_star.reset();
367  _smoother.reset();
368  if (_costmap_downsampler) {
369  _costmap_downsampler->on_cleanup();
370  _costmap_downsampler.reset();
371  }
372  _raw_plan_publisher.reset();
373  if (_debug_visualizations) {
374  _expansions_publisher.reset();
375  _planned_footprints_publisher.reset();
376  _smoothed_footprints_publisher.reset();
377  }
378 }
379 
380 nav_msgs::msg::Path SmacPlannerHybrid::createPlan(
381  const geometry_msgs::msg::PoseStamped & start,
382  const geometry_msgs::msg::PoseStamped & goal,
383  std::function<bool()> cancel_checker)
384 {
385  std::lock_guard<std::mutex> lock_reinit(_mutex);
386  steady_clock::time_point a = steady_clock::now();
387 
388  std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(_costmap->getMutex()));
389 
390  // Downsample costmap, if required
391  nav2_costmap_2d::Costmap2D * costmap = _costmap;
392  if (_downsample_costmap && _downsampling_factor > 1) {
393  costmap = _costmap_downsampler->downsample(_downsampling_factor);
394  _collision_checker.setCostmap(costmap);
395  }
396 
397  // Set collision checker and costmap information
398  _collision_checker.setFootprint(
399  _costmap_ros->getRobotFootprint(),
400  _costmap_ros->getUseRadius(),
401  findCircumscribedCost(_costmap_ros));
402  _a_star->setCollisionChecker(&_collision_checker);
403 
404  // Set starting point, in A* bin search coordinates
405  float mx_start, my_start, mx_goal, my_goal;
406  if (!costmap->worldToMapContinuous(
407  start.pose.position.x,
408  start.pose.position.y,
409  mx_start,
410  my_start))
411  {
413  "Start Coordinates of(" + std::to_string(start.pose.position.x) + ", " +
414  std::to_string(start.pose.position.y) + ") was outside bounds");
415  }
416 
417  double start_orientation_bin = std::round(tf2::getYaw(start.pose.orientation) / _angle_bin_size);
418  while (start_orientation_bin < 0.0) {
419  start_orientation_bin += static_cast<float>(_angle_quantizations);
420  }
421  // This is needed to handle precision issues
422  if (start_orientation_bin >= static_cast<float>(_angle_quantizations)) {
423  start_orientation_bin -= static_cast<float>(_angle_quantizations);
424  }
425  unsigned int start_orientation_bin_int =
426  static_cast<unsigned int>(start_orientation_bin);
427  _a_star->setStart(mx_start, my_start, start_orientation_bin_int);
428 
429  // Set goal point, in A* bin search coordinates
430  if (!costmap->worldToMapContinuous(
431  goal.pose.position.x,
432  goal.pose.position.y,
433  mx_goal,
434  my_goal))
435  {
437  "Goal Coordinates of(" + std::to_string(goal.pose.position.x) + ", " +
438  std::to_string(goal.pose.position.y) + ") was outside bounds");
439  }
440  double goal_orientation_bin = std::round(tf2::getYaw(goal.pose.orientation) / _angle_bin_size);
441  while (goal_orientation_bin < 0.0) {
442  goal_orientation_bin += static_cast<float>(_angle_quantizations);
443  }
444  // This is needed to handle precision issues
445  if (goal_orientation_bin >= static_cast<float>(_angle_quantizations)) {
446  goal_orientation_bin -= static_cast<float>(_angle_quantizations);
447  }
448  unsigned int goal_orientation_bin_int =
449  static_cast<unsigned int>(goal_orientation_bin);
450  _a_star->setGoal(mx_goal, my_goal, static_cast<unsigned int>(goal_orientation_bin_int),
451  _goal_heading_mode, _coarse_search_resolution);
452 
453  // Setup message
454  nav_msgs::msg::Path plan;
455  plan.header.stamp = _clock->now();
456  plan.header.frame_id = _global_frame;
457  geometry_msgs::msg::PoseStamped pose;
458  pose.header = plan.header;
459  pose.pose.position.z = 0.0;
460  pose.pose.orientation.x = 0.0;
461  pose.pose.orientation.y = 0.0;
462  pose.pose.orientation.z = 0.0;
463  pose.pose.orientation.w = 1.0;
464 
465  // Corner case of start and goal being on the same cell
466  if (std::floor(mx_start) == std::floor(mx_goal) &&
467  std::floor(my_start) == std::floor(my_goal) &&
468  start_orientation_bin_int == goal_orientation_bin_int)
469  {
470  pose.pose = start.pose;
471  pose.pose.orientation = goal.pose.orientation;
472  plan.poses.push_back(pose);
473 
474  // Publish raw path for debug
475  if (_raw_plan_publisher->get_subscription_count() > 0) {
476  _raw_plan_publisher->publish(plan);
477  }
478 
479  return plan;
480  }
481 
482  // Compute plan
483  NodeHybrid::CoordinateVector path;
484  int num_iterations = 0;
485  std::string error;
486  std::unique_ptr<std::vector<std::tuple<float, float, float>>> expansions = nullptr;
487  if (_debug_visualizations) {
488  expansions = std::make_unique<std::vector<std::tuple<float, float, float>>>();
489  }
490  // Note: All exceptions thrown are handled by the planner server and returned to the action
491  if (!_a_star->createPath(
492  path, num_iterations,
493  _tolerance / static_cast<float>(costmap->getResolution()), cancel_checker, expansions.get()))
494  {
495  if (_debug_visualizations) {
496  geometry_msgs::msg::PoseArray msg;
497  geometry_msgs::msg::Pose msg_pose;
498  msg.header.stamp = _clock->now();
499  msg.header.frame_id = _global_frame;
500  for (auto & e : *expansions) {
501  msg_pose.position.x = std::get<0>(e);
502  msg_pose.position.y = std::get<1>(e);
503  msg_pose.orientation = getWorldOrientation(std::get<2>(e));
504  msg.poses.push_back(msg_pose);
505  }
506  _expansions_publisher->publish(msg);
507  }
508 
509  // Note: If the start is blocked only one iteration will occur before failure
510  if (num_iterations == 1) {
511  throw nav2_core::StartOccupied("Start occupied");
512  }
513 
514  if (num_iterations < _a_star->getMaxIterations()) {
515  throw nav2_core::NoValidPathCouldBeFound("no valid path found");
516  } else {
517  throw nav2_core::PlannerTimedOut("exceeded maximum iterations");
518  }
519  }
520 
521  // Convert to world coordinates
522  plan.poses.reserve(path.size());
523  for (int i = path.size() - 1; i >= 0; --i) {
524  pose.pose = getWorldCoords(path[i].x, path[i].y, costmap);
525  pose.pose.orientation = getWorldOrientation(path[i].theta);
526  plan.poses.push_back(pose);
527  }
528 
529  // Publish raw path for debug
530  if (_raw_plan_publisher->get_subscription_count() > 0) {
531  _raw_plan_publisher->publish(plan);
532  }
533 
534  if (_debug_visualizations) {
535  // Publish expansions for debug
536  auto now = _clock->now();
537  geometry_msgs::msg::PoseArray msg;
538  geometry_msgs::msg::Pose msg_pose;
539  msg.header.stamp = now;
540  msg.header.frame_id = _global_frame;
541  for (auto & e : *expansions) {
542  msg_pose.position.x = std::get<0>(e);
543  msg_pose.position.y = std::get<1>(e);
544  msg_pose.orientation = getWorldOrientation(std::get<2>(e));
545  msg.poses.push_back(msg_pose);
546  }
547  _expansions_publisher->publish(msg);
548 
549  if (_planned_footprints_publisher->get_subscription_count() > 0) {
550  // Clear all markers first
551  auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
552  visualization_msgs::msg::Marker clear_all_marker;
553  clear_all_marker.action = visualization_msgs::msg::Marker::DELETEALL;
554  marker_array->markers.push_back(clear_all_marker);
555  _planned_footprints_publisher->publish(std::move(marker_array));
556 
557  // Publish smoothed footprints for debug
558  marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
559  for (size_t i = 0; i < plan.poses.size(); i++) {
560  const std::vector<geometry_msgs::msg::Point> edge =
561  transformFootprintToEdges(plan.poses[i].pose, _costmap_ros->getRobotFootprint());
562  marker_array->markers.push_back(createMarker(edge, i, _global_frame, now));
563  }
564  _planned_footprints_publisher->publish(std::move(marker_array));
565  }
566  }
567 
568  // Find how much time we have left to do smoothing
569  steady_clock::time_point b = steady_clock::now();
570  duration<double> time_span = duration_cast<duration<double>>(b - a);
571  double time_remaining = _max_planning_time - static_cast<double>(time_span.count());
572 
573 #ifdef BENCHMARK_TESTING
574  std::cout << "It took " << time_span.count() * 1000 <<
575  " milliseconds with " << num_iterations << " iterations." << std::endl;
576 #endif
577 
578  // Smooth plan
579  if (_smoother && num_iterations > 1) {
580  _smoother->smooth(plan, costmap, time_remaining);
581  }
582 
583 #ifdef BENCHMARK_TESTING
584  steady_clock::time_point c = steady_clock::now();
585  duration<double> time_span2 = duration_cast<duration<double>>(c - b);
586  std::cout << "It took " << time_span2.count() * 1000 <<
587  " milliseconds to smooth path." << std::endl;
588 #endif
589 
590  if (_debug_visualizations) {
591  if (_smoothed_footprints_publisher->get_subscription_count() > 0) {
592  // Clear all markers first
593  auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
594  visualization_msgs::msg::Marker clear_all_marker;
595  clear_all_marker.action = visualization_msgs::msg::Marker::DELETEALL;
596  marker_array->markers.push_back(clear_all_marker);
597  _smoothed_footprints_publisher->publish(std::move(marker_array));
598 
599  // Publish smoothed footprints for debug
600  marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
601  auto now = _clock->now();
602  for (size_t i = 0; i < plan.poses.size(); i++) {
603  const std::vector<geometry_msgs::msg::Point> edge =
604  transformFootprintToEdges(plan.poses[i].pose, _costmap_ros->getRobotFootprint());
605  marker_array->markers.push_back(createMarker(edge, i, _global_frame, now));
606  }
607  _smoothed_footprints_publisher->publish(std::move(marker_array));
608  }
609  }
610 
611  return plan;
612 }
613 
614 rcl_interfaces::msg::SetParametersResult
615 SmacPlannerHybrid::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
616 {
617  rcl_interfaces::msg::SetParametersResult result;
618  std::lock_guard<std::mutex> lock_reinit(_mutex);
619 
620  bool reinit_collision_checker = false;
621  bool reinit_a_star = false;
622  bool reinit_downsampler = false;
623  bool reinit_smoother = false;
624 
625  for (auto parameter : parameters) {
626  const auto & param_type = parameter.get_type();
627  const auto & param_name = parameter.get_name();
628  if(param_name.find(_name + ".") != 0 && param_name != "resolution") {
629  continue;
630  }
631  if (param_type == ParameterType::PARAMETER_DOUBLE) {
632  if (param_name == _name + ".max_planning_time") {
633  reinit_a_star = true;
634  _max_planning_time = parameter.as_double();
635  } else if (param_name == _name + ".tolerance") {
636  _tolerance = static_cast<float>(parameter.as_double());
637  } else if (param_name == _name + ".lookup_table_size") {
638  reinit_a_star = true;
639  _lookup_table_size = parameter.as_double();
640  } else if (param_name == _name + ".minimum_turning_radius") {
641  reinit_a_star = true;
642  if (_smoother) {
643  reinit_smoother = true;
644  }
645 
646  if (parameter.as_double() < _costmap->getResolution() * _downsampling_factor) {
647  RCLCPP_ERROR(
648  _logger, "Min turning radius cannot be less than the search grid cell resolution!");
649  result.successful = false;
650  }
651 
652  _minimum_turning_radius_global_coords = static_cast<float>(parameter.as_double());
653  } else if (param_name == _name + ".reverse_penalty") {
654  reinit_a_star = true;
655  _search_info.reverse_penalty = static_cast<float>(parameter.as_double());
656  } else if (param_name == _name + ".change_penalty") {
657  reinit_a_star = true;
658  _search_info.change_penalty = static_cast<float>(parameter.as_double());
659  } else if (param_name == _name + ".non_straight_penalty") {
660  reinit_a_star = true;
661  _search_info.non_straight_penalty = static_cast<float>(parameter.as_double());
662  } else if (param_name == _name + ".cost_penalty") {
663  reinit_a_star = true;
664  _search_info.cost_penalty = static_cast<float>(parameter.as_double());
665  } else if (param_name == _name + ".analytic_expansion_ratio") {
666  reinit_a_star = true;
667  _search_info.analytic_expansion_ratio = static_cast<float>(parameter.as_double());
668  } else if (param_name == _name + ".analytic_expansion_max_length") {
669  reinit_a_star = true;
670  _search_info.analytic_expansion_max_length =
671  static_cast<float>(parameter.as_double()) / _costmap->getResolution();
672  } else if (param_name == _name + ".analytic_expansion_max_cost") {
673  reinit_a_star = true;
674  _search_info.analytic_expansion_max_cost = static_cast<float>(parameter.as_double());
675  } else if (param_name == "resolution") {
676  // Special case: When the costmap's resolution changes, need to reinitialize
677  // the controller to have new resolution information
678  RCLCPP_INFO(_logger, "Costmap resolution changed. Reinitializing SmacPlannerHybrid.");
679  reinit_collision_checker = true;
680  reinit_a_star = true;
681  reinit_downsampler = true;
682  reinit_smoother = true;
683  }
684  } else if (param_type == ParameterType::PARAMETER_BOOL) {
685  if (param_name == _name + ".downsample_costmap") {
686  reinit_downsampler = true;
687  _downsample_costmap = parameter.as_bool();
688  } else if (param_name == _name + ".allow_unknown") {
689  reinit_a_star = true;
690  _allow_unknown = parameter.as_bool();
691  } else if (param_name == _name + ".cache_obstacle_heuristic") {
692  reinit_a_star = true;
693  _search_info.cache_obstacle_heuristic = parameter.as_bool();
694  } else if (param_name == _name + ".allow_primitive_interpolation") {
695  _search_info.allow_primitive_interpolation = parameter.as_bool();
696  reinit_a_star = true;
697  } else if (param_name == _name + ".smooth_path") {
698  if (parameter.as_bool()) {
699  reinit_smoother = true;
700  } else {
701  _smoother.reset();
702  }
703  } else if (param_name == _name + ".analytic_expansion_max_cost_override") {
704  _search_info.analytic_expansion_max_cost_override = parameter.as_bool();
705  reinit_a_star = true;
706  }
707  } else if (param_type == ParameterType::PARAMETER_INTEGER) {
708  if (param_name == _name + ".downsampling_factor") {
709  reinit_a_star = true;
710  reinit_downsampler = true;
711  _downsampling_factor = parameter.as_int();
712  } else if (param_name == _name + ".max_iterations") {
713  reinit_a_star = true;
714  _max_iterations = parameter.as_int();
715  if (_max_iterations <= 0) {
716  RCLCPP_INFO(
717  _logger, "maximum iteration selected as <= 0, "
718  "disabling maximum iterations.");
719  _max_iterations = std::numeric_limits<int>::max();
720  }
721  } else if (param_name == _name + ".max_on_approach_iterations") {
722  reinit_a_star = true;
723  _max_on_approach_iterations = parameter.as_int();
724  if (_max_on_approach_iterations <= 0) {
725  RCLCPP_INFO(
726  _logger, "On approach iteration selected as <= 0, "
727  "disabling tolerance and on approach iterations.");
728  _max_on_approach_iterations = std::numeric_limits<int>::max();
729  }
730  } else if (param_name == _name + ".terminal_checking_interval") {
731  reinit_a_star = true;
732  _terminal_checking_interval = parameter.as_int();
733  } else if (param_name == _name + ".angle_quantization_bins") {
734  reinit_collision_checker = true;
735  reinit_a_star = true;
736  int angle_quantizations = parameter.as_int();
737  _angle_bin_size = 2.0 * M_PI / angle_quantizations;
738  _angle_quantizations = static_cast<unsigned int>(angle_quantizations);
739 
740  if (_angle_quantizations % _coarse_search_resolution != 0) {
741  RCLCPP_WARN(
742  _logger, "coarse iteration should be an increment of the "
743  "number of angular bins configured. Disabling course research!"
744  );
745  _coarse_search_resolution = 1;
746  }
747  } else if (param_name == _name + ".coarse_search_resolution") {
748  _coarse_search_resolution = parameter.as_int();
749  if (_coarse_search_resolution <= 0) {
750  RCLCPP_WARN(
751  _logger, "coarse iteration resolution selected as <= 0. "
752  "Disabling course research!"
753  );
754  _coarse_search_resolution = 1;
755  }
756  if (_angle_quantizations % _coarse_search_resolution != 0) {
757  RCLCPP_WARN(
758  _logger,
759  "coarse iteration should be an increment of the "
760  "number of angular bins configured. Disabling course research!"
761  );
762  _coarse_search_resolution = 1;
763  }
764  }
765  } else if (param_type == ParameterType::PARAMETER_STRING) {
766  if (param_name == _name + ".motion_model_for_search") {
767  reinit_a_star = true;
768  _motion_model = fromString(parameter.as_string());
769  if (_motion_model == MotionModel::UNKNOWN) {
770  RCLCPP_WARN(
771  _logger,
772  "Unable to get MotionModel search type. Given '%s', "
773  "valid options are MOORE, VON_NEUMANN, DUBIN, REEDS_SHEPP.",
774  _motion_model_for_search.c_str());
775  }
776  } else if (param_name == _name + ".goal_heading_mode") {
777  std::string goal_heading_type = parameter.as_string();
778  GoalHeadingMode goal_heading_mode = fromStringToGH(goal_heading_type);
779  RCLCPP_INFO(
780  _logger,
781  "GoalHeadingMode type set to '%s'.",
782  goal_heading_type.c_str());
783  if (goal_heading_mode == GoalHeadingMode::UNKNOWN) {
784  RCLCPP_WARN(
785  _logger,
786  "Unable to get GoalHeader type. Given '%s', "
787  "Valid options are DEFAULT, BIDIRECTIONAL, ALL_DIRECTION. ",
788  goal_heading_type.c_str());
789  } else {
790  _goal_heading_mode = goal_heading_mode;
791  }
792  }
793  }
794  }
795 
796  // Re-init if needed with mutex lock (to avoid re-init while creating a plan)
797  if (reinit_a_star || reinit_downsampler || reinit_collision_checker || reinit_smoother) {
798  // convert to grid coordinates
799  if (!_downsample_costmap) {
800  _downsampling_factor = 1;
801  }
802  _search_info.minimum_turning_radius =
803  _minimum_turning_radius_global_coords / (_costmap->getResolution() * _downsampling_factor);
804  _lookup_table_dim =
805  static_cast<float>(_lookup_table_size) /
806  static_cast<float>(_costmap->getResolution() * _downsampling_factor);
807 
808  // Make sure its a whole number
809  _lookup_table_dim = static_cast<float>(static_cast<int>(_lookup_table_dim));
810 
811  // Make sure its an odd number
812  if (static_cast<int>(_lookup_table_dim) % 2 == 0) {
813  RCLCPP_INFO(
814  _logger,
815  "Even sized heuristic lookup table size set %f, increasing size by 1 to make odd",
816  _lookup_table_dim);
817  _lookup_table_dim += 1.0;
818  }
819 
820  auto node = _node.lock();
821 
822  // Re-Initialize A* template
823  if (reinit_a_star) {
824  _a_star = std::make_unique<AStarAlgorithm<NodeHybrid>>(_motion_model, _search_info);
825  _a_star->initialize(
826  _allow_unknown,
827  _max_iterations,
828  _max_on_approach_iterations,
829  _terminal_checking_interval,
830  _max_planning_time,
831  _lookup_table_dim,
832  _angle_quantizations);
833  }
834 
835  // Re-Initialize costmap downsampler
836  if (reinit_downsampler) {
837  if (_downsample_costmap && _downsampling_factor > 1) {
838  std::string topic_name = "downsampled_costmap";
839  _costmap_downsampler = std::make_unique<CostmapDownsampler>();
840  _costmap_downsampler->on_configure(
841  node, _global_frame, topic_name, _costmap, _downsampling_factor);
842  _costmap_downsampler->on_activate();
843  }
844  }
845 
846  // Re-Initialize collision checker
847  if (reinit_collision_checker) {
848  _collision_checker = GridCollisionChecker(_costmap_ros, _angle_quantizations, node);
849  _collision_checker.setFootprint(
850  _costmap_ros->getRobotFootprint(),
851  _costmap_ros->getUseRadius(),
852  findCircumscribedCost(_costmap_ros));
853  }
854 
855  // Re-Initialize smoother
856  if (reinit_smoother) {
857  SmootherParams params;
858  params.get(node, _name);
859  _smoother = std::make_unique<Smoother>(params);
860  _smoother->initialize(_minimum_turning_radius_global_coords);
861  }
862  }
863  result.successful = true;
864  return result;
865 }
866 
867 } // namespace nav2_smac_planner
868 
869 #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:69
double getResolution() const
Accessor for the resolution of the costmap.
Definition: costmap_2d.cpp:576
bool worldToMapContinuous(double wx, double wy, float &mx, float &my) const
Convert from world coordinates to map coordinates.
Definition: costmap_2d.cpp:306
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_collision_cost)
A constructor for nav2_smac_planner::GridCollisionChecker for use when irregular bin intervals are ap...
static void destroyStaticAssets()
Destroy shared pointer assets at the end of the process that don't require normal destruction handlin...
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
Configuring plugin.
nav_msgs::msg::Path createPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal, std::function< bool()> cancel_checker) override
Creating a plan from start and goal poses.
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 parameter change is detected.
Parameters for the smoother cost function.
void get(nav2::LifecycleNode::SharedPtr node, const std::string &name)
Get params from ROS parameter.
Definition: types.hpp:75