Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
a_star.hpp
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 #ifndef NAV2_SMAC_PLANNER__A_STAR_HPP_
17 #define NAV2_SMAC_PLANNER__A_STAR_HPP_
18 
19 #include <functional>
20 #include <memory>
21 #include <queue>
22 #include <tuple>
23 #include <utility>
24 #include <vector>
25 
26 #include "nav2_costmap_2d/costmap_2d.hpp"
27 #include "nav2_core/planner_exceptions.hpp"
28 
29 #include "nav2_smac_planner/thirdparty/robin_hood.h"
30 #include "nav2_smac_planner/analytic_expansion.hpp"
31 #include "nav2_smac_planner/node_2d.hpp"
32 #include "nav2_smac_planner/node_hybrid.hpp"
33 #include "nav2_smac_planner/node_lattice.hpp"
34 #include "nav2_smac_planner/node_basic.hpp"
35 #include "nav2_smac_planner/goal_manager.hpp"
36 #include "nav2_smac_planner/types.hpp"
37 #include "nav2_smac_planner/constants.hpp"
38 
39 namespace nav2_smac_planner
40 {
41 
46 template<typename NodeT>
48 {
49 public:
50  typedef NodeT * NodePtr;
52  typedef std::vector<NodePtr> NodeVector;
53  typedef std::pair<float, NodeBasic<NodeT>> NodeElement;
54  typedef typename NodeT::Coordinates Coordinates;
55  typedef typename NodeT::CoordinateVector CoordinateVector;
56  typedef typename NodeVector::iterator NeighborIterator;
57  typedef std::function<bool (const uint64_t &, NodeT * &)> NodeGetter;
59 
60 
66  {
67  bool operator()(const NodeElement & a, const NodeElement & b) const
68  {
69  return a.first > b.first;
70  }
71  };
72 
73  typedef std::priority_queue<NodeElement, std::vector<NodeElement>, NodeComparator> NodeQueue;
74 
78  explicit AStarAlgorithm(const MotionModel & motion_model, const SearchInfo & search_info);
79 
84 
99  void initialize(
100  const bool & allow_unknown,
101  int & max_iterations,
102  const int & max_on_approach_iterations,
103  const int & terminal_checking_interval,
104  const double & max_planning_time,
105  const float & lookup_table_size,
106  const unsigned int & dim_3_size);
107 
117  bool createPath(
118  CoordinateVector & path, int & num_iterations, const float & tolerance,
119  std::function<bool()> cancel_checker,
120  std::vector<std::tuple<float, float, float>> * expansions_log = nullptr);
121 
126  void setCollisionChecker(GridCollisionChecker * collision_checker);
127 
136  void setGoal(
137  const float & mx,
138  const float & my,
139  const unsigned int & dim_3,
140  const GoalHeadingMode & goal_heading_mode = GoalHeadingMode::DEFAULT,
141  const int & coarse_search_resolution = 1);
142 
149  void setStart(
150  const float & mx,
151  const float & my,
152  const unsigned int & dim_3);
153 
158  int & getMaxIterations();
159 
164  NodePtr & getStart();
165 
171 
176  float & getToleranceHeuristic();
177 
182  unsigned int & getSizeX();
183 
188  unsigned int & getSizeY();
189 
194  unsigned int & getSizeDim3();
195 
200  unsigned int getCoarseSearchResolution();
201 
207 
208 protected:
213  inline NodePtr getNextNode();
214 
220  inline void addNode(const float & cost, NodePtr & node);
221 
226  inline NodePtr addToGraph(const uint64_t & index);
227 
233  inline float getHeuristicCost(const NodePtr & node);
234 
239  inline bool areInputsValid();
240 
244  inline void clearQueue();
245 
249  inline void clearGraph();
250 
256  inline bool onVisitationCheckNode(const NodePtr & node);
257 
263  inline void populateExpansionsLog(
264  const NodePtr & node, std::vector<std::tuple<float, float, float>> * expansions_log);
265 
266  bool _traverse_unknown;
267  bool _is_initialized;
268  int _max_iterations;
269  int _max_on_approach_iterations;
270  int _terminal_checking_interval;
271  double _max_planning_time;
272  float _tolerance;
273  unsigned int _x_size;
274  unsigned int _y_size;
275  unsigned int _dim3_size;
276  unsigned int _coarse_search_resolution;
277  SearchInfo _search_info;
278 
279  NodePtr _start;
280  GoalManagerT _goal_manager;
281  Graph _graph;
282  NodeQueue _queue;
283 
284  MotionModel _motion_model;
285  NodeHeuristicPair _best_heuristic_node;
286 
287  GridCollisionChecker * _collision_checker;
288  nav2_costmap_2d::Costmap2D * _costmap;
289  std::unique_ptr<AnalyticExpansion<NodeT>> _expander;
290 };
291 
292 } // namespace nav2_smac_planner
293 
294 #endif // NAV2_SMAC_PLANNER__A_STAR_HPP_
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:69
An A* implementation for planning in a costmap. Templated based on the Node type.
Definition: a_star.hpp:48
~AStarAlgorithm()
A destructor for nav2_smac_planner::AStarAlgorithm.
Definition: a_star.cpp:54
unsigned int & getSizeDim3()
Get number of angle quantization bins (SE2) or Z coordinate (XYZ)
Definition: a_star.cpp:548
unsigned int getCoarseSearchResolution()
Get the resolution of the coarse search.
Definition: a_star.cpp:554
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:327
int & getOnApproachMaxIterations()
Get maximum number of on-approach iterations after within threshold.
Definition: a_star.cpp:524
bool onVisitationCheckNode(const NodePtr &node)
Check if node has been visited.
Definition: a_star.cpp:497
void setCollisionChecker(GridCollisionChecker *collision_checker)
Sets the collision checker to use.
Definition: a_star.cpp:107
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:59
NodePtr getNextNode()
Get pointer to next goal in open set.
Definition: a_star.cpp:467
bool areInputsValid()
Check if inputs to planner are valid.
Definition: a_star.cpp:302
void clearQueue()
Clear heuristic queue of nodes to search.
Definition: a_star.cpp:503
AStarAlgorithm(const MotionModel &motion_model, const SearchInfo &search_info)
A constructor for nav2_smac_planner::AStarAlgorithm.
Definition: a_star.cpp:35
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:179
int & getMaxIterations()
Get maximum number of iterations to plan.
Definition: a_star.cpp:518
void clearGraph()
Clear graph of nodes searched.
Definition: a_star.cpp:510
unsigned int & getSizeY()
Get size of graph in Y.
Definition: a_star.cpp:542
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:153
void addNode(const float &cost, NodePtr &node)
Add a node to the open set.
Definition: a_star.cpp:476
GoalManagerT getGoalManager()
Get the goals manager class.
Definition: a_star.cpp:560
unsigned int & getSizeX()
Get size of graph in X.
Definition: a_star.cpp:536
float getHeuristicCost(const NodePtr &node)
Get cost of heuristic of node.
Definition: a_star.cpp:484
float & getToleranceHeuristic()
Get tolerance, in node nodes.
Definition: a_star.cpp:530
NodePtr & getStart()
Get pointer reference to starting node.
Definition: a_star.cpp:461
NodePtr addToGraph(const uint64_t &index)
Adds node to graph.
Definition: a_star.cpp:125
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.
Definition: a_star.cpp:215
Responsible for managing multiple variables storing information on the goal.
A costmap grid collision checker.
Search properties and penalties.
Definition: types.hpp:36