Nav2 Navigation Stack - jazzy  jazzy
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 <vector>
20 #include <iostream>
21 #include <unordered_map>
22 #include <memory>
23 #include <queue>
24 #include <utility>
25 #include <tuple>
26 #include "Eigen/Core"
27 
28 #include "nav2_costmap_2d/costmap_2d.hpp"
29 #include "nav2_core/planner_exceptions.hpp"
30 
31 #include "nav2_smac_planner/thirdparty/robin_hood.h"
32 #include "nav2_smac_planner/analytic_expansion.hpp"
33 #include "nav2_smac_planner/node_2d.hpp"
34 #include "nav2_smac_planner/node_hybrid.hpp"
35 #include "nav2_smac_planner/node_lattice.hpp"
36 #include "nav2_smac_planner/node_basic.hpp"
37 #include "nav2_smac_planner/types.hpp"
38 #include "nav2_smac_planner/constants.hpp"
39 
40 namespace nav2_smac_planner
41 {
42 
47 template<typename NodeT>
49 {
50 public:
51  typedef NodeT * NodePtr;
53  typedef std::vector<NodePtr> NodeVector;
54  typedef std::pair<float, NodeBasic<NodeT>> NodeElement;
55  typedef typename NodeT::Coordinates Coordinates;
56  typedef typename NodeT::CoordinateVector CoordinateVector;
57  typedef typename NodeVector::iterator NeighborIterator;
58  typedef std::function<bool (const uint64_t &, NodeT * &)> NodeGetter;
59 
65  {
66  bool operator()(const NodeElement & a, const NodeElement & b) const
67  {
68  return a.first > b.first;
69  }
70  };
71 
72  typedef std::priority_queue<NodeElement, std::vector<NodeElement>, NodeComparator> NodeQueue;
73 
77  explicit AStarAlgorithm(const MotionModel & motion_model, const SearchInfo & search_info);
78 
83 
96  void initialize(
97  const bool & allow_unknown,
98  int & max_iterations,
99  const int & max_on_approach_iterations,
100  const int & terminal_checking_interval,
101  const double & max_planning_time,
102  const float & lookup_table_size,
103  const unsigned int & dim_3_size);
104 
114  bool createPath(
115  CoordinateVector & path, int & num_iterations, const float & tolerance,
116  std::function<bool()> cancel_checker,
117  std::vector<std::tuple<float, float, float>> * expansions_log = nullptr);
118 
123  void setCollisionChecker(GridCollisionChecker * collision_checker);
124 
131  void setGoal(
132  const float & mx,
133  const float & my,
134  const unsigned int & dim_3);
135 
142  void setStart(
143  const float & mx,
144  const float & my,
145  const unsigned int & dim_3);
146 
151  int & getMaxIterations();
152 
157  NodePtr & getStart();
158 
163  NodePtr & getGoal();
164 
170 
175  float & getToleranceHeuristic();
176 
181  unsigned int & getSizeX();
182 
187  unsigned int & getSizeY();
188 
193  unsigned int & getSizeDim3();
194 
195 protected:
200  inline NodePtr getNextNode();
201 
207  inline void addNode(const float & cost, NodePtr & node);
208 
213  inline NodePtr addToGraph(const uint64_t & index);
214 
220  inline bool isGoal(NodePtr & node);
221 
227  inline float getHeuristicCost(const NodePtr & node);
228 
233  inline bool areInputsValid();
234 
238  inline void clearQueue();
239 
243  inline void clearGraph();
244 
245  inline bool onVisitationCheckNode(const NodePtr & node);
246 
252  inline void populateExpansionsLog(
253  const NodePtr & node, std::vector<std::tuple<float, float, float>> * expansions_log);
254 
255  bool _traverse_unknown;
256  bool _is_initialized;
257  int _max_iterations;
258  int _max_on_approach_iterations;
259  int _terminal_checking_interval;
260  double _max_planning_time;
261  float _tolerance;
262  unsigned int _x_size;
263  unsigned int _y_size;
264  unsigned int _dim3_size;
265  SearchInfo _search_info;
266 
267  Coordinates _goal_coordinates;
268  NodePtr _start;
269  NodePtr _goal;
270 
271  Graph _graph;
272  NodeQueue _queue;
273 
274  MotionModel _motion_model;
275  NodeHeuristicPair _best_heuristic_node;
276 
277  GridCollisionChecker * _collision_checker;
278  nav2_costmap_2d::Costmap2D * _costmap;
279  std::unique_ptr<AnalyticExpansion<NodeT>> _expander;
280 };
281 
282 } // namespace nav2_smac_planner
283 
284 #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:68
An A* implementation for planning in a costmap. Templated based on the Node type.
Definition: a_star.hpp:49
~AStarAlgorithm()
A destructor for nav2_smac_planner::AStarAlgorithm.
Definition: a_star.cpp:55
unsigned int & getSizeDim3()
Get number of angle quantization bins (SE2) or Z coordinate (XYZ)
Definition: a_star.cpp:491
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:261
int & getOnApproachMaxIterations()
Get maximum number of on-approach iterations after within threshold.
Definition: a_star.cpp:467
void setCollisionChecker(GridCollisionChecker *collision_checker)
Sets the collision checker to use.
Definition: a_star.cpp:108
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:60
NodePtr getNextNode()
Get pointer to next goal in open set.
Definition: a_star.cpp:408
bool areInputsValid()
Check if inputs to planner are valid.
Definition: a_star.cpp:237
void clearQueue()
Clear hueristic queue of nodes to search.
Definition: a_star.cpp:446
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:180
int & getMaxIterations()
Get maximum number of iterations to plan.
Definition: a_star.cpp:461
void clearGraph()
Clear graph of nodes searched.
Definition: a_star.cpp:453
unsigned int & getSizeY()
Get size of graph in Y.
Definition: a_star.cpp:485
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:154
void addNode(const float &cost, NodePtr &node)
Add a node to the open set.
Definition: a_star.cpp:417
unsigned int & getSizeX()
Get size of graph in X.
Definition: a_star.cpp:479
NodePtr & getGoal()
Get pointer reference to goal node.
Definition: a_star.cpp:402
bool isGoal(NodePtr &node)
Check if this node is the goal node.
Definition: a_star.cpp:390
float getHeuristicCost(const NodePtr &node)
Get cost of heuristic of node.
Definition: a_star.cpp:425
float & getToleranceHeuristic()
Get tolerance, in node nodes.
Definition: a_star.cpp:473
NodePtr & getStart()
Get pointer reference to starting node.
Definition: a_star.cpp:396
NodePtr addToGraph(const uint64_t &index)
Adds node to graph.
Definition: a_star.cpp:126
void setGoal(const float &mx, const float &my, const unsigned int &dim_3)
Set the goal for planning, as a node index.
Definition: a_star.cpp:210
A costmap grid collision checker.
Search properties and penalties.
Definition: types.hpp:36