Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
node_lattice.hpp
1 // Copyright (c) 2020, Samsung Research America
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License. Reserved.
14 
15 #ifndef NAV2_SMAC_PLANNER__NODE_LATTICE_HPP_
16 #define NAV2_SMAC_PLANNER__NODE_LATTICE_HPP_
17 
18 #include <math.h>
19 
20 #include <vector>
21 #include <cmath>
22 #include <iostream>
23 #include <functional>
24 #include <queue>
25 #include <memory>
26 #include <utility>
27 #include <limits>
28 #include <string>
29 
30 #include "nlohmann/json.hpp"
31 #include "ompl/base/StateSpace.h"
32 #include "angles/angles.h"
33 
34 #include "nav2_smac_planner/constants.hpp"
35 #include "nav2_smac_planner/types.hpp"
36 #include "nav2_smac_planner/collision_checker.hpp"
37 #include "nav2_smac_planner/node_hybrid.hpp"
38 #include "nav2_smac_planner/utils.hpp"
39 
40 namespace nav2_smac_planner
41 {
42 
43 // forward declare
44 class NodeLattice;
45 class NodeHybrid;
46 
52 {
57 
63  void initMotionModel(
64  unsigned int & size_x_in,
65  SearchInfo & search_info);
66 
72  MotionPrimitivePtrs getMotionPrimitives(const NodeLattice * node);
73 
81  static LatticeMetadata getLatticeMetadata(const std::string & lattice_filepath);
82 
88  unsigned int getClosestAngularBin(const double & theta);
89 
95  float & getAngleFromBin(const unsigned int & bin_idx);
96 
97  unsigned int size_x;
98  unsigned int num_angle_quantization;
99  float change_penalty;
100  float non_straight_penalty;
101  float cost_penalty;
102  float reverse_penalty;
103  float travel_distance_reward;
104  float rotation_penalty;
105  bool allow_reverse_expansion;
106  std::vector<std::vector<MotionPrimitive>> motion_primitives;
107  ompl::base::StateSpacePtr state_space;
108  std::vector<TrigValues> trig_values;
109  std::string current_lattice_filepath;
110  LatticeMetadata lattice_metadata;
111 };
112 
118 {
119 public:
120  typedef NodeLattice * NodePtr;
121  typedef std::unique_ptr<std::vector<NodeLattice>> Graph;
122  typedef std::vector<NodePtr> NodeVector;
124  typedef NodeHybrid::CoordinateVector CoordinateVector;
125 
130  explicit NodeLattice(const unsigned int index);
131 
135  ~NodeLattice();
136 
142  bool operator==(const NodeLattice & rhs)
143  {
144  return this->_index == rhs._index;
145  }
146 
151  inline void setPose(const Coordinates & pose_in)
152  {
153  pose = pose_in;
154  }
155 
159  void reset();
160 
166  {
167  _motion_primitive = prim;
168  }
169 
175  {
176  return _motion_primitive;
177  }
178 
183  inline float & getAccumulatedCost()
184  {
185  return _accumulated_cost;
186  }
187 
192  inline void setAccumulatedCost(const float & cost_in)
193  {
194  _accumulated_cost = cost_in;
195  }
196 
201  inline float & getCost()
202  {
203  return _cell_cost;
204  }
205 
210  inline bool & wasVisited()
211  {
212  return _was_visited;
213  }
214 
218  inline void visited()
219  {
220  _was_visited = true;
221  }
222 
227  inline unsigned int & getIndex()
228  {
229  return _index;
230  }
231 
235  inline void backwards(bool back = true)
236  {
237  _backwards = back;
238  }
239 
244  inline bool isBackward()
245  {
246  return _backwards;
247  }
248 
259  bool isNodeValid(
260  const bool & traverse_unknown,
261  GridCollisionChecker * collision_checker,
262  MotionPrimitive * primitive = nullptr,
263  bool is_backwards = false);
264 
270  float getTraversalCost(const NodePtr & child);
271 
279  static inline unsigned int getIndex(
280  const unsigned int & x, const unsigned int & y, const unsigned int & angle)
281  {
282  // Hybrid-A* and State Lattice share a coordinate system
283  return NodeHybrid::getIndex(
284  x, y, angle, motion_table.size_x,
285  motion_table.num_angle_quantization);
286  }
287 
295  static inline Coordinates getCoords(
296  const unsigned int & index,
297  const unsigned int & width, const unsigned int & angle_quantization)
298  {
299  // Hybrid-A* and State Lattice share a coordinate system
301  (index / angle_quantization) % width, // x
302  index / (angle_quantization * width), // y
303  index % angle_quantization); // theta
304  }
305 
313  static float getHeuristicCost(
314  const Coordinates & node_coords,
315  const Coordinates & goal_coordinates,
316  const nav2_costmap_2d::Costmap2D * costmap);
317 
326  static void initMotionModel(
327  const MotionModel & motion_model,
328  unsigned int & size_x,
329  unsigned int & size_y,
330  unsigned int & angle_quantization,
331  SearchInfo & search_info);
332 
341  static void precomputeDistanceHeuristic(
342  const float & lookup_table_dim,
343  const MotionModel & motion_model,
344  const unsigned int & dim_3_size,
345  const SearchInfo & search_info);
346 
353  nav2_costmap_2d::Costmap2D * costmap,
354  const unsigned int & start_x, const unsigned int & start_y,
355  const unsigned int & goal_x, const unsigned int & goal_y)
356  {
357  // State Lattice and Hybrid-A* share this heuristics
358  NodeHybrid::resetObstacleHeuristic(costmap, start_x, start_y, goal_x, goal_y);
359  }
360 
367  static float getObstacleHeuristic(
368  const Coordinates & node_coords,
369  const Coordinates & goal_coords,
370  const double & cost_penalty)
371  {
372  return NodeHybrid::getObstacleHeuristic(node_coords, goal_coords, cost_penalty);
373  }
374 
383  static float getDistanceHeuristic(
384  const Coordinates & node_coords,
385  const Coordinates & goal_coords,
386  const float & obstacle_heuristic);
387 
395  void getNeighbors(
396  std::function<bool(const unsigned int &,
397  nav2_smac_planner::NodeLattice * &)> & validity_checker,
398  GridCollisionChecker * collision_checker,
399  const bool & traverse_unknown,
400  NodeVector & neighbors);
401 
407  bool backtracePath(CoordinateVector & path);
408 
413  void addNodeToPath(NodePtr current_node, CoordinateVector & path);
414 
415  NodeLattice * parent;
416  Coordinates pose;
417  static LatticeMotionTable motion_table;
418  // Dubin / Reeds-Shepp lookup and size for dereferencing
419  static LookupTable dist_heuristic_lookup_table;
420  static float size_lookup;
421 
422 private:
423  float _cell_cost;
424  float _accumulated_cost;
425  unsigned int _index;
426  bool _was_visited;
427  MotionPrimitive * _motion_primitive;
428  bool _backwards;
429 };
430 
431 } // namespace nav2_smac_planner
432 
433 #endif // NAV2_SMAC_PLANNER__NODE_LATTICE_HPP_
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:68
A costmap grid collision checker.
static void resetObstacleHeuristic(nav2_costmap_2d::Costmap2D *costmap, const unsigned int &start_x, const unsigned int &start_y, const unsigned int &goal_x, const unsigned int &goal_y)
reset the obstacle heuristic state
static float getObstacleHeuristic(const Coordinates &node_coords, const Coordinates &goal_coords, const double &cost_penalty)
Compute the Obstacle heuristic.
unsigned int & getIndex()
Gets cell index.
NodeLattice implementation for graph, Hybrid-A*.
void backwards(bool back=true)
Sets that this primitive is moving in reverse.
void setAccumulatedCost(const float &cost_in)
Sets the accumulated cost at this node.
~NodeLattice()
A destructor for nav2_smac_planner::NodeLattice.
void reset()
Reset method for new search.
bool backtracePath(CoordinateVector &path)
Set the starting pose for planning, as a node index.
float getTraversalCost(const NodePtr &child)
Get traversal cost of parent node to child node.
void visited()
Sets if cell has been visited in search.
float & getAccumulatedCost()
Gets the accumulated cost at this node.
bool isNodeValid(const bool &traverse_unknown, GridCollisionChecker *collision_checker, MotionPrimitive *primitive=nullptr, bool is_backwards=false)
Check if this node is valid.
static float getHeuristicCost(const Coordinates &node_coords, const Coordinates &goal_coordinates, const nav2_costmap_2d::Costmap2D *costmap)
Get cost of heuristic of node.
unsigned int & getIndex()
Gets cell index.
void addNodeToPath(NodePtr current_node, CoordinateVector &path)
add node to the path
bool isBackward()
Gets if this primitive is moving in reverse.
float & getCost()
Gets the costmap cost at this node.
static void initMotionModel(const MotionModel &motion_model, unsigned int &size_x, unsigned int &size_y, unsigned int &angle_quantization, SearchInfo &search_info)
Initialize motion models.
MotionPrimitive *& getMotionPrimitive()
Gets the motion primitive used to achieve node in search.
static Coordinates getCoords(const unsigned int &index, const unsigned int &width, const unsigned int &angle_quantization)
Get coordinates at index.
static void precomputeDistanceHeuristic(const float &lookup_table_dim, const MotionModel &motion_model, const unsigned int &dim_3_size, const SearchInfo &search_info)
Compute the SE2 distance heuristic.
void getNeighbors(std::function< bool(const unsigned int &, nav2_smac_planner::NodeLattice *&)> &validity_checker, GridCollisionChecker *collision_checker, const bool &traverse_unknown, NodeVector &neighbors)
Retrieve all valid neighbors of a node.
bool operator==(const NodeLattice &rhs)
operator== for comparisons
static unsigned int getIndex(const unsigned int &x, const unsigned int &y, const unsigned int &angle)
Get index at coordinates.
NodeLattice(const unsigned int index)
A constructor for nav2_smac_planner::NodeLattice.
static float getObstacleHeuristic(const Coordinates &node_coords, const Coordinates &goal_coords, const double &cost_penalty)
Compute the Obstacle heuristic.
void setMotionPrimitive(MotionPrimitive *prim)
Sets the motion primitive used to achieve node in search.
bool & wasVisited()
Gets if cell has been visited in search.
static float getDistanceHeuristic(const Coordinates &node_coords, const Coordinates &goal_coords, const float &obstacle_heuristic)
Compute the Distance heuristic.
void setPose(const Coordinates &pose_in)
setting continuous coordinate search poses (in partial-cells)
static void resetObstacleHeuristic(nav2_costmap_2d::Costmap2D *costmap, const unsigned int &start_x, const unsigned int &start_y, const unsigned int &goal_x, const unsigned int &goal_y)
Compute the wavefront heuristic.
A struct of all lattice metadata.
Definition: types.hpp:138
A table of motion primitives and related functions.
static LatticeMetadata getLatticeMetadata(const std::string &lattice_filepath)
Get file metadata needed.
MotionPrimitivePtrs getMotionPrimitives(const NodeLattice *node)
Get projections of motion models.
unsigned int getClosestAngularBin(const double &theta)
Get the angular bin to use from a raw orientation.
void initMotionModel(unsigned int &size_x_in, SearchInfo &search_info)
Initializing state lattice planner's motion model.
float & getAngleFromBin(const unsigned int &bin_idx)
Get the raw orientation from an angular bin.
LatticeMotionTable()
A constructor for nav2_smac_planner::LatticeMotionTable.
A struct of all motion primitive data.
Definition: types.hpp:152
NodeHybrid implementation of coordinate structure.
Search properties and penalties.
Definition: types.hpp:36