Nav2 Navigation Stack - kilted  kilted
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 rclcpp_lifecycle::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_util::declare_parameter_if_not_declared(
72  node, name + ".downsample_costmap", rclcpp::ParameterValue(false));
73  node->get_parameter(name + ".downsample_costmap", _downsample_costmap);
74  nav2_util::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_util::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_util::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_util::declare_parameter_if_not_declared(
88  node, name + ".allow_unknown", rclcpp::ParameterValue(true));
89  node->get_parameter(name + ".allow_unknown", _allow_unknown);
90  nav2_util::declare_parameter_if_not_declared(
91  node, name + ".max_iterations", rclcpp::ParameterValue(1000000));
92  node->get_parameter(name + ".max_iterations", _max_iterations);
93  nav2_util::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_util::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_util::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_util::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_util::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_util::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_util::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_util::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_util::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_util::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_util::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_util::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_util::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_util::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_util::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_util::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_util::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_util::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_util::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_util::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_util::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_util::declare_parameter_if_not_declared(
172  node, "service_introspection_mode", rclcpp::ParameterValue("disabled"));
173 
174  std::string goal_heading_type;
175  nav2_util::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_util::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  SmootherParams params;
277  params.get(node, name);
278  if (smooth_path) {
279  _smoother = std::make_unique<Smoother>(params);
280  _smoother->initialize(_minimum_turning_radius_global_coords);
281  }
282 
283  // Initialize costmap downsampler
284  if (_downsample_costmap && _downsampling_factor > 1) {
285  _costmap_downsampler = std::make_unique<CostmapDownsampler>();
286  std::string topic_name = "downsampled_costmap";
287  _costmap_downsampler->on_configure(
288  node, _global_frame, topic_name, _costmap, _downsampling_factor);
289  }
290 
291  _raw_plan_publisher = node->create_publisher<nav_msgs::msg::Path>("unsmoothed_plan", 1);
292 
293  if (_debug_visualizations) {
294  _expansions_publisher = node->create_publisher<geometry_msgs::msg::PoseArray>("expansions", 1);
295  _planned_footprints_publisher = node->create_publisher<visualization_msgs::msg::MarkerArray>(
296  "planned_footprints", 1);
297  _smoothed_footprints_publisher =
298  node->create_publisher<visualization_msgs::msg::MarkerArray>(
299  "smoothed_footprints", 1);
300  }
301 
302  RCLCPP_INFO(
303  _logger, "Configured plugin %s of type SmacPlannerHybrid with "
304  "maximum iterations %i, max on approach iterations %i, and %s. Tolerance %.2f."
305  "Using motion model: %s.",
306  _name.c_str(), _max_iterations, _max_on_approach_iterations,
307  _allow_unknown ? "allowing unknown traversal" : "not allowing unknown traversal",
308  _tolerance, toString(_motion_model).c_str());
309 }
310 
312 {
313  RCLCPP_INFO(
314  _logger, "Activating plugin %s of type SmacPlannerHybrid",
315  _name.c_str());
316  _raw_plan_publisher->on_activate();
317  if (_debug_visualizations) {
318  _expansions_publisher->on_activate();
319  _planned_footprints_publisher->on_activate();
320  _smoothed_footprints_publisher->on_activate();
321  }
322  if (_costmap_downsampler) {
323  _costmap_downsampler->on_activate();
324  }
325  auto node = _node.lock();
326  // Add callback for dynamic parameters
327  _dyn_params_handler = node->add_on_set_parameters_callback(
328  std::bind(&SmacPlannerHybrid::dynamicParametersCallback, this, _1));
329 
330  // Special case handling to obtain resolution changes in global costmap
331  auto resolution_remote_cb = [this](const rclcpp::Parameter & p) {
333  {rclcpp::Parameter("resolution", rclcpp::ParameterValue(p.as_double()))});
334  };
335  _remote_param_subscriber = std::make_shared<rclcpp::ParameterEventHandler>(_node.lock());
336  _remote_resolution_handler = _remote_param_subscriber->add_parameter_callback(
337  "resolution", resolution_remote_cb, "global_costmap/global_costmap");
338 }
339 
341 {
342  RCLCPP_INFO(
343  _logger, "Deactivating plugin %s of type SmacPlannerHybrid",
344  _name.c_str());
345  _raw_plan_publisher->on_deactivate();
346  if (_debug_visualizations) {
347  _expansions_publisher->on_deactivate();
348  _planned_footprints_publisher->on_deactivate();
349  _smoothed_footprints_publisher->on_deactivate();
350  }
351  if (_costmap_downsampler) {
352  _costmap_downsampler->on_deactivate();
353  }
354  // shutdown dyn_param_handler
355  auto node = _node.lock();
356  if (_dyn_params_handler && node) {
357  node->remove_on_set_parameters_callback(_dyn_params_handler.get());
358  }
359  _dyn_params_handler.reset();
360 }
361 
363 {
364  RCLCPP_INFO(
365  _logger, "Cleaning up plugin %s of type SmacPlannerHybrid",
366  _name.c_str());
368  _a_star.reset();
369  _smoother.reset();
370  if (_costmap_downsampler) {
371  _costmap_downsampler->on_cleanup();
372  _costmap_downsampler.reset();
373  }
374  _raw_plan_publisher.reset();
375  if (_debug_visualizations) {
376  _expansions_publisher.reset();
377  _planned_footprints_publisher.reset();
378  _smoothed_footprints_publisher.reset();
379  }
380 }
381 
382 nav_msgs::msg::Path SmacPlannerHybrid::createPlan(
383  const geometry_msgs::msg::PoseStamped & start,
384  const geometry_msgs::msg::PoseStamped & goal,
385  std::function<bool()> cancel_checker)
386 {
387  std::lock_guard<std::mutex> lock_reinit(_mutex);
388  steady_clock::time_point a = steady_clock::now();
389 
390  std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(_costmap->getMutex()));
391 
392  // Downsample costmap, if required
393  nav2_costmap_2d::Costmap2D * costmap = _costmap;
394  if (_costmap_downsampler) {
395  costmap = _costmap_downsampler->downsample(_downsampling_factor);
396  _collision_checker.setCostmap(costmap);
397  }
398 
399  // Set collision checker and costmap information
400  _collision_checker.setFootprint(
401  _costmap_ros->getRobotFootprint(),
402  _costmap_ros->getUseRadius(),
403  findCircumscribedCost(_costmap_ros));
404  _a_star->setCollisionChecker(&_collision_checker);
405 
406  // Set starting point, in A* bin search coordinates
407  float mx_start, my_start, mx_goal, my_goal;
408  if (!costmap->worldToMapContinuous(
409  start.pose.position.x,
410  start.pose.position.y,
411  mx_start,
412  my_start))
413  {
415  "Start Coordinates of(" + std::to_string(start.pose.position.x) + ", " +
416  std::to_string(start.pose.position.y) + ") was outside bounds");
417  }
418 
419  double start_orientation_bin = std::round(tf2::getYaw(start.pose.orientation) / _angle_bin_size);
420  while (start_orientation_bin < 0.0) {
421  start_orientation_bin += static_cast<float>(_angle_quantizations);
422  }
423  // This is needed to handle precision issues
424  if (start_orientation_bin >= static_cast<float>(_angle_quantizations)) {
425  start_orientation_bin -= static_cast<float>(_angle_quantizations);
426  }
427  unsigned int start_orientation_bin_int =
428  static_cast<unsigned int>(start_orientation_bin);
429  _a_star->setStart(mx_start, my_start, start_orientation_bin_int);
430 
431  // Set goal point, in A* bin search coordinates
432  if (!costmap->worldToMapContinuous(
433  goal.pose.position.x,
434  goal.pose.position.y,
435  mx_goal,
436  my_goal))
437  {
439  "Goal Coordinates of(" + std::to_string(goal.pose.position.x) + ", " +
440  std::to_string(goal.pose.position.y) + ") was outside bounds");
441  }
442  double goal_orientation_bin = std::round(tf2::getYaw(goal.pose.orientation) / _angle_bin_size);
443  while (goal_orientation_bin < 0.0) {
444  goal_orientation_bin += static_cast<float>(_angle_quantizations);
445  }
446  // This is needed to handle precision issues
447  if (goal_orientation_bin >= static_cast<float>(_angle_quantizations)) {
448  goal_orientation_bin -= static_cast<float>(_angle_quantizations);
449  }
450  unsigned int goal_orientation_bin_int =
451  static_cast<unsigned int>(goal_orientation_bin);
452  _a_star->setGoal(mx_goal, my_goal, static_cast<unsigned int>(goal_orientation_bin_int),
453  _goal_heading_mode, _coarse_search_resolution);
454 
455  // Setup message
456  nav_msgs::msg::Path plan;
457  plan.header.stamp = _clock->now();
458  plan.header.frame_id = _global_frame;
459  geometry_msgs::msg::PoseStamped pose;
460  pose.header = plan.header;
461  pose.pose.position.z = 0.0;
462  pose.pose.orientation.x = 0.0;
463  pose.pose.orientation.y = 0.0;
464  pose.pose.orientation.z = 0.0;
465  pose.pose.orientation.w = 1.0;
466 
467  // Corner case of start and goal being on the same cell
468  if (std::floor(mx_start) == std::floor(mx_goal) &&
469  std::floor(my_start) == std::floor(my_goal) &&
470  start_orientation_bin_int == goal_orientation_bin_int)
471  {
472  pose.pose = start.pose;
473  pose.pose.orientation = goal.pose.orientation;
474  plan.poses.push_back(pose);
475 
476  // Publish raw path for debug
477  if (_raw_plan_publisher->get_subscription_count() > 0) {
478  _raw_plan_publisher->publish(plan);
479  }
480 
481  return plan;
482  }
483 
484  // Compute plan
485  NodeHybrid::CoordinateVector path;
486  int num_iterations = 0;
487  std::string error;
488  std::unique_ptr<std::vector<std::tuple<float, float, float>>> expansions = nullptr;
489  if (_debug_visualizations) {
490  expansions = std::make_unique<std::vector<std::tuple<float, float, float>>>();
491  }
492  // Note: All exceptions thrown are handled by the planner server and returned to the action
493  if (!_a_star->createPath(
494  path, num_iterations,
495  _tolerance / static_cast<float>(costmap->getResolution()), cancel_checker, expansions.get()))
496  {
497  if (_debug_visualizations) {
498  geometry_msgs::msg::PoseArray msg;
499  geometry_msgs::msg::Pose msg_pose;
500  msg.header.stamp = _clock->now();
501  msg.header.frame_id = _global_frame;
502  for (auto & e : *expansions) {
503  msg_pose.position.x = std::get<0>(e);
504  msg_pose.position.y = std::get<1>(e);
505  msg_pose.orientation = getWorldOrientation(std::get<2>(e));
506  msg.poses.push_back(msg_pose);
507  }
508  _expansions_publisher->publish(msg);
509  }
510 
511  // Note: If the start is blocked only one iteration will occur before failure
512  if (num_iterations == 1) {
513  throw nav2_core::StartOccupied("Start occupied");
514  }
515 
516  if (num_iterations < _a_star->getMaxIterations()) {
517  throw nav2_core::NoValidPathCouldBeFound("no valid path found");
518  } else {
519  throw nav2_core::PlannerTimedOut("exceeded maximum iterations");
520  }
521  }
522 
523  // Convert to world coordinates
524  plan.poses.reserve(path.size());
525  for (int i = path.size() - 1; i >= 0; --i) {
526  pose.pose = getWorldCoords(path[i].x, path[i].y, costmap);
527  pose.pose.orientation = getWorldOrientation(path[i].theta);
528  plan.poses.push_back(pose);
529  }
530 
531  // Publish raw path for debug
532  if (_raw_plan_publisher->get_subscription_count() > 0) {
533  _raw_plan_publisher->publish(plan);
534  }
535 
536  if (_debug_visualizations) {
537  // Publish expansions for debug
538  auto now = _clock->now();
539  geometry_msgs::msg::PoseArray msg;
540  geometry_msgs::msg::Pose msg_pose;
541  msg.header.stamp = now;
542  msg.header.frame_id = _global_frame;
543  for (auto & e : *expansions) {
544  msg_pose.position.x = std::get<0>(e);
545  msg_pose.position.y = std::get<1>(e);
546  msg_pose.orientation = getWorldOrientation(std::get<2>(e));
547  msg.poses.push_back(msg_pose);
548  }
549  _expansions_publisher->publish(msg);
550 
551  if (_planned_footprints_publisher->get_subscription_count() > 0) {
552  // Clear all markers first
553  auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
554  visualization_msgs::msg::Marker clear_all_marker;
555  clear_all_marker.action = visualization_msgs::msg::Marker::DELETEALL;
556  marker_array->markers.push_back(clear_all_marker);
557  _planned_footprints_publisher->publish(std::move(marker_array));
558 
559  // Publish smoothed footprints for debug
560  marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
561  for (size_t i = 0; i < plan.poses.size(); i++) {
562  const std::vector<geometry_msgs::msg::Point> edge =
563  transformFootprintToEdges(plan.poses[i].pose, _costmap_ros->getRobotFootprint());
564  marker_array->markers.push_back(createMarker(edge, i, _global_frame, now));
565  }
566  _planned_footprints_publisher->publish(std::move(marker_array));
567  }
568  }
569 
570  // Find how much time we have left to do smoothing
571  steady_clock::time_point b = steady_clock::now();
572  duration<double> time_span = duration_cast<duration<double>>(b - a);
573  double time_remaining = _max_planning_time - static_cast<double>(time_span.count());
574 
575 #ifdef BENCHMARK_TESTING
576  std::cout << "It took " << time_span.count() * 1000 <<
577  " milliseconds with " << num_iterations << " iterations." << std::endl;
578 #endif
579 
580  // Smooth plan
581  if (_smoother && num_iterations > 1) {
582  _smoother->smooth(plan, costmap, time_remaining);
583  }
584 
585 #ifdef BENCHMARK_TESTING
586  steady_clock::time_point c = steady_clock::now();
587  duration<double> time_span2 = duration_cast<duration<double>>(c - b);
588  std::cout << "It took " << time_span2.count() * 1000 <<
589  " milliseconds to smooth path." << std::endl;
590 #endif
591 
592  if (_debug_visualizations) {
593  if (_smoothed_footprints_publisher->get_subscription_count() > 0) {
594  // Clear all markers first
595  auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
596  visualization_msgs::msg::Marker clear_all_marker;
597  clear_all_marker.action = visualization_msgs::msg::Marker::DELETEALL;
598  marker_array->markers.push_back(clear_all_marker);
599  _smoothed_footprints_publisher->publish(std::move(marker_array));
600 
601  // Publish smoothed footprints for debug
602  marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
603  auto now = _clock->now();
604  for (size_t i = 0; i < plan.poses.size(); i++) {
605  const std::vector<geometry_msgs::msg::Point> edge =
606  transformFootprintToEdges(plan.poses[i].pose, _costmap_ros->getRobotFootprint());
607  marker_array->markers.push_back(createMarker(edge, i, _global_frame, now));
608  }
609  _smoothed_footprints_publisher->publish(std::move(marker_array));
610  }
611  }
612 
613  return plan;
614 }
615 
616 rcl_interfaces::msg::SetParametersResult
617 SmacPlannerHybrid::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
618 {
619  rcl_interfaces::msg::SetParametersResult result;
620  std::lock_guard<std::mutex> lock_reinit(_mutex);
621 
622  bool reinit_collision_checker = false;
623  bool reinit_a_star = false;
624  bool reinit_downsampler = false;
625  bool reinit_smoother = false;
626 
627  for (auto parameter : parameters) {
628  const auto & param_type = parameter.get_type();
629  const auto & param_name = parameter.get_name();
630  if(param_name.find(_name + ".") != 0 && param_name != "resolution") {
631  continue;
632  }
633  if (param_type == ParameterType::PARAMETER_DOUBLE) {
634  if (param_name == _name + ".max_planning_time") {
635  reinit_a_star = true;
636  _max_planning_time = parameter.as_double();
637  } else if (param_name == _name + ".tolerance") {
638  _tolerance = static_cast<float>(parameter.as_double());
639  } else if (param_name == _name + ".lookup_table_size") {
640  reinit_a_star = true;
641  _lookup_table_size = parameter.as_double();
642  } else if (param_name == _name + ".minimum_turning_radius") {
643  reinit_a_star = true;
644  if (_smoother) {
645  reinit_smoother = true;
646  }
647 
648  if (parameter.as_double() < _costmap->getResolution() * _downsampling_factor) {
649  RCLCPP_ERROR(
650  _logger, "Min turning radius cannot be less than the search grid cell resolution!");
651  result.successful = false;
652  }
653 
654  _minimum_turning_radius_global_coords = static_cast<float>(parameter.as_double());
655  } else if (param_name == _name + ".reverse_penalty") {
656  reinit_a_star = true;
657  _search_info.reverse_penalty = static_cast<float>(parameter.as_double());
658  } else if (param_name == _name + ".change_penalty") {
659  reinit_a_star = true;
660  _search_info.change_penalty = static_cast<float>(parameter.as_double());
661  } else if (param_name == _name + ".non_straight_penalty") {
662  reinit_a_star = true;
663  _search_info.non_straight_penalty = static_cast<float>(parameter.as_double());
664  } else if (param_name == _name + ".cost_penalty") {
665  reinit_a_star = true;
666  _search_info.cost_penalty = static_cast<float>(parameter.as_double());
667  } else if (param_name == _name + ".analytic_expansion_ratio") {
668  reinit_a_star = true;
669  _search_info.analytic_expansion_ratio = static_cast<float>(parameter.as_double());
670  } else if (param_name == _name + ".analytic_expansion_max_length") {
671  reinit_a_star = true;
672  _search_info.analytic_expansion_max_length =
673  static_cast<float>(parameter.as_double()) / _costmap->getResolution();
674  } else if (param_name == _name + ".analytic_expansion_max_cost") {
675  reinit_a_star = true;
676  _search_info.analytic_expansion_max_cost = static_cast<float>(parameter.as_double());
677  } else if (param_name == "resolution") {
678  // Special case: When the costmap's resolution changes, need to reinitialize
679  // the controller to have new resolution information
680  RCLCPP_INFO(_logger, "Costmap resolution changed. Reinitializing SmacPlannerHybrid.");
681  reinit_collision_checker = true;
682  reinit_a_star = true;
683  reinit_downsampler = true;
684  reinit_smoother = true;
685  }
686  } else if (param_type == ParameterType::PARAMETER_BOOL) {
687  if (param_name == _name + ".downsample_costmap") {
688  reinit_downsampler = true;
689  _downsample_costmap = parameter.as_bool();
690  } else if (param_name == _name + ".allow_unknown") {
691  reinit_a_star = true;
692  _allow_unknown = parameter.as_bool();
693  } else if (param_name == _name + ".cache_obstacle_heuristic") {
694  reinit_a_star = true;
695  _search_info.cache_obstacle_heuristic = parameter.as_bool();
696  } else if (param_name == _name + ".allow_primitive_interpolation") {
697  _search_info.allow_primitive_interpolation = parameter.as_bool();
698  reinit_a_star = true;
699  } else if (param_name == _name + ".smooth_path") {
700  if (parameter.as_bool()) {
701  reinit_smoother = true;
702  } else {
703  _smoother.reset();
704  }
705  } else if (param_name == _name + ".analytic_expansion_max_cost_override") {
706  _search_info.analytic_expansion_max_cost_override = parameter.as_bool();
707  reinit_a_star = true;
708  }
709  } else if (param_type == ParameterType::PARAMETER_INTEGER) {
710  if (param_name == _name + ".downsampling_factor") {
711  reinit_a_star = true;
712  reinit_downsampler = true;
713  _downsampling_factor = parameter.as_int();
714  } else if (param_name == _name + ".max_iterations") {
715  reinit_a_star = true;
716  _max_iterations = parameter.as_int();
717  if (_max_iterations <= 0) {
718  RCLCPP_INFO(
719  _logger, "maximum iteration selected as <= 0, "
720  "disabling maximum iterations.");
721  _max_iterations = std::numeric_limits<int>::max();
722  }
723  } else if (param_name == _name + ".max_on_approach_iterations") {
724  reinit_a_star = true;
725  _max_on_approach_iterations = parameter.as_int();
726  if (_max_on_approach_iterations <= 0) {
727  RCLCPP_INFO(
728  _logger, "On approach iteration selected as <= 0, "
729  "disabling tolerance and on approach iterations.");
730  _max_on_approach_iterations = std::numeric_limits<int>::max();
731  }
732  } else if (param_name == _name + ".terminal_checking_interval") {
733  reinit_a_star = true;
734  _terminal_checking_interval = parameter.as_int();
735  } else if (param_name == _name + ".angle_quantization_bins") {
736  reinit_collision_checker = true;
737  reinit_a_star = true;
738  int angle_quantizations = parameter.as_int();
739  _angle_bin_size = 2.0 * M_PI / angle_quantizations;
740  _angle_quantizations = static_cast<unsigned int>(angle_quantizations);
741 
742  if (_angle_quantizations % _coarse_search_resolution != 0) {
743  RCLCPP_WARN(
744  _logger, "coarse iteration should be an increment of the "
745  "number of angular bins configured. Disabling course research!"
746  );
747  _coarse_search_resolution = 1;
748  }
749  } else if (param_name == _name + ".coarse_search_resolution") {
750  _coarse_search_resolution = parameter.as_int();
751  if (_coarse_search_resolution <= 0) {
752  RCLCPP_WARN(
753  _logger, "coarse iteration resolution selected as <= 0. "
754  "Disabling course research!"
755  );
756  _coarse_search_resolution = 1;
757  }
758  if (_angle_quantizations % _coarse_search_resolution != 0) {
759  RCLCPP_WARN(
760  _logger,
761  "coarse iteration should be an increment of the "
762  "number of angular bins configured. Disabling course research!"
763  );
764  _coarse_search_resolution = 1;
765  }
766  }
767  } else if (param_type == ParameterType::PARAMETER_STRING) {
768  if (param_name == _name + ".motion_model_for_search") {
769  reinit_a_star = true;
770  _motion_model = fromString(parameter.as_string());
771  if (_motion_model == MotionModel::UNKNOWN) {
772  RCLCPP_WARN(
773  _logger,
774  "Unable to get MotionModel search type. Given '%s', "
775  "valid options are MOORE, VON_NEUMANN, DUBIN, REEDS_SHEPP.",
776  _motion_model_for_search.c_str());
777  }
778  } else if (param_name == _name + ".goal_heading_mode") {
779  std::string goal_heading_type = parameter.as_string();
780  GoalHeadingMode goal_heading_mode = fromStringToGH(goal_heading_type);
781  RCLCPP_INFO(
782  _logger,
783  "GoalHeadingMode type set to '%s'.",
784  goal_heading_type.c_str());
785  if (goal_heading_mode == GoalHeadingMode::UNKNOWN) {
786  RCLCPP_WARN(
787  _logger,
788  "Unable to get GoalHeader type. Given '%s', "
789  "Valid options are DEFAULT, BIDIRECTIONAL, ALL_DIRECTION. ",
790  goal_heading_type.c_str());
791  } else {
792  _goal_heading_mode = goal_heading_mode;
793  }
794  }
795  }
796  }
797 
798  // Re-init if needed with mutex lock (to avoid re-init while creating a plan)
799  if (reinit_a_star || reinit_downsampler || reinit_collision_checker || reinit_smoother) {
800  // convert to grid coordinates
801  if (!_downsample_costmap) {
802  _downsampling_factor = 1;
803  }
804  _search_info.minimum_turning_radius =
805  _minimum_turning_radius_global_coords / (_costmap->getResolution() * _downsampling_factor);
806  _lookup_table_dim =
807  static_cast<float>(_lookup_table_size) /
808  static_cast<float>(_costmap->getResolution() * _downsampling_factor);
809 
810  // Make sure its a whole number
811  _lookup_table_dim = static_cast<float>(static_cast<int>(_lookup_table_dim));
812 
813  // Make sure its an odd number
814  if (static_cast<int>(_lookup_table_dim) % 2 == 0) {
815  RCLCPP_INFO(
816  _logger,
817  "Even sized heuristic lookup table size set %f, increasing size by 1 to make odd",
818  _lookup_table_dim);
819  _lookup_table_dim += 1.0;
820  }
821 
822  auto node = _node.lock();
823 
824  // Re-Initialize A* template
825  if (reinit_a_star) {
826  _a_star = std::make_unique<AStarAlgorithm<NodeHybrid>>(_motion_model, _search_info);
827  _a_star->initialize(
828  _allow_unknown,
829  _max_iterations,
830  _max_on_approach_iterations,
831  _terminal_checking_interval,
832  _max_planning_time,
833  _lookup_table_dim,
834  _angle_quantizations);
835  }
836 
837  // Re-Initialize costmap downsampler
838  if (reinit_downsampler) {
839  if (_downsample_costmap && _downsampling_factor > 1) {
840  std::string topic_name = "downsampled_costmap";
841  _costmap_downsampler = std::make_unique<CostmapDownsampler>();
842  _costmap_downsampler->on_configure(
843  node, _global_frame, topic_name, _costmap, _downsampling_factor);
844  }
845  }
846 
847  // Re-Initialize collision checker
848  if (reinit_collision_checker) {
849  _collision_checker = GridCollisionChecker(_costmap_ros, _angle_quantizations, node);
850  _collision_checker.setFootprint(
851  _costmap_ros->getRobotFootprint(),
852  _costmap_ros->getUseRadius(),
853  findCircumscribedCost(_costmap_ros));
854  }
855 
856  // Re-Initialize smoother
857  if (reinit_smoother) {
858  SmootherParams params;
859  params.get(node, _name);
860  _smoother = std::make_unique<Smoother>(params);
861  _smoother->initialize(_minimum_turning_radius_global_coords);
862  }
863  }
864  result.successful = true;
865  return result;
866 }
867 
868 } // namespace nav2_smac_planner
869 
870 #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...
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 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 parameter change is detected.
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:75