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 _max_planning_time(0),
44 _search_info(search_info),
45 _goal_coordinates(Coordinates()),
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 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 _max_planning_time = max_planning_time;
71 if (!_is_initialized) {
72 NodeT::precomputeDistanceHeuristic(lookup_table_size, _motion_model, dim_3_size, _search_info);
74 _is_initialized =
true;
75 _dim3_size = dim_3_size;
76 _expander = std::make_unique<AnalyticExpansion<NodeT>>(
77 _motion_model, _search_info, _traverse_unknown, _dim3_size);
82 const bool & allow_unknown,
84 const int & max_on_approach_iterations,
85 const double & max_planning_time,
87 const unsigned int & dim_3_size)
89 _traverse_unknown = allow_unknown;
90 _max_iterations = max_iterations;
91 _max_on_approach_iterations = max_on_approach_iterations;
92 _max_planning_time = max_planning_time;
94 if (dim_3_size != 1) {
95 throw std::runtime_error(
"Node type Node2D cannot be given non-1 dim 3 quantization.");
97 _dim3_size = dim_3_size;
98 _expander = std::make_unique<AnalyticExpansion<Node2D>>(
99 _motion_model, _search_info, _traverse_unknown, _dim3_size);
102 template<
typename NodeT>
105 _collision_checker = collision_checker;
108 unsigned int y_size = _costmap->getSizeInCellsY();
112 if (getSizeX() != x_size || getSizeY() != y_size) {
115 NodeT::initMotionModel(_motion_model, _x_size, _y_size, _dim3_size, _search_info);
117 _expander->setCollisionChecker(collision_checker);
120 template<
typename NodeT>
122 const unsigned int & index)
124 auto iter = _graph.find(index);
125 if (iter != _graph.end()) {
126 return &(iter->second);
129 return &(_graph.emplace(index, NodeT(index)).first->second);
134 const unsigned int & mx,
135 const unsigned int & my,
136 const unsigned int & dim_3)
139 throw std::runtime_error(
"Node type Node2D cannot be given non-zero starting dim 3.");
144 template<
typename NodeT>
146 const unsigned int & mx,
147 const unsigned int & my,
148 const unsigned int & dim_3)
150 _start = addToGraph(NodeT::getIndex(mx, my, dim_3));
153 static_cast<float>(mx),
154 static_cast<float>(my),
155 static_cast<float>(dim_3)));
160 const unsigned int & mx,
161 const unsigned int & my,
162 const unsigned int & dim_3)
165 throw std::runtime_error(
"Node type Node2D cannot be given non-zero goal dim 3.");
169 _goal_coordinates = Node2D::Coordinates(mx, my);
172 template<
typename NodeT>
174 const unsigned int & mx,
175 const unsigned int & my,
176 const unsigned int & dim_3)
178 _goal = addToGraph(NodeT::getIndex(mx, my, dim_3));
180 typename NodeT::Coordinates goal_coords(
181 static_cast<float>(mx),
182 static_cast<float>(my),
183 static_cast<float>(dim_3));
185 if (!_search_info.cache_obstacle_heuristic || goal_coords != _goal_coordinates) {
187 throw std::runtime_error(
"Start must be set before goal.");
190 NodeT::resetObstacleHeuristic(_costmap, _start->pose.x, _start->pose.y, mx, my);
193 _goal_coordinates = goal_coords;
194 _goal->setPose(_goal_coordinates);
197 template<
typename NodeT>
201 if (_graph.empty()) {
202 throw std::runtime_error(
"Failed to compute path, no costmap given.");
206 if (!_start || !_goal) {
207 throw std::runtime_error(
"Failed to compute path, no valid start or goal given.");
211 if (getToleranceHeuristic() < 0.001 &&
212 !_goal->isNodeValid(_traverse_unknown, _collision_checker))
214 throw std::runtime_error(
"Failed to compute path, goal is occupied with no tolerance.");
218 if (!_start->isNodeValid(_traverse_unknown, _collision_checker)) {
219 throw std::runtime_error(
"Starting point in lethal space! Cannot create feasible plan.");
225 template<
typename NodeT>
227 CoordinateVector & path,
int & iterations,
228 const float & tolerance)
230 steady_clock::time_point start_time = steady_clock::now();
231 _tolerance = tolerance;
232 _best_heuristic_node = {std::numeric_limits<float>::max(), 0};
235 if (!areInputsValid()) {
240 addNode(0.0, getStart());
241 getStart()->setAccumulatedCost(0.0);
244 NodePtr current_node =
nullptr;
245 NodePtr neighbor =
nullptr;
246 NodePtr expansion_result =
nullptr;
248 NodeVector neighbors;
249 int approach_iterations = 0;
250 NeighborIterator neighbor_iterator;
251 int analytic_iterations = 0;
252 int closest_distance = std::numeric_limits<int>::max();
255 const unsigned int max_index = getSizeX() * getSizeY() * getSizeDim3();
256 NodeGetter neighborGetter =
257 [&,
this](
const unsigned int & index, NodePtr & neighbor_rtn) ->
bool
259 if (index >= max_index) {
263 neighbor_rtn = addToGraph(index);
267 while (iterations < getMaxIterations() && !_queue.empty()) {
269 if (iterations % _timing_interval == 0) {
270 std::chrono::duration<double> planning_duration =
271 std::chrono::duration_cast<std::chrono::duration<double>>(steady_clock::now() - start_time);
272 if (
static_cast<double>(planning_duration.count()) >= _max_planning_time) {
278 current_node = getNextNode();
282 if (current_node->wasVisited()) {
289 current_node->visited();
292 expansion_result =
nullptr;
293 expansion_result = _expander->tryAnalyticExpansion(
294 current_node, getGoal(), neighborGetter, analytic_iterations, closest_distance);
295 if (expansion_result !=
nullptr) {
296 current_node = expansion_result;
300 if (isGoal(current_node)) {
301 return current_node->backtracePath(path);
302 }
else if (_best_heuristic_node.first < getToleranceHeuristic()) {
304 approach_iterations++;
305 if (approach_iterations >= getOnApproachMaxIterations()) {
306 return _graph.at(_best_heuristic_node.second).backtracePath(path);
312 current_node->getNeighbors(neighborGetter, _collision_checker, _traverse_unknown, neighbors);
314 for (neighbor_iterator = neighbors.begin();
315 neighbor_iterator != neighbors.end(); ++neighbor_iterator)
317 neighbor = *neighbor_iterator;
320 g_cost = current_node->getAccumulatedCost() + current_node->getTraversalCost(neighbor);
323 if (g_cost < neighbor->getAccumulatedCost()) {
324 neighbor->setAccumulatedCost(g_cost);
325 neighbor->parent = current_node;
328 addNode(g_cost + getHeuristicCost(neighbor), neighbor);
333 if (_best_heuristic_node.first < getToleranceHeuristic()) {
335 return _graph.at(_best_heuristic_node.second).backtracePath(path);
341 template<
typename NodeT>
344 return node == getGoal();
347 template<
typename NodeT>
353 template<
typename NodeT>
359 template<
typename NodeT>
365 return node.graph_node_ptr;
368 template<
typename NodeT>
373 _queue.emplace(cost, queued_node);
376 template<
typename NodeT>
379 const Coordinates node_coords =
380 NodeT::getCoords(node->getIndex(), getSizeX(), getSizeDim3());
381 float heuristic = NodeT::getHeuristicCost(
382 node_coords, _goal_coordinates, _costmap);
384 if (heuristic < _best_heuristic_node.first) {
385 _best_heuristic_node = {heuristic, node->getIndex()};
391 template<
typename NodeT>
395 std::swap(_queue, q);
398 template<
typename NodeT>
402 std::swap(_graph, g);
403 _graph.reserve(100000);
406 template<
typename NodeT>
409 return _max_iterations;
412 template<
typename NodeT>
415 return _max_on_approach_iterations;
418 template<
typename NodeT>
424 template<
typename NodeT>
430 template<
typename NodeT>
436 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)
NodePtr addToGraph(const unsigned int &index)
Adds node to graph.
void initialize(const bool &allow_unknown, int &max_iterations, const int &max_on_approach_iterations, const double &max_planning_time, const float &lookup_table_size, const unsigned int &dim_3_size)
Initialization of the planner with defaults.
void setGoal(const unsigned int &mx, const unsigned int &my, const unsigned int &dim_3)
Set the goal for planning, as a node index.
int & getOnApproachMaxIterations()
Get maximum number of on-approach iterations after within threshold.
void setCollisionChecker(GridCollisionChecker *collision_checker)
Sets the collision checker to use.
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.
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 unsigned int &mx, const unsigned int &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.
bool createPath(CoordinateVector &path, int &num_iterations, const float &tolerance)
Creating path from given costmap, start, and goal.
A costmap grid collision checker.
unsigned int & 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.
Search properties and penalties.