Nav2 Navigation Stack - humble  humble
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 "Eigen/Core"
26 
27 #include "nav2_costmap_2d/costmap_2d.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/types.hpp"
36 #include "nav2_smac_planner/constants.hpp"
37 
38 namespace nav2_smac_planner
39 {
40 
45 template<typename NodeT>
47 {
48 public:
49  typedef NodeT * NodePtr;
51  typedef std::vector<NodePtr> NodeVector;
52  typedef std::pair<float, NodeBasic<NodeT>> NodeElement;
53  typedef typename NodeT::Coordinates Coordinates;
54  typedef typename NodeT::CoordinateVector CoordinateVector;
55  typedef typename NodeVector::iterator NeighborIterator;
56  typedef std::function<bool (const unsigned int &, NodeT * &)> NodeGetter;
57 
63  {
64  bool operator()(const NodeElement & a, const NodeElement & b) const
65  {
66  return a.first > b.first;
67  }
68  };
69 
70  typedef std::priority_queue<NodeElement, std::vector<NodeElement>, NodeComparator> NodeQueue;
71 
75  explicit AStarAlgorithm(const MotionModel & motion_model, const SearchInfo & search_info);
76 
81 
92  void initialize(
93  const bool & allow_unknown,
94  int & max_iterations,
95  const int & max_on_approach_iterations,
96  const double & max_planning_time,
97  const float & lookup_table_size,
98  const unsigned int & dim_3_size);
99 
107  bool createPath(CoordinateVector & path, int & num_iterations, const float & tolerance);
108 
113  void setCollisionChecker(GridCollisionChecker * collision_checker);
114 
121  void setGoal(
122  const unsigned int & mx,
123  const unsigned int & my,
124  const unsigned int & dim_3);
125 
132  void setStart(
133  const unsigned int & mx,
134  const unsigned int & my,
135  const unsigned int & dim_3);
136 
141  int & getMaxIterations();
142 
147  NodePtr & getStart();
148 
153  NodePtr & getGoal();
154 
160 
165  float & getToleranceHeuristic();
166 
171  unsigned int & getSizeX();
172 
177  unsigned int & getSizeY();
178 
183  unsigned int & getSizeDim3();
184 
185 protected:
190  inline NodePtr getNextNode();
191 
197  inline void addNode(const float & cost, NodePtr & node);
198 
203  inline NodePtr addToGraph(const unsigned int & index);
204 
210  inline bool isGoal(NodePtr & node);
211 
217  inline float getHeuristicCost(const NodePtr & node);
218 
223  inline bool areInputsValid();
224 
228  inline void clearQueue();
229 
233  inline void clearGraph();
234 
235  int _timing_interval = 5000;
236 
237  bool _traverse_unknown;
238  bool _is_initialized;
239  int _max_iterations;
240  int _max_on_approach_iterations;
241  double _max_planning_time;
242  float _tolerance;
243  unsigned int _x_size;
244  unsigned int _y_size;
245  unsigned int _dim3_size;
246  SearchInfo _search_info;
247 
248  Coordinates _goal_coordinates;
249  NodePtr _start;
250  NodePtr _goal;
251 
252  Graph _graph;
253  NodeQueue _queue;
254 
255  MotionModel _motion_model;
256  NodeHeuristicPair _best_heuristic_node;
257 
258  GridCollisionChecker * _collision_checker;
259  nav2_costmap_2d::Costmap2D * _costmap;
260  std::unique_ptr<AnalyticExpansion<NodeT>> _expander;
261 };
262 
263 } // namespace nav2_smac_planner
264 
265 #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:47
~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:437
NodePtr addToGraph(const unsigned int &index)
Adds node to graph.
Definition: a_star.cpp:121
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.
Definition: a_star.cpp:59
void setGoal(const unsigned int &mx, const unsigned int &my, const unsigned int &dim_3)
Set the goal for planning, as a node index.
Definition: a_star.cpp:173
int & getOnApproachMaxIterations()
Get maximum number of on-approach iterations after within threshold.
Definition: a_star.cpp:413
void setCollisionChecker(GridCollisionChecker *collision_checker)
Sets the collision checker to use.
Definition: a_star.cpp:103
NodePtr getNextNode()
Get pointer to next goal in open set.
Definition: a_star.cpp:360
bool areInputsValid()
Check if inputs to planner are valid.
Definition: a_star.cpp:198
void clearQueue()
Clear hueristic queue of nodes to search.
Definition: a_star.cpp:392
AStarAlgorithm(const MotionModel &motion_model, const SearchInfo &search_info)
A constructor for nav2_smac_planner::AStarAlgorithm.
Definition: a_star.cpp:35
int & getMaxIterations()
Get maximum number of iterations to plan.
Definition: a_star.cpp:407
void clearGraph()
Clear graph of nodes searched.
Definition: a_star.cpp:399
unsigned int & getSizeY()
Get size of graph in Y.
Definition: a_star.cpp:431
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.
Definition: a_star.cpp:145
void addNode(const float &cost, NodePtr &node)
Add a node to the open set.
Definition: a_star.cpp:369
unsigned int & getSizeX()
Get size of graph in X.
Definition: a_star.cpp:425
NodePtr & getGoal()
Get pointer reference to goal node.
Definition: a_star.cpp:354
bool isGoal(NodePtr &node)
Check if this node is the goal node.
Definition: a_star.cpp:342
float getHeuristicCost(const NodePtr &node)
Get cost of heuristic of node.
Definition: a_star.cpp:377
float & getToleranceHeuristic()
Get tolerance, in node nodes.
Definition: a_star.cpp:419
NodePtr & getStart()
Get pointer reference to starting node.
Definition: a_star.cpp:348
bool createPath(CoordinateVector &path, int &num_iterations, const float &tolerance)
Creating path from given costmap, start, and goal.
Definition: a_star.cpp:226
A costmap grid collision checker.
Search properties and penalties.
Definition: types.hpp:36