21 #include <type_traits>
27 #include "nav2_smac_planner/a_star.hpp"
28 using namespace std::chrono;
30 namespace nav2_smac_planner
33 template<
typename NodeT>
35 const MotionModel & motion_model,
37 : _traverse_unknown(true),
38 _is_initialized(false),
40 _terminal_checking_interval(5000),
41 _max_planning_time(0),
44 _search_info(search_info),
47 _motion_model(motion_model)
49 _graph.reserve(100000);
52 template<
typename NodeT>
57 template<
typename NodeT>
59 const bool & allow_unknown,
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)
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);
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);
83 const bool & allow_unknown,
85 const int & max_on_approach_iterations,
86 const int & terminal_checking_interval,
87 const double & max_planning_time,
89 const unsigned int & dim_3_size)
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;
97 if (dim_3_size != 1) {
98 throw std::runtime_error(
"Node type Node2D cannot be given non-1 dim 3 quantization.");
100 _dim3_size = dim_3_size;
101 _expander = std::make_unique<AnalyticExpansion<Node2D>>(
102 _motion_model, _search_info, _traverse_unknown, _dim3_size);
105 template<
typename NodeT>
108 _collision_checker = collision_checker;
111 unsigned int y_size = _costmap->getSizeInCellsY();
115 if (getSizeX() != x_size || getSizeY() != y_size) {
118 NodeT::initMotionModel(_motion_model, _x_size, _y_size, _dim3_size, _search_info);
120 _expander->setCollisionChecker(_collision_checker);
123 template<
typename NodeT>
125 const uint64_t & index)
127 auto iter = _graph.find(index);
128 if (iter != _graph.end()) {
129 return &(iter->second);
132 return &(_graph.emplace(index, NodeT(index)).first->second);
139 const unsigned int & dim_3)
142 throw std::runtime_error(
"Node type Node2D cannot be given non-zero starting dim 3.");
146 static_cast<unsigned int>(mx),
147 static_cast<unsigned int>(my),
151 template<
typename NodeT>
155 const unsigned int & dim_3)
159 static_cast<unsigned int>(mx),
160 static_cast<unsigned int>(my),
162 _start->setPose(Coordinates(mx, my, dim_3));
167 const NodePtr & node,
168 std::vector<std::tuple<float, float, float>> * expansions_log)
171 expansions_log->emplace_back(
172 _costmap->getOriginX() + ((coords.x + 0.5) * _costmap->getResolution()),
173 _costmap->getOriginY() + ((coords.y + 0.5) * _costmap->getResolution()),
177 template<
typename NodeT>
179 const NodePtr & node,
180 std::vector<std::tuple<float, float, float>> * expansions_log)
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));
193 const unsigned int & dim_3,
194 const GoalHeadingMode & ,
198 throw std::runtime_error(
"Node type Node2D cannot be given non-zero goal dim 3.");
200 _goal_manager.clear();
201 auto goal = addToGraph(
203 static_cast<unsigned int>(mx),
204 static_cast<unsigned int>(my),
207 goal->setPose(Node2D::Coordinates(mx, my));
208 _goal_manager.addGoal(goal);
210 _coarse_search_resolution = 1;
213 template<
typename NodeT>
217 const unsigned int & dim_3,
218 const GoalHeadingMode & goal_heading_mode,
219 const int & coarse_search_resolution)
222 _coarse_search_resolution = 1;
224 _goal_manager.clear();
225 Coordinates ref_goal_coord(mx, my,
static_cast<float>(dim_3));
227 if (!_search_info.cache_obstacle_heuristic ||
228 _goal_manager.hasGoalChanged(ref_goal_coord))
231 throw std::runtime_error(
"Start must be set before goal.");
234 NodeT::resetObstacleHeuristic(
235 _collision_checker->getCostmapROS(), _start->pose.x, _start->pose.y, mx, my);
238 _goal_manager.setRefGoalCoordinates(ref_goal_coord);
240 unsigned int num_bins = NodeT::motion_table.num_angle_quantization;
242 switch (goal_heading_mode) {
243 case GoalHeadingMode::DEFAULT: {
245 auto goal = addToGraph(
247 static_cast<unsigned int>(mx),
248 static_cast<unsigned int>(my),
250 goal->setPose(
typename NodeT::Coordinates(mx, my,
static_cast<float>(dim_3)));
251 _goal_manager.addGoal(goal);
255 case GoalHeadingMode::BIDIRECTIONAL: {
258 auto goal = addToGraph(
260 static_cast<unsigned int>(mx),
261 static_cast<unsigned int>(my),
263 goal->setPose(
typename NodeT::Coordinates(mx, my,
static_cast<float>(dim_3)));
264 _goal_manager.addGoal(goal);
267 unsigned int opposite_heading = (dim_3 + (num_bins / 2)) % num_bins;
268 auto opposite_goal = addToGraph(
270 static_cast<unsigned int>(mx),
271 static_cast<unsigned int>(my),
273 opposite_goal->setPose(
274 typename NodeT::Coordinates(mx, my,
static_cast<float>(opposite_heading)));
275 _goal_manager.addGoal(opposite_goal);
279 case GoalHeadingMode::ALL_DIRECTION: {
281 _coarse_search_resolution = coarse_search_resolution;
284 for (
unsigned int i = 0; i < num_bins; ++i) {
285 auto goal = addToGraph(
287 static_cast<unsigned int>(mx),
288 static_cast<unsigned int>(my),
290 goal->setPose(
typename NodeT::Coordinates(mx, my,
static_cast<float>(i)));
291 _goal_manager.addGoal(goal);
295 case GoalHeadingMode::UNKNOWN:
296 throw std::runtime_error(
"Goal heading is UNKNOWN.");
300 template<
typename NodeT>
304 if (_graph.empty()) {
305 throw std::runtime_error(
"Failed to compute path, no costmap given.");
309 if (!_start || _goal_manager.goalsIsEmpty()) {
310 throw std::runtime_error(
"Failed to compute path, no valid start or goal given.");
314 _goal_manager.removeInvalidGoals(getToleranceHeuristic(), _collision_checker, _traverse_unknown);
317 if (_goal_manager.getGoalsSet().empty()) {
325 template<
typename NodeT>
328 if (_best_heuristic_node.first < getToleranceHeuristic()) {
329 _graph.at(_best_heuristic_node.second).backtracePath(path);
336 template<
typename NodeT>
338 CoordinateVector & path,
int & iterations,
339 const float & tolerance,
340 std::function<
bool()> cancel_checker,
341 std::vector<std::tuple<float, float, float>> * expansions_log)
343 steady_clock::time_point start_time = steady_clock::now();
344 _tolerance = tolerance;
345 _best_heuristic_node = {std::numeric_limits<float>::max(), 0};
348 if (!areInputsValid()) {
352 NodeVector coarse_check_goals, fine_check_goals;
353 _goal_manager.prepareGoalsForAnalyticExpansion(coarse_check_goals, fine_check_goals,
354 _coarse_search_resolution);
357 addNode(0.0, getStart());
358 getStart()->setAccumulatedCost(0.0);
361 NodePtr current_node =
nullptr;
362 NodePtr neighbor =
nullptr;
363 NodePtr expansion_result =
nullptr;
365 NodeVector neighbors;
366 int approach_iterations = 0;
367 NeighborIterator neighbor_iterator;
368 int analytic_iterations = 0;
369 int closest_distance = std::numeric_limits<int>::max();
372 const uint64_t max_index =
static_cast<uint64_t
>(getSizeX()) *
373 static_cast<uint64_t
>(getSizeY()) *
374 static_cast<uint64_t
>(getSizeDim3());
375 NodeGetter neighborGetter =
376 [&,
this](
const uint64_t & index, NodePtr & neighbor_rtn) ->
bool
378 if (index >= max_index) {
382 neighbor_rtn = addToGraph(index);
386 while (iterations < getMaxIterations() && !_queue.empty()) {
388 if (iterations % _terminal_checking_interval == 0) {
389 if (cancel_checker()) {
392 std::chrono::duration<double> planning_duration =
393 std::chrono::duration_cast<std::chrono::duration<double>>(steady_clock::now() - start_time);
394 if (
static_cast<double>(planning_duration.count()) >= _max_planning_time) {
396 return getClosestPathWithinTolerance(path);
401 current_node = getNextNode();
404 if (expansions_log) {
405 populateExpansionsLog(current_node, expansions_log);
411 if (onVisitationCheckNode(current_node)) {
418 current_node->visited();
421 expansion_result =
nullptr;
422 expansion_result = _expander->tryAnalyticExpansion(
423 current_node, coarse_check_goals, fine_check_goals,
424 _goal_manager.getGoalsCoordinates(), neighborGetter, analytic_iterations, closest_distance);
425 if (expansion_result !=
nullptr) {
426 current_node = expansion_result;
430 if (_goal_manager.isGoal(current_node)) {
431 return current_node->backtracePath(path);
432 }
else if (_best_heuristic_node.first < getToleranceHeuristic()) {
434 approach_iterations++;
435 if (approach_iterations >= getOnApproachMaxIterations()) {
436 return _graph.at(_best_heuristic_node.second).backtracePath(path);
442 current_node->getNeighbors(neighborGetter, _collision_checker, _traverse_unknown, neighbors);
444 for (neighbor_iterator = neighbors.begin();
445 neighbor_iterator != neighbors.end(); ++neighbor_iterator)
447 neighbor = *neighbor_iterator;
450 g_cost = current_node->getAccumulatedCost() + current_node->getTraversalCost(neighbor);
453 if (g_cost < neighbor->getAccumulatedCost()) {
454 neighbor->setAccumulatedCost(g_cost);
455 neighbor->parent = current_node;
458 addNode(g_cost + getHeuristicCost(neighbor), neighbor);
464 return getClosestPathWithinTolerance(path);
467 template<
typename NodeT>
473 template<
typename NodeT>
479 return node.graph_node_ptr;
482 template<
typename NodeT>
487 _queue.emplace(cost, queued_node);
490 template<
typename NodeT>
493 const Coordinates node_coords =
494 NodeT::getCoords(node->getIndex(), getSizeX(), getSizeDim3());
495 float heuristic = NodeT::getHeuristicCost(node_coords, _goal_manager.getGoalsCoordinates());
496 if (heuristic < _best_heuristic_node.first) {
497 _best_heuristic_node = {heuristic, node->getIndex()};
503 template<
typename NodeT>
506 return current_node->wasVisited();
509 template<
typename NodeT>
513 std::swap(_queue, q);
516 template<
typename NodeT>
520 std::swap(_graph, g);
521 _graph.reserve(100000);
524 template<
typename NodeT>
527 return _max_iterations;
530 template<
typename NodeT>
533 return _max_on_approach_iterations;
536 template<
typename NodeT>
542 template<
typename NodeT>
548 template<
typename NodeT>
554 template<
typename NodeT>
560 template<
typename NodeT>
563 return _coarse_search_resolution;
566 template<
typename NodeT>
569 return _goal_manager;
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
An A* implementation for planning in a costmap. Templated based on the Node type.
~AStarAlgorithm()
A destructor for nav2_smac_planner::AStarAlgorithm.
unsigned int & getSizeDim3()
Get number of angle quantization bins (SE2) or Z coordinate (XYZ)
unsigned int getCoarseSearchResolution()
Get the resolution of the coarse search.
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.
int & getOnApproachMaxIterations()
Get maximum number of on-approach iterations after within threshold.
bool onVisitationCheckNode(const NodePtr &node)
Check if node has been visited.
void setCollisionChecker(GridCollisionChecker *collision_checker)
Sets the collision checker to use.
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.
NodePtr getNextNode()
Get pointer to next goal in open set.
bool areInputsValid()
Check if inputs to planner are valid.
void clearQueue()
Clear heuristic queue of nodes to search.
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.
bool getClosestPathWithinTolerance(CoordinateVector &path)
Get the closest path within tolerance if available.
int & getMaxIterations()
Get maximum number of iterations to plan.
void clearGraph()
Clear graph of nodes searched.
unsigned int & getSizeY()
Get size of graph in Y.
void setStart(const float &mx, const float &my, const unsigned int &dim_3)
Set the starting pose for planning, as a node index.
void addNode(const float &cost, NodePtr &node)
Add a node to the open set.
GoalManagerT getGoalManager()
Get the goals manager class.
unsigned int & getSizeX()
Get size of graph in X.
float getHeuristicCost(const NodePtr &node)
Get cost of heuristic of node.
float & getToleranceHeuristic()
Get tolerance, in node nodes.
NodePtr & getStart()
Get pointer reference to starting node.
NodePtr addToGraph(const uint64_t &index)
Adds node to graph.
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.
Responsible for managing multiple variables storing information on the goal.
A costmap grid collision checker.
uint64_t getIndex()
Gets cell index.
NodeBasic implementation for priority queue insertion.
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.
Node2D implementation of coordinate structure.
Search properties and penalties.