22 #include <type_traits>
28 #include "nav2_smac_planner/a_star.hpp"
29 using namespace std::chrono;
31 namespace nav2_smac_planner
34 template<
typename NodeT>
36 const MotionModel & motion_model,
38 : _traverse_unknown(true),
39 _is_initialized(false),
41 _terminal_checking_interval(5000),
42 _max_planning_time(0),
45 _search_info(search_info),
48 _motion_model(motion_model)
50 _graph.reserve(100000);
53 template<
typename NodeT>
58 template<
typename NodeT>
60 const bool & allow_unknown,
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)
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);
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);
84 const bool & allow_unknown,
86 const int & max_on_approach_iterations,
87 const int & terminal_checking_interval,
88 const double & max_planning_time,
90 const unsigned int & dim_3_size)
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;
98 if (dim_3_size != 1) {
99 throw std::runtime_error(
"Node type Node2D cannot be given non-1 dim 3 quantization.");
101 _dim3_size = dim_3_size;
102 _expander = std::make_unique<AnalyticExpansion<Node2D>>(
103 _motion_model, _search_info, _traverse_unknown, _dim3_size);
106 template<
typename NodeT>
109 _collision_checker = collision_checker;
112 unsigned int y_size = _costmap->getSizeInCellsY();
116 if (getSizeX() != x_size || getSizeY() != y_size) {
119 NodeT::initMotionModel(_motion_model, _x_size, _y_size, _dim3_size, _search_info);
121 _expander->setCollisionChecker(_collision_checker);
124 template<
typename NodeT>
126 const uint64_t & index)
128 auto iter = _graph.find(index);
129 if (iter != _graph.end()) {
130 return &(iter->second);
133 return &(_graph.emplace(index, NodeT(index)).first->second);
140 const unsigned int & dim_3)
143 throw std::runtime_error(
"Node type Node2D cannot be given non-zero starting dim 3.");
147 static_cast<unsigned int>(mx),
148 static_cast<unsigned int>(my),
152 template<
typename NodeT>
156 const unsigned int & dim_3)
160 static_cast<unsigned int>(mx),
161 static_cast<unsigned int>(my),
163 _start->setPose(Coordinates(mx, my, dim_3));
168 const NodePtr & node,
169 std::vector<std::tuple<float, float, float>> * expansions_log)
172 expansions_log->emplace_back(
173 _costmap->getOriginX() + ((coords.x + 0.5) * _costmap->getResolution()),
174 _costmap->getOriginY() + ((coords.y + 0.5) * _costmap->getResolution()),
178 template<
typename NodeT>
180 const NodePtr & node,
181 std::vector<std::tuple<float, float, float>> * expansions_log)
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));
194 const unsigned int & dim_3,
195 const GoalHeadingMode & ,
199 throw std::runtime_error(
"Node type Node2D cannot be given non-zero goal dim 3.");
201 _goal_manager.clear();
202 auto goal = addToGraph(
204 static_cast<unsigned int>(mx),
205 static_cast<unsigned int>(my),
208 goal->setPose(Node2D::Coordinates(mx, my));
209 _goal_manager.addGoal(goal);
211 _coarse_search_resolution = 1;
214 template<
typename NodeT>
218 const unsigned int & dim_3,
219 const GoalHeadingMode & goal_heading_mode,
220 const int & coarse_search_resolution)
223 _coarse_search_resolution = 1;
225 _goal_manager.clear();
226 Coordinates ref_goal_coord(mx, my,
static_cast<float>(dim_3));
228 if (!_search_info.cache_obstacle_heuristic ||
229 _goal_manager.hasGoalChanged(ref_goal_coord))
232 throw std::runtime_error(
"Start must be set before goal.");
235 NodeT::resetObstacleHeuristic(
236 _collision_checker->getCostmapROS(), _start->pose.x, _start->pose.y, mx, my);
239 _goal_manager.setRefGoalCoordinates(ref_goal_coord);
241 unsigned int num_bins = NodeT::motion_table.num_angle_quantization;
243 switch (goal_heading_mode) {
244 case GoalHeadingMode::DEFAULT: {
246 auto goal = addToGraph(
248 static_cast<unsigned int>(mx),
249 static_cast<unsigned int>(my),
251 goal->setPose(
typename NodeT::Coordinates(mx, my,
static_cast<float>(dim_3)));
252 _goal_manager.addGoal(goal);
256 case GoalHeadingMode::BIDIRECTIONAL: {
259 auto goal = addToGraph(
261 static_cast<unsigned int>(mx),
262 static_cast<unsigned int>(my),
264 goal->setPose(
typename NodeT::Coordinates(mx, my,
static_cast<float>(dim_3)));
265 _goal_manager.addGoal(goal);
268 unsigned int opposite_heading = (dim_3 + (num_bins / 2)) % num_bins;
269 auto opposite_goal = addToGraph(
271 static_cast<unsigned int>(mx),
272 static_cast<unsigned int>(my),
274 opposite_goal->setPose(
275 typename NodeT::Coordinates(mx, my,
static_cast<float>(opposite_heading)));
276 _goal_manager.addGoal(opposite_goal);
280 case GoalHeadingMode::ALL_DIRECTION: {
282 _coarse_search_resolution = coarse_search_resolution;
285 for (
unsigned int i = 0; i < num_bins; ++i) {
286 auto goal = addToGraph(
288 static_cast<unsigned int>(mx),
289 static_cast<unsigned int>(my),
291 goal->setPose(
typename NodeT::Coordinates(mx, my,
static_cast<float>(i)));
292 _goal_manager.addGoal(goal);
296 case GoalHeadingMode::UNKNOWN:
297 throw std::runtime_error(
"Goal heading is UNKNOWN.");
301 template<
typename NodeT>
305 if (_graph.empty()) {
306 throw std::runtime_error(
"Failed to compute path, no costmap given.");
310 if (!_start || _goal_manager.goalsIsEmpty()) {
311 throw std::runtime_error(
"Failed to compute path, no valid start or goal given.");
315 _goal_manager.removeInvalidGoals(getToleranceHeuristic(), _collision_checker, _traverse_unknown);
318 if (_goal_manager.getGoalsSet().empty()) {
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)
333 steady_clock::time_point start_time = steady_clock::now();
334 _tolerance = tolerance;
335 _best_heuristic_node = {std::numeric_limits<float>::max(), 0};
338 if (!areInputsValid()) {
342 NodeVector coarse_check_goals, fine_check_goals;
343 _goal_manager.prepareGoalsForAnalyticExpansion(coarse_check_goals, fine_check_goals,
344 _coarse_search_resolution);
347 addNode(0.0, getStart());
348 getStart()->setAccumulatedCost(0.0);
351 NodePtr current_node =
nullptr;
352 NodePtr neighbor =
nullptr;
353 NodePtr expansion_result =
nullptr;
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();
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
368 if (index >= max_index) {
372 neighbor_rtn = addToGraph(index);
376 while (iterations < getMaxIterations() && !_queue.empty()) {
378 if (iterations % _terminal_checking_interval == 0) {
379 if (cancel_checker()) {
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) {
390 current_node = getNextNode();
393 if (expansions_log) {
394 populateExpansionsLog(current_node, expansions_log);
400 if (onVisitationCheckNode(current_node)) {
407 current_node->visited();
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;
419 if (_goal_manager.isGoal(current_node)) {
420 return current_node->backtracePath(path);
421 }
else if (_best_heuristic_node.first < getToleranceHeuristic()) {
423 approach_iterations++;
424 if (approach_iterations >= getOnApproachMaxIterations()) {
425 return _graph.at(_best_heuristic_node.second).backtracePath(path);
431 current_node->getNeighbors(neighborGetter, _collision_checker, _traverse_unknown, neighbors);
433 for (neighbor_iterator = neighbors.begin();
434 neighbor_iterator != neighbors.end(); ++neighbor_iterator)
436 neighbor = *neighbor_iterator;
439 g_cost = current_node->getAccumulatedCost() + current_node->getTraversalCost(neighbor);
442 if (g_cost < neighbor->getAccumulatedCost()) {
443 neighbor->setAccumulatedCost(g_cost);
444 neighbor->parent = current_node;
447 addNode(g_cost + getHeuristicCost(neighbor), neighbor);
452 if (_best_heuristic_node.first < getToleranceHeuristic()) {
454 return _graph.at(_best_heuristic_node.second).backtracePath(path);
460 template<
typename NodeT>
466 template<
typename NodeT>
472 return node.graph_node_ptr;
475 template<
typename NodeT>
480 _queue.emplace(cost, queued_node);
483 template<
typename NodeT>
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()};
496 template<
typename NodeT>
499 return current_node->wasVisited();
502 template<
typename NodeT>
506 std::swap(_queue, q);
509 template<
typename NodeT>
513 std::swap(_graph, g);
514 _graph.reserve(100000);
517 template<
typename NodeT>
520 return _max_iterations;
523 template<
typename NodeT>
526 return _max_on_approach_iterations;
529 template<
typename NodeT>
535 template<
typename NodeT>
541 template<
typename NodeT>
547 template<
typename NodeT>
553 template<
typename NodeT>
556 return _coarse_search_resolution;
559 template<
typename NodeT>
562 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.
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.