Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
smac_planner_lattice.cpp
1 // Copyright (c) 2021, 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 "nav2_smac_planner/smac_planner_lattice.hpp"
22 
23 // #define BENCHMARK_TESTING
24 
25 namespace nav2_smac_planner
26 {
27 
28 using namespace std::chrono; // NOLINT
29 using rcl_interfaces::msg::ParameterType;
30 
32 : _a_star(nullptr),
33  _collision_checker(nullptr, 1, nullptr),
34  _smoother(nullptr),
35  _costmap(nullptr)
36 {
37 }
38 
40 {
41  RCLCPP_INFO(
42  _logger, "Destroying plugin %s of type SmacPlannerLattice",
43  _name.c_str());
44 }
45 
47  const nav2::LifecycleNode::WeakPtr & parent,
48  std::string name, std::shared_ptr<tf2_ros::Buffer>/*tf*/,
49  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
50 {
51  _node = parent;
52  auto node = parent.lock();
53  _logger = node->get_logger();
54  _clock = node->get_clock();
55  _costmap = costmap_ros->getCostmap();
56  _costmap_ros = costmap_ros;
57  _name = name;
58  _global_frame = costmap_ros->getGlobalFrameID();
59 
60  RCLCPP_INFO(_logger, "Configuring %s of type SmacPlannerLattice", name.c_str());
61 
62  // General planner params
63  double analytic_expansion_max_length_m;
64  bool smooth_path;
65 
66  nav2::declare_parameter_if_not_declared(
67  node, name + ".tolerance", rclcpp::ParameterValue(0.25));
68  _tolerance = static_cast<float>(node->get_parameter(name + ".tolerance").as_double());
69  nav2::declare_parameter_if_not_declared(
70  node, name + ".allow_unknown", rclcpp::ParameterValue(true));
71  node->get_parameter(name + ".allow_unknown", _allow_unknown);
72  nav2::declare_parameter_if_not_declared(
73  node, name + ".max_iterations", rclcpp::ParameterValue(1000000));
74  node->get_parameter(name + ".max_iterations", _max_iterations);
75  nav2::declare_parameter_if_not_declared(
76  node, name + ".max_on_approach_iterations", rclcpp::ParameterValue(1000));
77  node->get_parameter(name + ".max_on_approach_iterations", _max_on_approach_iterations);
78  nav2::declare_parameter_if_not_declared(
79  node, name + ".terminal_checking_interval", rclcpp::ParameterValue(5000));
80  node->get_parameter(name + ".terminal_checking_interval", _terminal_checking_interval);
81  nav2::declare_parameter_if_not_declared(
82  node, name + ".smooth_path", rclcpp::ParameterValue(true));
83  node->get_parameter(name + ".smooth_path", smooth_path);
84 
85  // Default to a well rounded model: 16 bin, 0.4m turning radius, ackermann model
86  nav2::declare_parameter_if_not_declared(
87  node, name + ".lattice_filepath", rclcpp::ParameterValue(
88  ament_index_cpp::get_package_share_directory("nav2_smac_planner") +
89  "/sample_primitives/5cm_resolution/0.5m_turning_radius/ackermann/output.json"));
90  node->get_parameter(name + ".lattice_filepath", _search_info.lattice_filepath);
91  nav2::declare_parameter_if_not_declared(
92  node, name + ".cache_obstacle_heuristic", rclcpp::ParameterValue(false));
93  node->get_parameter(name + ".cache_obstacle_heuristic", _search_info.cache_obstacle_heuristic);
94  nav2::declare_parameter_if_not_declared(
95  node, name + ".reverse_penalty", rclcpp::ParameterValue(2.0));
96  node->get_parameter(name + ".reverse_penalty", _search_info.reverse_penalty);
97  nav2::declare_parameter_if_not_declared(
98  node, name + ".change_penalty", rclcpp::ParameterValue(0.05));
99  node->get_parameter(name + ".change_penalty", _search_info.change_penalty);
100  nav2::declare_parameter_if_not_declared(
101  node, name + ".non_straight_penalty", rclcpp::ParameterValue(1.05));
102  node->get_parameter(name + ".non_straight_penalty", _search_info.non_straight_penalty);
103  nav2::declare_parameter_if_not_declared(
104  node, name + ".cost_penalty", rclcpp::ParameterValue(2.0));
105  node->get_parameter(name + ".cost_penalty", _search_info.cost_penalty);
106  nav2::declare_parameter_if_not_declared(
107  node, name + ".retrospective_penalty", rclcpp::ParameterValue(0.015));
108  node->get_parameter(name + ".retrospective_penalty", _search_info.retrospective_penalty);
109  nav2::declare_parameter_if_not_declared(
110  node, name + ".rotation_penalty", rclcpp::ParameterValue(5.0));
111  node->get_parameter(name + ".rotation_penalty", _search_info.rotation_penalty);
112  nav2::declare_parameter_if_not_declared(
113  node, name + ".analytic_expansion_ratio", rclcpp::ParameterValue(3.5));
114  node->get_parameter(name + ".analytic_expansion_ratio", _search_info.analytic_expansion_ratio);
115  nav2::declare_parameter_if_not_declared(
116  node, name + ".analytic_expansion_max_cost", rclcpp::ParameterValue(200.0));
117  node->get_parameter(
118  name + ".analytic_expansion_max_cost", _search_info.analytic_expansion_max_cost);
119  nav2::declare_parameter_if_not_declared(
120  node, name + ".analytic_expansion_max_cost_override", rclcpp::ParameterValue(false));
121  node->get_parameter(
122  name + ".analytic_expansion_max_cost_override",
123  _search_info.analytic_expansion_max_cost_override);
124  nav2::declare_parameter_if_not_declared(
125  node, name + ".analytic_expansion_max_length", rclcpp::ParameterValue(3.0));
126  node->get_parameter(name + ".analytic_expansion_max_length", analytic_expansion_max_length_m);
127  _search_info.analytic_expansion_max_length =
128  analytic_expansion_max_length_m / _costmap->getResolution();
129 
130  nav2::declare_parameter_if_not_declared(
131  node, name + ".max_planning_time", rclcpp::ParameterValue(5.0));
132  node->get_parameter(name + ".max_planning_time", _max_planning_time);
133  nav2::declare_parameter_if_not_declared(
134  node, name + ".lookup_table_size", rclcpp::ParameterValue(20.0));
135  node->get_parameter(name + ".lookup_table_size", _lookup_table_size);
136  nav2::declare_parameter_if_not_declared(
137  node, name + ".allow_reverse_expansion", rclcpp::ParameterValue(false));
138  node->get_parameter(name + ".allow_reverse_expansion", _search_info.allow_reverse_expansion);
139  nav2::declare_parameter_if_not_declared(
140  node, name + ".debug_visualizations", rclcpp::ParameterValue(false));
141  node->get_parameter(name + ".debug_visualizations", _debug_visualizations);
142 
143  std::string goal_heading_type;
144  nav2::declare_parameter_if_not_declared(
145  node, name + ".goal_heading_mode", rclcpp::ParameterValue("DEFAULT"));
146  node->get_parameter(name + ".goal_heading_mode", goal_heading_type);
147  _goal_heading_mode = fromStringToGH(goal_heading_type);
148 
149  nav2::declare_parameter_if_not_declared(
150  node, name + ".coarse_search_resolution", rclcpp::ParameterValue(1));
151  node->get_parameter(name + ".coarse_search_resolution", _coarse_search_resolution);
152 
153  if (_goal_heading_mode == GoalHeadingMode::UNKNOWN) {
154  std::string error_msg = "Unable to get GoalHeader type. Given '" + goal_heading_type + "' "
155  "Valid options are DEFAULT, BIDIRECTIONAL, ALL_DIRECTION. ";
156  throw nav2_core::PlannerException(error_msg);
157  }
158 
159  _metadata = LatticeMotionTable::getLatticeMetadata(_search_info.lattice_filepath);
160  _search_info.minimum_turning_radius =
161  _metadata.min_turning_radius / (_costmap->getResolution());
162  _motion_model = MotionModel::STATE_LATTICE;
163 
164  if (_max_on_approach_iterations <= 0) {
165  RCLCPP_INFO(
166  _logger, "On approach iteration selected as <= 0, "
167  "disabling tolerance and on approach iterations.");
168  _max_on_approach_iterations = std::numeric_limits<int>::max();
169  }
170 
171  if (_max_iterations <= 0) {
172  RCLCPP_INFO(
173  _logger, "maximum iteration selected as <= 0, "
174  "disabling maximum iterations.");
175  _max_iterations = std::numeric_limits<int>::max();
176  }
177 
178  if (_coarse_search_resolution <= 0) {
179  RCLCPP_WARN(
180  _logger, "coarse iteration resolution selected as <= 0, "
181  "disabling coarse iteration resolution search for goal heading"
182  );
183  _coarse_search_resolution = 1;
184  }
185 
186  if (_metadata.number_of_headings % _coarse_search_resolution != 0) {
187  std::string error_msg = "coarse iteration should be an increment of"
188  " the number of angular bins configured";
189  throw nav2_core::PlannerException(error_msg);
190  }
191 
192  float lookup_table_dim =
193  static_cast<float>(_lookup_table_size) /
194  static_cast<float>(_costmap->getResolution());
195 
196  // Make sure its a whole number
197  lookup_table_dim = static_cast<float>(static_cast<int>(lookup_table_dim));
198 
199  // Make sure its an odd number
200  if (static_cast<int>(lookup_table_dim) % 2 == 0) {
201  RCLCPP_INFO(
202  _logger,
203  "Even sized heuristic lookup table size set %f, increasing size by 1 to make odd",
204  lookup_table_dim);
205  lookup_table_dim += 1.0;
206  }
207 
208  // Initialize collision checker using 72 evenly sized bins instead of the lattice
209  // heading angles. This is done so that we have precomputed angles every 5 degrees.
210  // If we used the sparse lattice headings (usually 16), then when we attempt to collision
211  // check for intermediary points of the primitives, we're forced to round to one of the 16
212  // increments causing "wobbly" checks that could cause larger robots to virtually show collisions
213  // in valid configurations. This approximation helps to bound orientation error for all checks
214  // in exchange for slight inaccuracies in the collision headings in terminal search states.
215  _collision_checker = GridCollisionChecker(_costmap_ros, 72u, node);
216  _collision_checker.setFootprint(
217  costmap_ros->getRobotFootprint(),
218  costmap_ros->getUseRadius(),
219  findCircumscribedCost(costmap_ros));
220 
221  // Initialize A* template
222  _a_star = std::make_unique<AStarAlgorithm<NodeLattice>>(_motion_model, _search_info);
223  _a_star->initialize(
224  _allow_unknown,
225  _max_iterations,
226  _max_on_approach_iterations,
227  _terminal_checking_interval,
228  _max_planning_time,
229  lookup_table_dim,
230  _metadata.number_of_headings);
231 
232  // Initialize path smoother
233  if (smooth_path) {
234  SmootherParams params;
235  params.get(node, name);
236  _smoother = std::make_unique<Smoother>(params);
237  _smoother->initialize(_metadata.min_turning_radius);
238  }
239 
240  _raw_plan_publisher = node->create_publisher<nav_msgs::msg::Path>("unsmoothed_plan");
241 
242  if (_debug_visualizations) {
243  _expansions_publisher = node->create_publisher<geometry_msgs::msg::PoseArray>("expansions");
244  _planned_footprints_publisher = node->create_publisher<visualization_msgs::msg::MarkerArray>(
245  "planned_footprints");
246  _smoothed_footprints_publisher =
247  node->create_publisher<visualization_msgs::msg::MarkerArray>(
248  "smoothed_footprints");
249  }
250 
251  RCLCPP_INFO(
252  _logger, "Configured plugin %s of type SmacPlannerLattice with "
253  "maximum iterations %i, max on approach iterations %i, "
254  "and %s. Tolerance %.2f. Using motion model: %s. State lattice file: %s.",
255  _name.c_str(), _max_iterations, _max_on_approach_iterations,
256  _allow_unknown ? "allowing unknown traversal" : "not allowing unknown traversal",
257  _tolerance, toString(_motion_model).c_str(), _search_info.lattice_filepath.c_str());
258 }
259 
261 {
262  RCLCPP_INFO(
263  _logger, "Activating plugin %s of type SmacPlannerLattice",
264  _name.c_str());
265  _raw_plan_publisher->on_activate();
266  if (_debug_visualizations) {
267  _expansions_publisher->on_activate();
268  _planned_footprints_publisher->on_activate();
269  _smoothed_footprints_publisher->on_activate();
270  }
271  auto node = _node.lock();
272  // Add callback for dynamic parameters
273  _dyn_params_handler = node->add_on_set_parameters_callback(
274  std::bind(&SmacPlannerLattice::dynamicParametersCallback, this, std::placeholders::_1));
275 }
276 
278 {
279  RCLCPP_INFO(
280  _logger, "Deactivating plugin %s of type SmacPlannerLattice",
281  _name.c_str());
282  _raw_plan_publisher->on_deactivate();
283  if (_debug_visualizations) {
284  _expansions_publisher->on_deactivate();
285  _planned_footprints_publisher->on_deactivate();
286  _smoothed_footprints_publisher->on_deactivate();
287  }
288  // shutdown dyn_param_handler
289  auto node = _node.lock();
290  if (_dyn_params_handler && node) {
291  node->remove_on_set_parameters_callback(_dyn_params_handler.get());
292  }
293  _dyn_params_handler.reset();
294 }
295 
297 {
298  RCLCPP_INFO(
299  _logger, "Cleaning up plugin %s of type SmacPlannerLattice",
300  _name.c_str());
302  _a_star.reset();
303  _smoother.reset();
304  _raw_plan_publisher.reset();
305  if (_debug_visualizations) {
306  _expansions_publisher.reset();
307  _planned_footprints_publisher.reset();
308  _smoothed_footprints_publisher.reset();
309  }
310 }
311 
312 nav_msgs::msg::Path SmacPlannerLattice::createPlan(
313  const geometry_msgs::msg::PoseStamped & start,
314  const geometry_msgs::msg::PoseStamped & goal,
315  std::function<bool()> cancel_checker)
316 {
317  std::lock_guard<std::mutex> lock_reinit(_mutex);
318  steady_clock::time_point a = steady_clock::now();
319 
320  std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(_costmap->getMutex()));
321 
322  // Set collision checker and costmap information
323  _collision_checker.setFootprint(
324  _costmap_ros->getRobotFootprint(),
325  _costmap_ros->getUseRadius(),
326  findCircumscribedCost(_costmap_ros));
327  _a_star->setCollisionChecker(&_collision_checker);
328 
329  // Set starting point, in A* bin search coordinates
330  float mx_start, my_start, mx_goal, my_goal;
331  if (!_costmap->worldToMapContinuous(
332  start.pose.position.x,
333  start.pose.position.y,
334  mx_start,
335  my_start))
336  {
338  "Start Coordinates of(" + std::to_string(start.pose.position.x) + ", " +
339  std::to_string(start.pose.position.y) + ") was outside bounds");
340  }
341  unsigned int start_bin =
342  NodeLattice::motion_table.getClosestAngularBin(tf2::getYaw(start.pose.orientation));
343  _a_star->setStart(mx_start, my_start, start_bin);
344 
345  // Set goal point, in A* bin search coordinates
346  if (!_costmap->worldToMapContinuous(
347  goal.pose.position.x,
348  goal.pose.position.y,
349  mx_goal,
350  my_goal))
351  {
353  "Goal Coordinates of(" + std::to_string(goal.pose.position.x) + ", " +
354  std::to_string(goal.pose.position.y) + ") was outside bounds");
355  }
356  unsigned int goal_bin =
357  NodeLattice::motion_table.getClosestAngularBin(tf2::getYaw(goal.pose.orientation));
358  _a_star->setGoal(
359  mx_goal, my_goal, goal_bin,
360  _goal_heading_mode, _coarse_search_resolution);
361 
362  // Setup message
363  nav_msgs::msg::Path plan;
364  plan.header.stamp = _clock->now();
365  plan.header.frame_id = _global_frame;
366  geometry_msgs::msg::PoseStamped pose;
367  pose.header = plan.header;
368  pose.pose.position.z = 0.0;
369  pose.pose.orientation.x = 0.0;
370  pose.pose.orientation.y = 0.0;
371  pose.pose.orientation.z = 0.0;
372  pose.pose.orientation.w = 1.0;
373 
374  // Corner case of start and goal being on the same cell
375  if (std::floor(mx_start) == std::floor(mx_goal) &&
376  std::floor(my_start) == std::floor(my_goal) &&
377  start_bin == goal_bin)
378  {
379  pose.pose = start.pose;
380  pose.pose.orientation = goal.pose.orientation;
381  plan.poses.push_back(pose);
382 
383  // Publish raw path for debug
384  if (_raw_plan_publisher->get_subscription_count() > 0) {
385  _raw_plan_publisher->publish(plan);
386  }
387 
388  return plan;
389  }
390 
391  // Compute plan
392  NodeLattice::CoordinateVector path;
393  int num_iterations = 0;
394  std::string error;
395  std::unique_ptr<std::vector<std::tuple<float, float, float>>> expansions = nullptr;
396  if (_debug_visualizations) {
397  expansions = std::make_unique<std::vector<std::tuple<float, float, float>>>();
398  }
399 
400  // Note: All exceptions thrown are handled by the planner server and returned to the action
401  if (!_a_star->createPath(
402  path, num_iterations,
403  _tolerance / static_cast<float>(_costmap->getResolution()), cancel_checker, expansions.get()))
404  {
405  if (_debug_visualizations) {
406  auto now = _clock->now();
407  geometry_msgs::msg::PoseArray msg;
408  geometry_msgs::msg::Pose msg_pose;
409  msg.header.stamp = now;
410  msg.header.frame_id = _global_frame;
411  for (auto & e : *expansions) {
412  msg_pose.position.x = std::get<0>(e);
413  msg_pose.position.y = std::get<1>(e);
414  msg_pose.orientation = getWorldOrientation(std::get<2>(e));
415  msg.poses.push_back(msg_pose);
416  }
417  _expansions_publisher->publish(msg);
418  }
419 
420  // Note: If the start is blocked only one iteration will occur before failure
421  if (num_iterations == 1) {
422  throw nav2_core::StartOccupied("Start occupied");
423  }
424 
425  if (num_iterations < _a_star->getMaxIterations()) {
426  throw nav2_core::NoValidPathCouldBeFound("no valid path found");
427  } else {
428  throw nav2_core::PlannerTimedOut("exceeded maximum iterations");
429  }
430  }
431 
432  // Convert to world coordinates
433  plan.poses.reserve(path.size());
434  geometry_msgs::msg::PoseStamped last_pose = pose;
435  for (int i = path.size() - 1; i >= 0; --i) {
436  pose.pose = getWorldCoords(path[i].x, path[i].y, _costmap);
437  pose.pose.orientation = getWorldOrientation(path[i].theta);
438  if (fabs(pose.pose.position.x - last_pose.pose.position.x) < 1e-4 &&
439  fabs(pose.pose.position.y - last_pose.pose.position.y) < 1e-4 &&
440  fabs(tf2::getYaw(pose.pose.orientation) - tf2::getYaw(last_pose.pose.orientation)) < 1e-4)
441  {
442  RCLCPP_DEBUG(
443  _logger,
444  "Removed a path from the path due to replication. "
445  "Make sure your minimum control set does not contain duplicate values!");
446  continue;
447  }
448  last_pose = pose;
449  plan.poses.push_back(pose);
450  }
451 
452  // Publish raw path for debug
453  if (_raw_plan_publisher->get_subscription_count() > 0) {
454  _raw_plan_publisher->publish(plan);
455  }
456 
457  if (_debug_visualizations) {
458  auto now = _clock->now();
459  // Publish expansions for debug
460  geometry_msgs::msg::PoseArray msg;
461  geometry_msgs::msg::Pose msg_pose;
462  msg.header.stamp = now;
463  msg.header.frame_id = _global_frame;
464  for (auto & e : *expansions) {
465  msg_pose.position.x = std::get<0>(e);
466  msg_pose.position.y = std::get<1>(e);
467  msg_pose.orientation = getWorldOrientation(std::get<2>(e));
468  msg.poses.push_back(msg_pose);
469  }
470  _expansions_publisher->publish(msg);
471 
472  if (_planned_footprints_publisher->get_subscription_count() > 0) {
473  // Clear all markers first
474  auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
475  visualization_msgs::msg::Marker clear_all_marker;
476  clear_all_marker.action = visualization_msgs::msg::Marker::DELETEALL;
477  marker_array->markers.push_back(clear_all_marker);
478  _planned_footprints_publisher->publish(std::move(marker_array));
479 
480  // Publish smoothed footprints for debug
481  marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
482  for (size_t i = 0; i < plan.poses.size(); i++) {
483  const std::vector<geometry_msgs::msg::Point> edge =
484  transformFootprintToEdges(plan.poses[i].pose, _costmap_ros->getRobotFootprint());
485  marker_array->markers.push_back(createMarker(edge, i, _global_frame, now));
486  }
487  _planned_footprints_publisher->publish(std::move(marker_array));
488  }
489  }
490 
491  // Find how much time we have left to do smoothing
492  steady_clock::time_point b = steady_clock::now();
493  duration<double> time_span = duration_cast<duration<double>>(b - a);
494  double time_remaining = _max_planning_time - static_cast<double>(time_span.count());
495 
496 #ifdef BENCHMARK_TESTING
497  std::cout << "It took " << time_span.count() * 1000 <<
498  " milliseconds with " << num_iterations << " iterations." << std::endl;
499 #endif
500 
501  // Smooth plan
502  if (_smoother && num_iterations > 1) {
503  _smoother->smooth(plan, _costmap, time_remaining);
504  }
505 
506 #ifdef BENCHMARK_TESTING
507  steady_clock::time_point c = steady_clock::now();
508  duration<double> time_span2 = duration_cast<duration<double>>(c - b);
509  std::cout << "It took " << time_span2.count() * 1000 <<
510  " milliseconds to smooth path." << std::endl;
511 #endif
512 
513  if (_debug_visualizations) {
514  if (_smoothed_footprints_publisher->get_subscription_count() > 0) {
515  // Clear all markers first
516  auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
517  visualization_msgs::msg::Marker clear_all_marker;
518  clear_all_marker.action = visualization_msgs::msg::Marker::DELETEALL;
519  marker_array->markers.push_back(clear_all_marker);
520  _smoothed_footprints_publisher->publish(std::move(marker_array));
521 
522  // Publish smoothed footprints for debug
523  marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
524  auto now = _clock->now();
525  for (size_t i = 0; i < plan.poses.size(); i++) {
526  const std::vector<geometry_msgs::msg::Point> edge =
527  transformFootprintToEdges(plan.poses[i].pose, _costmap_ros->getRobotFootprint());
528  marker_array->markers.push_back(createMarker(edge, i, _global_frame, now));
529  }
530  _smoothed_footprints_publisher->publish(std::move(marker_array));
531  }
532  }
533 
534  return plan;
535 }
536 
537 rcl_interfaces::msg::SetParametersResult
538 SmacPlannerLattice::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
539 {
540  rcl_interfaces::msg::SetParametersResult result;
541  std::lock_guard<std::mutex> lock_reinit(_mutex);
542 
543  bool reinit_a_star = false;
544  bool reinit_smoother = false;
545 
546  for (auto parameter : parameters) {
547  const auto & param_type = parameter.get_type();
548  const auto & param_name = parameter.get_name();
549  if(param_name.find(_name + ".") != 0) {
550  continue;
551  }
552  if (param_type == ParameterType::PARAMETER_DOUBLE) {
553  if (param_name == _name + ".max_planning_time") {
554  reinit_a_star = true;
555  _max_planning_time = parameter.as_double();
556  } else if (param_name == _name + ".tolerance") {
557  _tolerance = static_cast<float>(parameter.as_double());
558  } else if (param_name == _name + ".lookup_table_size") {
559  reinit_a_star = true;
560  _lookup_table_size = parameter.as_double();
561  } else if (param_name == _name + ".reverse_penalty") {
562  reinit_a_star = true;
563  _search_info.reverse_penalty = static_cast<float>(parameter.as_double());
564  } else if (param_name == _name + ".change_penalty") {
565  reinit_a_star = true;
566  _search_info.change_penalty = static_cast<float>(parameter.as_double());
567  } else if (param_name == _name + ".non_straight_penalty") {
568  reinit_a_star = true;
569  _search_info.non_straight_penalty = static_cast<float>(parameter.as_double());
570  } else if (param_name == _name + ".cost_penalty") {
571  reinit_a_star = true;
572  _search_info.cost_penalty = static_cast<float>(parameter.as_double());
573  } else if (param_name == _name + ".rotation_penalty") {
574  reinit_a_star = true;
575  _search_info.rotation_penalty = static_cast<float>(parameter.as_double());
576  } else if (param_name == _name + ".analytic_expansion_ratio") {
577  reinit_a_star = true;
578  _search_info.analytic_expansion_ratio = static_cast<float>(parameter.as_double());
579  } else if (param_name == _name + ".analytic_expansion_max_length") {
580  reinit_a_star = true;
581  _search_info.analytic_expansion_max_length =
582  static_cast<float>(parameter.as_double()) / _costmap->getResolution();
583  } else if (param_name == _name + ".analytic_expansion_max_cost") {
584  reinit_a_star = true;
585  _search_info.analytic_expansion_max_cost = static_cast<float>(parameter.as_double());
586  }
587  } else if (param_type == ParameterType::PARAMETER_BOOL) {
588  if (param_name == _name + ".allow_unknown") {
589  reinit_a_star = true;
590  _allow_unknown = parameter.as_bool();
591  } else if (param_name == _name + ".cache_obstacle_heuristic") {
592  reinit_a_star = true;
593  _search_info.cache_obstacle_heuristic = parameter.as_bool();
594  } else if (param_name == _name + ".allow_reverse_expansion") {
595  reinit_a_star = true;
596  _search_info.allow_reverse_expansion = parameter.as_bool();
597  } else if (param_name == _name + ".smooth_path") {
598  if (parameter.as_bool()) {
599  reinit_smoother = true;
600  } else {
601  _smoother.reset();
602  }
603  } else if (param_name == _name + ".analytic_expansion_max_cost_override") {
604  _search_info.analytic_expansion_max_cost_override = parameter.as_bool();
605  reinit_a_star = true;
606  }
607  } else if (param_type == ParameterType::PARAMETER_INTEGER) {
608  if (param_name == _name + ".max_iterations") {
609  reinit_a_star = true;
610  _max_iterations = parameter.as_int();
611  if (_max_iterations <= 0) {
612  RCLCPP_INFO(
613  _logger, "maximum iteration selected as <= 0, "
614  "disabling maximum iterations.");
615  _max_iterations = std::numeric_limits<int>::max();
616  }
617  } else if (param_name == _name + ".max_on_approach_iterations") {
618  reinit_a_star = true;
619  _max_on_approach_iterations = parameter.as_int();
620  if (_max_on_approach_iterations <= 0) {
621  RCLCPP_INFO(
622  _logger, "On approach iteration selected as <= 0, "
623  "disabling tolerance and on approach iterations.");
624  _max_on_approach_iterations = std::numeric_limits<int>::max();
625  }
626  } else if (param_name == _name + ".terminal_checking_interval") {
627  reinit_a_star = true;
628  _terminal_checking_interval = parameter.as_int();
629  } else if (param_name == _name + ".coarse_search_resolution") {
630  _coarse_search_resolution = parameter.as_int();
631  if (_coarse_search_resolution <= 0) {
632  RCLCPP_WARN(
633  _logger, "coarse iteration resolution selected as <= 0. "
634  "Disabling course research!"
635  );
636  _coarse_search_resolution = 1;
637  }
638  if (_metadata.number_of_headings % _coarse_search_resolution != 0) {
639  RCLCPP_WARN(
640  _logger,
641  "coarse iteration should be an increment of the number<"
642  " of angular bins configured. Disabling course research!"
643  );
644  _coarse_search_resolution = 1;
645  }
646  }
647  } else if (param_type == ParameterType::PARAMETER_STRING) {
648  if (param_name == _name + ".lattice_filepath") {
649  reinit_a_star = true;
650  if (_smoother) {
651  reinit_smoother = true;
652  }
653  _search_info.lattice_filepath = parameter.as_string();
654  _metadata = LatticeMotionTable::getLatticeMetadata(_search_info.lattice_filepath);
655  _search_info.minimum_turning_radius =
656  _metadata.min_turning_radius / (_costmap->getResolution());
657  if (_metadata.number_of_headings % _coarse_search_resolution != 0) {
658  RCLCPP_WARN(
659  _logger, "coarse iteration should be an increment of the number "
660  "of angular bins configured. Disabling course research!"
661  );
662  _coarse_search_resolution = 1;
663  }
664  } else if (param_name == _name + ".goal_heading_mode") {
665  std::string goal_heading_type = parameter.as_string();
666  GoalHeadingMode goal_heading_mode = fromStringToGH(goal_heading_type);
667  RCLCPP_INFO(
668  _logger,
669  "GoalHeadingMode type set to '%s'.",
670  goal_heading_type.c_str());
671  if (goal_heading_mode == GoalHeadingMode::UNKNOWN) {
672  RCLCPP_WARN(
673  _logger,
674  "Unable to get GoalHeader type. Given '%s', "
675  "Valid options are DEFAULT, BIDIRECTIONAL, ALL_DIRECTION. ",
676  goal_heading_type.c_str());
677  } else {
678  _goal_heading_mode = goal_heading_mode;
679  }
680  }
681  }
682  }
683 
684  // Re-init if needed with mutex lock (to avoid re-init while creating a plan)
685  if (reinit_a_star || reinit_smoother) {
686  // convert to grid coordinates
687  _search_info.minimum_turning_radius =
688  _metadata.min_turning_radius / (_costmap->getResolution());
689  float lookup_table_dim =
690  static_cast<float>(_lookup_table_size) /
691  static_cast<float>(_costmap->getResolution());
692 
693  // Make sure its a whole number
694  lookup_table_dim = static_cast<float>(static_cast<int>(lookup_table_dim));
695 
696  // Make sure its an odd number
697  if (static_cast<int>(lookup_table_dim) % 2 == 0) {
698  RCLCPP_INFO(
699  _logger,
700  "Even sized heuristic lookup table size set %f, increasing size by 1 to make odd",
701  lookup_table_dim);
702  lookup_table_dim += 1.0;
703  }
704 
705  // Re-Initialize smoother
706  if (reinit_smoother) {
707  auto node = _node.lock();
708  SmootherParams params;
709  params.get(node, _name);
710  _smoother = std::make_unique<Smoother>(params);
711  _smoother->initialize(_metadata.min_turning_radius);
712  }
713 
714  // Re-Initialize A* template
715  if (reinit_a_star) {
716  _a_star = std::make_unique<AStarAlgorithm<NodeLattice>>(_motion_model, _search_info);
717  _a_star->initialize(
718  _allow_unknown,
719  _max_iterations,
720  _max_on_approach_iterations,
721  _terminal_checking_interval,
722  _max_planning_time,
723  lookup_table_dim,
724  _metadata.number_of_headings);
725  }
726  }
727 
728  result.successful = true;
729  return result;
730 }
731 
732 } // namespace nav2_smac_planner
733 
734 #include "pluginlib/class_list_macros.hpp"
Abstract interface for global planners to adhere to with pluginlib.
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
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 deactivate() override
Deactivate lifecycle node.
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.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
void cleanup() override
Cleanup lifecycle node.
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.
void activate() override
Activate lifecycle node.
static LatticeMetadata getLatticeMetadata(const std::string &lattice_filepath)
Get file metadata needed.
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