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),
46 _goal_coordinates(Coordinates()),
49 _motion_model(motion_model)
51 _graph.reserve(100000);
54 template<
typename NodeT>
59 template<
typename NodeT>
61 const bool & allow_unknown,
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)
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);
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);
85 const bool & allow_unknown,
87 const int & max_on_approach_iterations,
88 const int & terminal_checking_interval,
89 const double & max_planning_time,
91 const unsigned int & dim_3_size)
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;
99 if (dim_3_size != 1) {
100 throw std::runtime_error(
"Node type Node2D cannot be given non-1 dim 3 quantization.");
102 _dim3_size = dim_3_size;
103 _expander = std::make_unique<AnalyticExpansion<Node2D>>(
104 _motion_model, _search_info, _traverse_unknown, _dim3_size);
107 template<
typename NodeT>
110 _collision_checker = collision_checker;
113 unsigned int y_size = _costmap->getSizeInCellsY();
117 if (getSizeX() != x_size || getSizeY() != y_size) {
120 NodeT::initMotionModel(_motion_model, _x_size, _y_size, _dim3_size, _search_info);
122 _expander->setCollisionChecker(_collision_checker);
125 template<
typename NodeT>
127 const uint64_t & index)
129 auto iter = _graph.find(index);
130 if (iter != _graph.end()) {
131 return &(iter->second);
134 return &(_graph.emplace(index, NodeT(index)).first->second);
141 const unsigned int & dim_3)
144 throw std::runtime_error(
"Node type Node2D cannot be given non-zero starting dim 3.");
148 static_cast<unsigned int>(mx),
149 static_cast<unsigned int>(my),
153 template<
typename NodeT>
157 const unsigned int & dim_3)
161 static_cast<unsigned int>(mx),
162 static_cast<unsigned int>(my),
164 _start->setPose(Coordinates(mx, my, dim_3));
169 const NodePtr & node,
170 std::vector<std::tuple<float, float, float>> * expansions_log)
173 expansions_log->emplace_back(
174 _costmap->getOriginX() + ((coords.x + 0.5) * _costmap->getResolution()),
175 _costmap->getOriginY() + ((coords.y + 0.5) * _costmap->getResolution()),
179 template<
typename NodeT>
181 const NodePtr & node,
182 std::vector<std::tuple<float, float, float>> * expansions_log)
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));
195 const unsigned int & dim_3)
198 throw std::runtime_error(
"Node type Node2D cannot be given non-zero goal dim 3.");
203 static_cast<unsigned int>(mx),
204 static_cast<unsigned int>(my),
206 _goal_coordinates = Node2D::Coordinates(mx, my);
209 template<
typename NodeT>
213 const unsigned int & dim_3)
217 static_cast<unsigned int>(mx),
218 static_cast<unsigned int>(my),
221 typename NodeT::Coordinates goal_coords(mx, my, dim_3);
223 if (!_search_info.cache_obstacle_heuristic || goal_coords != _goal_coordinates) {
225 throw std::runtime_error(
"Start must be set before goal.");
228 NodeT::resetObstacleHeuristic(
229 _collision_checker->getCostmapROS(), _start->pose.x, _start->pose.y, mx, my);
232 _goal_coordinates = goal_coords;
233 _goal->setPose(_goal_coordinates);
236 template<
typename NodeT>
240 if (_graph.empty()) {
241 throw std::runtime_error(
"Failed to compute path, no costmap given.");
245 if (!_start || !_goal) {
246 throw std::runtime_error(
"Failed to compute path, no valid start or goal given.");
250 if (getToleranceHeuristic() < 0.001 &&
251 !_goal->isNodeValid(_traverse_unknown, _collision_checker))
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)
267 steady_clock::time_point start_time = steady_clock::now();
268 _tolerance = tolerance;
269 _best_heuristic_node = {std::numeric_limits<float>::max(), 0};
272 if (!areInputsValid()) {
277 addNode(0.0, getStart());
278 getStart()->setAccumulatedCost(0.0);
281 NodePtr current_node =
nullptr;
282 NodePtr neighbor =
nullptr;
283 NodePtr expansion_result =
nullptr;
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();
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
298 if (index >= max_index) {
302 neighbor_rtn = addToGraph(index);
306 while (iterations < getMaxIterations() && !_queue.empty()) {
308 if (iterations % _terminal_checking_interval == 0) {
309 if (cancel_checker()) {
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) {
320 current_node = getNextNode();
323 if (expansions_log) {
324 populateExpansionsLog(current_node, expansions_log);
330 if (onVisitationCheckNode(current_node)) {
337 current_node->visited();
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;
348 if (isGoal(current_node)) {
349 return current_node->backtracePath(path);
350 }
else if (_best_heuristic_node.first < getToleranceHeuristic()) {
352 approach_iterations++;
353 if (approach_iterations >= getOnApproachMaxIterations()) {
354 return _graph.at(_best_heuristic_node.second).backtracePath(path);
360 current_node->getNeighbors(neighborGetter, _collision_checker, _traverse_unknown, neighbors);
362 for (neighbor_iterator = neighbors.begin();
363 neighbor_iterator != neighbors.end(); ++neighbor_iterator)
365 neighbor = *neighbor_iterator;
368 g_cost = current_node->getAccumulatedCost() + current_node->getTraversalCost(neighbor);
371 if (g_cost < neighbor->getAccumulatedCost()) {
372 neighbor->setAccumulatedCost(g_cost);
373 neighbor->parent = current_node;
376 addNode(g_cost + getHeuristicCost(neighbor), neighbor);
381 if (_best_heuristic_node.first < getToleranceHeuristic()) {
383 return _graph.at(_best_heuristic_node.second).backtracePath(path);
389 template<
typename NodeT>
392 return node == getGoal();
395 template<
typename NodeT>
401 template<
typename NodeT>
407 template<
typename NodeT>
413 return node.graph_node_ptr;
416 template<
typename NodeT>
421 _queue.emplace(cost, queued_node);
424 template<
typename NodeT>
427 const Coordinates node_coords =
428 NodeT::getCoords(node->getIndex(), getSizeX(), getSizeDim3());
429 float heuristic = NodeT::getHeuristicCost(
430 node_coords, _goal_coordinates);
432 if (heuristic < _best_heuristic_node.first) {
433 _best_heuristic_node = {heuristic, node->getIndex()};
439 template<
typename NodeT>
442 return current_node->wasVisited();
445 template<
typename NodeT>
449 std::swap(_queue, q);
452 template<
typename NodeT>
456 std::swap(_graph, g);
457 _graph.reserve(100000);
460 template<
typename NodeT>
463 return _max_iterations;
466 template<
typename NodeT>
469 return _max_on_approach_iterations;
472 template<
typename NodeT>
478 template<
typename NodeT>
484 template<
typename NodeT>
490 template<
typename NodeT>
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)
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.
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 hueristic 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.
unsigned int & getSizeX()
Get size of graph in X.
NodePtr & getGoal()
Get pointer reference to goal node.
bool isGoal(NodePtr &node)
Check if this node is the goal node.
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)
Set the goal for planning, as a node index.
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.