Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
a_star.cpp
1 // Copyright (c) 2020, Samsung Research America
2 // Copyright (c) 2020, Applied Electric Vehicles Pty Ltd
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 <omp.h>
17 #include <cmath>
18 #include <stdexcept>
19 #include <memory>
20 #include <algorithm>
21 #include <limits>
22 #include <type_traits>
23 #include <chrono>
24 #include <thread>
25 #include <utility>
26 #include <vector>
27 
28 #include "nav2_smac_planner/a_star.hpp"
29 using namespace std::chrono; // NOLINT
30 
31 namespace nav2_smac_planner
32 {
33 
34 template<typename NodeT>
36  const MotionModel & motion_model,
37  const SearchInfo & search_info)
38 : _traverse_unknown(true),
39  _is_initialized(false),
40  _max_iterations(0),
41  _terminal_checking_interval(5000),
42  _max_planning_time(0),
43  _x_size(0),
44  _y_size(0),
45  _search_info(search_info),
46  _start(nullptr),
47  _goal_manager(GoalManagerT()),
48  _motion_model(motion_model)
49 {
50  _graph.reserve(100000);
51 }
52 
53 template<typename NodeT>
55 {
56 }
57 
58 template<typename NodeT>
60  const bool & allow_unknown,
61  int & max_iterations,
62  const int & max_on_approach_iterations,
63  const int & terminal_checking_interval,
64  const double & max_planning_time,
65  const float & lookup_table_size,
66  const unsigned int & dim_3_size)
67 {
68  _traverse_unknown = allow_unknown;
69  _max_iterations = max_iterations;
70  _max_on_approach_iterations = max_on_approach_iterations;
71  _terminal_checking_interval = terminal_checking_interval;
72  _max_planning_time = max_planning_time;
73  if (!_is_initialized) {
74  NodeT::precomputeDistanceHeuristic(lookup_table_size, _motion_model, dim_3_size, _search_info);
75  }
76  _is_initialized = true;
77  _dim3_size = dim_3_size;
78  _expander = std::make_unique<AnalyticExpansion<NodeT>>(
79  _motion_model, _search_info, _traverse_unknown, _dim3_size);
80 }
81 
82 template<>
84  const bool & allow_unknown,
85  int & max_iterations,
86  const int & max_on_approach_iterations,
87  const int & terminal_checking_interval,
88  const double & max_planning_time,
89  const float & /*lookup_table_size*/,
90  const unsigned int & dim_3_size)
91 {
92  _traverse_unknown = allow_unknown;
93  _max_iterations = max_iterations;
94  _max_on_approach_iterations = max_on_approach_iterations;
95  _terminal_checking_interval = terminal_checking_interval;
96  _max_planning_time = max_planning_time;
97 
98  if (dim_3_size != 1) {
99  throw std::runtime_error("Node type Node2D cannot be given non-1 dim 3 quantization.");
100  }
101  _dim3_size = dim_3_size;
102  _expander = std::make_unique<AnalyticExpansion<Node2D>>(
103  _motion_model, _search_info, _traverse_unknown, _dim3_size);
104 }
105 
106 template<typename NodeT>
108 {
109  _collision_checker = collision_checker;
110  _costmap = collision_checker->getCostmap();
111  unsigned int x_size = _costmap->getSizeInCellsX();
112  unsigned int y_size = _costmap->getSizeInCellsY();
113 
114  clearGraph();
115 
116  if (getSizeX() != x_size || getSizeY() != y_size) {
117  _x_size = x_size;
118  _y_size = y_size;
119  NodeT::initMotionModel(_motion_model, _x_size, _y_size, _dim3_size, _search_info);
120  }
121  _expander->setCollisionChecker(_collision_checker);
122 }
123 
124 template<typename NodeT>
125 typename AStarAlgorithm<NodeT>::NodePtr AStarAlgorithm<NodeT>::addToGraph(
126  const uint64_t & index)
127 {
128  auto iter = _graph.find(index);
129  if (iter != _graph.end()) {
130  return &(iter->second);
131  }
132 
133  return &(_graph.emplace(index, NodeT(index)).first->second);
134 }
135 
136 template<>
138  const float & mx,
139  const float & my,
140  const unsigned int & dim_3)
141 {
142  if (dim_3 != 0) {
143  throw std::runtime_error("Node type Node2D cannot be given non-zero starting dim 3.");
144  }
145  _start = addToGraph(
147  static_cast<unsigned int>(mx),
148  static_cast<unsigned int>(my),
149  getSizeX()));
150 }
151 
152 template<typename NodeT>
154  const float & mx,
155  const float & my,
156  const unsigned int & dim_3)
157 {
158  _start = addToGraph(
159  NodeT::getIndex(
160  static_cast<unsigned int>(mx),
161  static_cast<unsigned int>(my),
162  dim_3));
163  _start->setPose(Coordinates(mx, my, dim_3));
164 }
165 
166 template<>
168  const NodePtr & node,
169  std::vector<std::tuple<float, float, float>> * expansions_log)
170 {
171  Node2D::Coordinates coords = node->getCoords(node->getIndex());
172  expansions_log->emplace_back(
173  _costmap->getOriginX() + ((coords.x + 0.5) * _costmap->getResolution()),
174  _costmap->getOriginY() + ((coords.y + 0.5) * _costmap->getResolution()),
175  0.0);
176 }
177 
178 template<typename NodeT>
180  const NodePtr & node,
181  std::vector<std::tuple<float, float, float>> * expansions_log)
182 {
183  typename NodeT::Coordinates coords = node->pose;
184  expansions_log->emplace_back(
185  _costmap->getOriginX() + ((coords.x + 0.5) * _costmap->getResolution()),
186  _costmap->getOriginY() + ((coords.y + 0.5) * _costmap->getResolution()),
187  NodeT::motion_table.getAngleFromBin(coords.theta));
188 }
189 
190 template<>
192  const float & mx,
193  const float & my,
194  const unsigned int & dim_3,
195  const GoalHeadingMode & /*goal_heading_mode*/,
196  const int & /*coarse_search_resolution*/)
197 {
198  if (dim_3 != 0) {
199  throw std::runtime_error("Node type Node2D cannot be given non-zero goal dim 3.");
200  }
201  _goal_manager.clear();
202  auto goal = addToGraph(
204  static_cast<unsigned int>(mx),
205  static_cast<unsigned int>(my),
206  getSizeX()));
207 
208  goal->setPose(Node2D::Coordinates(mx, my));
209  _goal_manager.addGoal(goal);
210 
211  _coarse_search_resolution = 1;
212 }
213 
214 template<typename NodeT>
216  const float & mx,
217  const float & my,
218  const unsigned int & dim_3,
219  const GoalHeadingMode & goal_heading_mode,
220  const int & coarse_search_resolution)
221 {
222  // Default to minimal resolution unless overridden for ALL_DIRECTION
223  _coarse_search_resolution = 1;
224 
225  _goal_manager.clear();
226  Coordinates ref_goal_coord(mx, my, static_cast<float>(dim_3));
227 
228  if (!_search_info.cache_obstacle_heuristic ||
229  _goal_manager.hasGoalChanged(ref_goal_coord))
230  {
231  if (!_start) {
232  throw std::runtime_error("Start must be set before goal.");
233  }
234 
235  NodeT::resetObstacleHeuristic(
236  _collision_checker->getCostmapROS(), _start->pose.x, _start->pose.y, mx, my);
237  }
238 
239  _goal_manager.setRefGoalCoordinates(ref_goal_coord);
240 
241  unsigned int num_bins = NodeT::motion_table.num_angle_quantization;
242  // set goal based on heading mode
243  switch (goal_heading_mode) {
244  case GoalHeadingMode::DEFAULT: {
245  // add a single goal node with single heading
246  auto goal = addToGraph(
247  NodeT::getIndex(
248  static_cast<unsigned int>(mx),
249  static_cast<unsigned int>(my),
250  dim_3));
251  goal->setPose(typename NodeT::Coordinates(mx, my, static_cast<float>(dim_3)));
252  _goal_manager.addGoal(goal);
253  break;
254  }
255 
256  case GoalHeadingMode::BIDIRECTIONAL: {
257  // Add two goals, one for each direction
258  // add goal in original direction
259  auto goal = addToGraph(
260  NodeT::getIndex(
261  static_cast<unsigned int>(mx),
262  static_cast<unsigned int>(my),
263  dim_3));
264  goal->setPose(typename NodeT::Coordinates(mx, my, static_cast<float>(dim_3)));
265  _goal_manager.addGoal(goal);
266 
267  // Add goal node in opposite (180°) direction
268  unsigned int opposite_heading = (dim_3 + (num_bins / 2)) % num_bins;
269  auto opposite_goal = addToGraph(
270  NodeT::getIndex(
271  static_cast<unsigned int>(mx),
272  static_cast<unsigned int>(my),
273  opposite_heading));
274  opposite_goal->setPose(
275  typename NodeT::Coordinates(mx, my, static_cast<float>(opposite_heading)));
276  _goal_manager.addGoal(opposite_goal);
277  break;
278  }
279 
280  case GoalHeadingMode::ALL_DIRECTION: {
281  // Set the coarse search resolution only for all direction
282  _coarse_search_resolution = coarse_search_resolution;
283 
284  // Add goal nodes for all headings
285  for (unsigned int i = 0; i < num_bins; ++i) {
286  auto goal = addToGraph(
287  NodeT::getIndex(
288  static_cast<unsigned int>(mx),
289  static_cast<unsigned int>(my),
290  i));
291  goal->setPose(typename NodeT::Coordinates(mx, my, static_cast<float>(i)));
292  _goal_manager.addGoal(goal);
293  }
294  break;
295  }
296  case GoalHeadingMode::UNKNOWN:
297  throw std::runtime_error("Goal heading is UNKNOWN.");
298  }
299 }
300 
301 template<typename NodeT>
303 {
304  // Check if graph was filled in
305  if (_graph.empty()) {
306  throw std::runtime_error("Failed to compute path, no costmap given.");
307  }
308 
309  // Check if points were filled in
310  if (!_start || _goal_manager.goalsIsEmpty()) {
311  throw std::runtime_error("Failed to compute path, no valid start or goal given.");
312  }
313 
314  // remove invalid goals
315  _goal_manager.removeInvalidGoals(getToleranceHeuristic(), _collision_checker, _traverse_unknown);
316 
317  // Check if ending point is valid
318  if (_goal_manager.getGoalsSet().empty()) {
319  throw nav2_core::GoalOccupied("Goal was in lethal cost");
320  }
321 
322  // Note: We do not check the if the start is valid because it is cleared
323  return true;
324 }
325 
326 template<typename NodeT>
328  CoordinateVector & path, int & iterations,
329  const float & tolerance,
330  std::function<bool()> cancel_checker,
331  std::vector<std::tuple<float, float, float>> * expansions_log)
332 {
333  steady_clock::time_point start_time = steady_clock::now();
334  _tolerance = tolerance;
335  _best_heuristic_node = {std::numeric_limits<float>::max(), 0};
336  clearQueue();
337 
338  if (!areInputsValid()) {
339  return false;
340  }
341 
342  NodeVector coarse_check_goals, fine_check_goals;
343  _goal_manager.prepareGoalsForAnalyticExpansion(coarse_check_goals, fine_check_goals,
344  _coarse_search_resolution);
345 
346  // 0) Add starting point to the open set
347  addNode(0.0, getStart());
348  getStart()->setAccumulatedCost(0.0);
349 
350  // Optimization: preallocate all variables
351  NodePtr current_node = nullptr;
352  NodePtr neighbor = nullptr;
353  NodePtr expansion_result = nullptr;
354  float g_cost = 0.0;
355  NodeVector neighbors;
356  int approach_iterations = 0;
357  NeighborIterator neighbor_iterator;
358  int analytic_iterations = 0;
359  int closest_distance = std::numeric_limits<int>::max();
360 
361  // Given an index, return a node ptr reference if its collision-free and valid
362  const uint64_t max_index = static_cast<uint64_t>(getSizeX()) *
363  static_cast<uint64_t>(getSizeY()) *
364  static_cast<uint64_t>(getSizeDim3());
365  NodeGetter neighborGetter =
366  [&, this](const uint64_t & index, NodePtr & neighbor_rtn) -> bool
367  {
368  if (index >= max_index) {
369  return false;
370  }
371 
372  neighbor_rtn = addToGraph(index);
373  return true;
374  };
375 
376  while (iterations < getMaxIterations() && !_queue.empty()) {
377  // Check for planning timeout and cancel only on every Nth iteration
378  if (iterations % _terminal_checking_interval == 0) {
379  if (cancel_checker()) {
380  throw nav2_core::PlannerCancelled("Planner was cancelled");
381  }
382  std::chrono::duration<double> planning_duration =
383  std::chrono::duration_cast<std::chrono::duration<double>>(steady_clock::now() - start_time);
384  if (static_cast<double>(planning_duration.count()) >= _max_planning_time) {
385  return false;
386  }
387  }
388 
389  // 1) Pick Nbest from O s.t. min(f(Nbest)), remove from queue
390  current_node = getNextNode();
391 
392  // Save current node coordinates for debug
393  if (expansions_log) {
394  populateExpansionsLog(current_node, expansions_log);
395  }
396 
397  // We allow for nodes to be queued multiple times in case
398  // shorter paths result in it, but we can visit only once
399  // Also a chance to perform last-checks necessary.
400  if (onVisitationCheckNode(current_node)) {
401  continue;
402  }
403 
404  iterations++;
405 
406  // 2) Mark Nbest as visited
407  current_node->visited();
408 
409  // 2.1) Use an analytic expansion (if available) to generate a path
410  expansion_result = nullptr;
411  expansion_result = _expander->tryAnalyticExpansion(
412  current_node, coarse_check_goals, fine_check_goals,
413  _goal_manager.getGoalsCoordinates(), neighborGetter, analytic_iterations, closest_distance);
414  if (expansion_result != nullptr) {
415  current_node = expansion_result;
416  }
417 
418  // 3) Check if we're at the goal, backtrace if required
419  if (_goal_manager.isGoal(current_node)) {
420  return current_node->backtracePath(path);
421  } else if (_best_heuristic_node.first < getToleranceHeuristic()) {
422  // Optimization: Let us find when in tolerance and refine within reason
423  approach_iterations++;
424  if (approach_iterations >= getOnApproachMaxIterations()) {
425  return _graph.at(_best_heuristic_node.second).backtracePath(path);
426  }
427  }
428 
429  // 4) Expand neighbors of Nbest not visited
430  neighbors.clear();
431  current_node->getNeighbors(neighborGetter, _collision_checker, _traverse_unknown, neighbors);
432 
433  for (neighbor_iterator = neighbors.begin();
434  neighbor_iterator != neighbors.end(); ++neighbor_iterator)
435  {
436  neighbor = *neighbor_iterator;
437 
438  // 4.1) Compute the cost to go to this node
439  g_cost = current_node->getAccumulatedCost() + current_node->getTraversalCost(neighbor);
440 
441  // 4.2) If this is a lower cost than prior, we set this as the new cost and new approach
442  if (g_cost < neighbor->getAccumulatedCost()) {
443  neighbor->setAccumulatedCost(g_cost);
444  neighbor->parent = current_node;
445 
446  // 4.3) Add to queue with heuristic cost
447  addNode(g_cost + getHeuristicCost(neighbor), neighbor);
448  }
449  }
450  }
451 
452  if (_best_heuristic_node.first < getToleranceHeuristic()) {
453  // If we run out of search options, return the path that is closest, if within tolerance.
454  return _graph.at(_best_heuristic_node.second).backtracePath(path);
455  }
456 
457  return false;
458 }
459 
460 template<typename NodeT>
461 typename AStarAlgorithm<NodeT>::NodePtr & AStarAlgorithm<NodeT>::getStart()
462 {
463  return _start;
464 }
465 
466 template<typename NodeT>
467 typename AStarAlgorithm<NodeT>::NodePtr AStarAlgorithm<NodeT>::getNextNode()
468 {
469  NodeBasic<NodeT> node = _queue.top().second;
470  _queue.pop();
471  node.processSearchNode();
472  return node.graph_node_ptr;
473 }
474 
475 template<typename NodeT>
476 void AStarAlgorithm<NodeT>::addNode(const float & cost, NodePtr & node)
477 {
478  NodeBasic<NodeT> queued_node(node->getIndex());
479  queued_node.populateSearchNode(node);
480  _queue.emplace(cost, queued_node);
481 }
482 
483 template<typename NodeT>
484 float AStarAlgorithm<NodeT>::getHeuristicCost(const NodePtr & node)
485 {
486  const Coordinates node_coords =
487  NodeT::getCoords(node->getIndex(), getSizeX(), getSizeDim3());
488  float heuristic = NodeT::getHeuristicCost(node_coords, _goal_manager.getGoalsCoordinates());
489  if (heuristic < _best_heuristic_node.first) {
490  _best_heuristic_node = {heuristic, node->getIndex()};
491  }
492 
493  return heuristic;
494 }
495 
496 template<typename NodeT>
497 bool AStarAlgorithm<NodeT>::onVisitationCheckNode(const NodePtr & current_node)
498 {
499  return current_node->wasVisited();
500 }
501 
502 template<typename NodeT>
504 {
505  NodeQueue q;
506  std::swap(_queue, q);
507 }
508 
509 template<typename NodeT>
511 {
512  Graph g;
513  std::swap(_graph, g);
514  _graph.reserve(100000);
515 }
516 
517 template<typename NodeT>
519 {
520  return _max_iterations;
521 }
522 
523 template<typename NodeT>
525 {
526  return _max_on_approach_iterations;
527 }
528 
529 template<typename NodeT>
531 {
532  return _tolerance;
533 }
534 
535 template<typename NodeT>
537 {
538  return _x_size;
539 }
540 
541 template<typename NodeT>
543 {
544  return _y_size;
545 }
546 
547 template<typename NodeT>
549 {
550  return _dim3_size;
551 }
552 
553 template<typename NodeT>
555 {
556  return _coarse_search_resolution;
557 }
558 
559 template<typename NodeT>
561 {
562  return _goal_manager;
563 }
564 
565 // Instantiate algorithm for the supported template types
566 template class AStarAlgorithm<Node2D>;
567 template class AStarAlgorithm<NodeHybrid>;
568 template class AStarAlgorithm<NodeLattice>;
569 
570 } // namespace nav2_smac_planner
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:546
CostmapT getCostmap()
Get the current costmap object.
An A* implementation for planning in a costmap. Templated based on the Node type.
Definition: a_star.hpp:48
~AStarAlgorithm()
A destructor for nav2_smac_planner::AStarAlgorithm.
Definition: a_star.cpp:54
unsigned int & getSizeDim3()
Get number of angle quantization bins (SE2) or Z coordinate (XYZ)
Definition: a_star.cpp:548
unsigned int getCoarseSearchResolution()
Get the resolution of the coarse search.
Definition: a_star.cpp:554
bool createPath(CoordinateVector &path, int &num_iterations, const float &tolerance, std::function< bool()> cancel_checker, std::vector< std::tuple< float, float, float >> *expansions_log=nullptr)
Creating path from given costmap, start, and goal.
Definition: a_star.cpp:327
int & getOnApproachMaxIterations()
Get maximum number of on-approach iterations after within threshold.
Definition: a_star.cpp:524
bool onVisitationCheckNode(const NodePtr &node)
Check if node has been visited.
Definition: a_star.cpp:497
void setCollisionChecker(GridCollisionChecker *collision_checker)
Sets the collision checker to use.
Definition: a_star.cpp:107
void initialize(const bool &allow_unknown, int &max_iterations, const int &max_on_approach_iterations, const int &terminal_checking_interval, const double &max_planning_time, const float &lookup_table_size, const unsigned int &dim_3_size)
Initialization of the planner with defaults.
Definition: a_star.cpp:59
NodePtr getNextNode()
Get pointer to next goal in open set.
Definition: a_star.cpp:467
bool areInputsValid()
Check if inputs to planner are valid.
Definition: a_star.cpp:302
void clearQueue()
Clear heuristic queue of nodes to search.
Definition: a_star.cpp:503
void populateExpansionsLog(const NodePtr &node, std::vector< std::tuple< float, float, float >> *expansions_log)
Populate a debug log of expansions for Hybrid-A* for visualization.
Definition: a_star.cpp:179
int & getMaxIterations()
Get maximum number of iterations to plan.
Definition: a_star.cpp:518
void clearGraph()
Clear graph of nodes searched.
Definition: a_star.cpp:510
unsigned int & getSizeY()
Get size of graph in Y.
Definition: a_star.cpp:542
void setStart(const float &mx, const float &my, const unsigned int &dim_3)
Set the starting pose for planning, as a node index.
Definition: a_star.cpp:153
void addNode(const float &cost, NodePtr &node)
Add a node to the open set.
Definition: a_star.cpp:476
GoalManagerT getGoalManager()
Get the goals manager class.
Definition: a_star.cpp:560
unsigned int & getSizeX()
Get size of graph in X.
Definition: a_star.cpp:536
float getHeuristicCost(const NodePtr &node)
Get cost of heuristic of node.
Definition: a_star.cpp:484
float & getToleranceHeuristic()
Get tolerance, in node nodes.
Definition: a_star.cpp:530
NodePtr & getStart()
Get pointer reference to starting node.
Definition: a_star.cpp:461
NodePtr addToGraph(const uint64_t &index)
Adds node to graph.
Definition: a_star.cpp:125
void setGoal(const float &mx, const float &my, const unsigned int &dim_3, const GoalHeadingMode &goal_heading_mode=GoalHeadingMode::DEFAULT, const int &coarse_search_resolution=1)
Set the goal for planning, as a node index.
Definition: a_star.cpp:215
Responsible for managing multiple variables storing information on the goal.
A costmap grid collision checker.
uint64_t getIndex()
Gets cell index.
Definition: node_2d.hpp:176
NodeBasic implementation for priority queue insertion.
Definition: node_basic.hpp:34
void populateSearchNode(NodeT *&node)
Take a NodeBasic and populate it with any necessary state cached in the queue for NodeT.
void processSearchNode()
Take a NodeBasic and populate it with any necessary state cached in the queue for NodeTs.
Definition: node_basic.cpp:21
Node2D implementation of coordinate structure.
Definition: node_2d.hpp:47
Search properties and penalties.
Definition: types.hpp:36