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