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