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