Nav2 Navigation Stack - rolling  main
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 <functional>
19 #include <memory>
20 #include <string>
21 #include <vector>
22 
23 #include "ompl/base/StateSpace.h"
24 
25 #include "nav2_smac_planner/constants.hpp"
26 #include "nav2_smac_planner/types.hpp"
27 #include "nav2_smac_planner/collision_checker.hpp"
28 #include "nav2_smac_planner/node_hybrid.hpp"
29 #include "nav2_smac_planner/utils.hpp"
30 #include "nav2_smac_planner/nav2_smac_planner_common_visibility_control.hpp"
31 
32 namespace nav2_smac_planner
33 {
34 
35 // forward declare
36 class NodeLattice;
37 class NodeHybrid;
38 
44 {
49 
55  void initMotionModel(
56  unsigned int & size_x_in,
57  SearchInfo & search_info);
58 
65  MotionPrimitivePtrs getMotionPrimitives(
66  const NodeLattice * node,
67  unsigned int & direction_change_index);
68 
76  static LatticeMetadata getLatticeMetadata(const std::string & lattice_filepath);
77 
83  unsigned int getClosestAngularBin(const double & theta);
84 
90  float & getAngleFromBin(const unsigned int & bin_idx);
91 
97  double getAngle(const double & theta);
98 
99  unsigned int size_x;
100  unsigned int num_angle_quantization;
101  float change_penalty;
102  float non_straight_penalty;
103  float cost_penalty;
104  float reverse_penalty;
105  float travel_distance_reward;
106  float rotation_penalty;
107  float min_turning_radius;
108  bool allow_reverse_expansion;
109  std::vector<std::vector<MotionPrimitive>> motion_primitives;
110  ompl::base::StateSpacePtr state_space;
111  std::vector<TrigValues> trig_values;
112  std::string current_lattice_filepath;
113  LatticeMetadata lattice_metadata;
114  MotionModel motion_model = MotionModel::UNKNOWN;
115 };
116 
122 {
123 public:
124  typedef NodeLattice * NodePtr;
125  typedef std::unique_ptr<std::vector<NodeLattice>> Graph;
126  typedef std::vector<NodePtr> NodeVector;
128  typedef NodeHybrid::CoordinateVector CoordinateVector;
129 
134  explicit NodeLattice(const uint64_t index);
135 
139  ~NodeLattice();
140 
146  bool operator==(const NodeLattice & rhs)
147  {
148  return this->_index == rhs._index;
149  }
150 
155  inline void setPose(const Coordinates & pose_in)
156  {
157  pose = pose_in;
158  }
159 
163  void reset();
164 
170  {
171  _motion_primitive = prim;
172  }
173 
179  {
180  return _motion_primitive;
181  }
182 
187  inline float getAccumulatedCost()
188  {
189  return _accumulated_cost;
190  }
191 
196  inline void setAccumulatedCost(const float & cost_in)
197  {
198  _accumulated_cost = cost_in;
199  }
200 
205  inline float getCost()
206  {
207  return _cell_cost;
208  }
209 
214  inline bool wasVisited()
215  {
216  return _was_visited;
217  }
218 
222  inline void visited()
223  {
224  _was_visited = true;
225  }
226 
231  inline uint64_t getIndex()
232  {
233  return _index;
234  }
235 
239  inline void backwards(bool back = true)
240  {
241  _backwards = back;
242  }
243 
248  inline bool isBackward()
249  {
250  return _backwards;
251  }
252 
263  bool isNodeValid(
264  const bool & traverse_unknown,
265  GridCollisionChecker * collision_checker,
266  MotionPrimitive * primitive = nullptr,
267  bool is_backwards = false);
268 
274  float getTraversalCost(const NodePtr & child);
275 
283  static inline uint64_t getIndex(
284  const unsigned int & x, const unsigned int & y, const unsigned int & angle)
285  {
286  // Hybrid-A* and State Lattice share a coordinate system
287  return NodeHybrid::getIndex(
288  x, y, angle, motion_table.size_x,
289  motion_table.num_angle_quantization);
290  }
291 
299  static inline Coordinates getCoords(
300  const uint64_t & index,
301  const unsigned int & width, const unsigned int & angle_quantization)
302  {
303  // Hybrid-A* and State Lattice share a coordinate system
305  (index / angle_quantization) % width, // x
306  index / (angle_quantization * width), // y
307  index % angle_quantization); // theta
308  }
309 
316  static float getHeuristicCost(
317  const Coordinates & node_coords,
318  const CoordinateVector & goals_coords);
319 
328  static void initMotionModel(
329  const MotionModel & motion_model,
330  unsigned int & size_x,
331  unsigned int & size_y,
332  unsigned int & angle_quantization,
333  SearchInfo & search_info);
334 
343  static void precomputeDistanceHeuristic(
344  const float & lookup_table_dim,
345  const MotionModel & motion_model,
346  const unsigned int & dim_3_size,
347  const SearchInfo & search_info);
348 
355  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros,
356  const unsigned int & start_x, const unsigned int & start_y,
357  const unsigned int & goal_x, const unsigned int & goal_y)
358  {
359  // State Lattice and Hybrid-A* share this heuristics
360  NodeHybrid::resetObstacleHeuristic(costmap_ros, start_x, start_y, goal_x, goal_y);
361  }
362 
369  static float getObstacleHeuristic(
370  const Coordinates & node_coords,
371  const Coordinates & goal_coords,
372  const double & cost_penalty)
373  {
374  return NodeHybrid::getObstacleHeuristic(node_coords, goal_coords, cost_penalty);
375  }
376 
385  static float getDistanceHeuristic(
386  const Coordinates & node_coords,
387  const Coordinates & goal_coords,
388  const float & obstacle_heuristic);
389 
397  void getNeighbors(
398  std::function<bool(const uint64_t &,
399  nav2_smac_planner::NodeLattice * &)> & validity_checker,
400  GridCollisionChecker * collision_checker,
401  const bool & traverse_unknown,
402  NodeVector & neighbors);
403 
409  bool backtracePath(CoordinateVector & path);
410 
415  void addNodeToPath(NodePtr current_node, CoordinateVector & path);
416 
417  NodeLattice * parent;
418  Coordinates pose;
419  NAV2_SMAC_PLANNER_COMMON_EXPORT static LatticeMotionTable motion_table;
420  // Dubin / Reeds-Shepp lookup and size for dereferencing
421  NAV2_SMAC_PLANNER_COMMON_EXPORT static LookupTable dist_heuristic_lookup_table;
422  NAV2_SMAC_PLANNER_COMMON_EXPORT static float size_lookup;
423 
424 private:
425  float _cell_cost;
426  float _accumulated_cost;
427  uint64_t _index;
428  bool _was_visited;
429  MotionPrimitive * _motion_primitive;
430  bool _backwards;
431  bool _is_node_valid{false};
432 };
433 
434 } // namespace nav2_smac_planner
435 
436 #endif // NAV2_SMAC_PLANNER__NODE_LATTICE_HPP_
A costmap grid collision checker.
uint64_t getIndex()
Gets cell index.
static float getObstacleHeuristic(const Coordinates &node_coords, const Coordinates &goal_coords, const float &cost_penalty)
Compute the Obstacle heuristic.
static void resetObstacleHeuristic(std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros, 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
NodeLattice implementation for graph, Hybrid-A*.
void getNeighbors(std::function< bool(const uint64_t &, nav2_smac_planner::NodeLattice *&)> &validity_checker, GridCollisionChecker *collision_checker, const bool &traverse_unknown, NodeVector &neighbors)
Retrieve all valid neighbors of a node.
void backwards(bool back=true)
Sets that this primitive is moving in reverse.
static Coordinates getCoords(const uint64_t &index, const unsigned int &width, const unsigned int &angle_quantization)
Get coordinates at index.
void setAccumulatedCost(const float &cost_in)
Sets the accumulated cost at this node.
uint64_t getIndex()
Gets cell index.
~NodeLattice()
A destructor for nav2_smac_planner::NodeLattice.
float getCost()
Gets the costmap cost at this node.
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.
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 CoordinateVector &goals_coords)
Get cost of heuristic of node.
void addNodeToPath(NodePtr current_node, CoordinateVector &path)
add node to the path
bool isBackward()
Gets if this primitive is moving in reverse.
bool wasVisited()
Gets if cell has been visited in search.
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 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.
bool operator==(const NodeLattice &rhs)
operator== for comparisons
static void resetObstacleHeuristic(std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros, const unsigned int &start_x, const unsigned int &start_y, const unsigned int &goal_x, const unsigned int &goal_y)
Compute the wavefront heuristic.
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.
static uint64_t getIndex(const unsigned int &x, const unsigned int &y, const unsigned int &angle)
Get index at coordinates.
NodeLattice(const uint64_t index)
A constructor for nav2_smac_planner::NodeLattice.
static float getDistanceHeuristic(const Coordinates &node_coords, const Coordinates &goal_coords, const float &obstacle_heuristic)
Compute the Distance heuristic.
float getAccumulatedCost()
Gets the accumulated cost at this node.
void setPose(const Coordinates &pose_in)
setting continuous coordinate search poses (in partial-cells)
A struct of all lattice metadata.
Definition: types.hpp:165
A table of motion primitives and related functions.
static LatticeMetadata getLatticeMetadata(const std::string &lattice_filepath)
Get file metadata needed.
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.
MotionPrimitivePtrs getMotionPrimitives(const NodeLattice *node, unsigned int &direction_change_index)
Get projections of motion models.
float & getAngleFromBin(const unsigned int &bin_idx)
Get the raw orientation from an angular bin.
double getAngle(const double &theta)
Get the angular bin to use from a raw orientation.
LatticeMotionTable()
A constructor for nav2_smac_planner::LatticeMotionTable.
A struct of all motion primitive data.
Definition: types.hpp:179
NodeHybrid implementation of coordinate structure.
Search properties and penalties.
Definition: types.hpp:36