Nav2 Navigation Stack - kilted  kilted
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 
31 namespace nav2_smac_planner
32 {
33 
34 // forward declare
35 class NodeLattice;
36 class NodeHybrid;
37 
43 {
48 
54  void initMotionModel(
55  unsigned int & size_x_in,
56  SearchInfo & search_info);
57 
64  MotionPrimitivePtrs getMotionPrimitives(
65  const NodeLattice * node,
66  unsigned int & direction_change_index);
67 
75  static LatticeMetadata getLatticeMetadata(const std::string & lattice_filepath);
76 
82  unsigned int getClosestAngularBin(const double & theta);
83 
89  float & getAngleFromBin(const unsigned int & bin_idx);
90 
96  double getAngle(const double & theta);
97 
98  unsigned int size_x;
99  unsigned int num_angle_quantization;
100  float change_penalty;
101  float non_straight_penalty;
102  float cost_penalty;
103  float reverse_penalty;
104  float travel_distance_reward;
105  float rotation_penalty;
106  float min_turning_radius;
107  bool allow_reverse_expansion;
108  std::vector<std::vector<MotionPrimitive>> motion_primitives;
109  ompl::base::StateSpacePtr state_space;
110  std::vector<TrigValues> trig_values;
111  std::string current_lattice_filepath;
112  LatticeMetadata lattice_metadata;
113  MotionModel motion_model = MotionModel::UNKNOWN;
114 };
115 
121 {
122 public:
123  typedef NodeLattice * NodePtr;
124  typedef std::unique_ptr<std::vector<NodeLattice>> Graph;
125  typedef std::vector<NodePtr> NodeVector;
127  typedef NodeHybrid::CoordinateVector CoordinateVector;
128 
133  explicit NodeLattice(const uint64_t index);
134 
138  ~NodeLattice();
139 
145  bool operator==(const NodeLattice & rhs)
146  {
147  return this->_index == rhs._index;
148  }
149 
154  inline void setPose(const Coordinates & pose_in)
155  {
156  pose = pose_in;
157  }
158 
162  void reset();
163 
169  {
170  _motion_primitive = prim;
171  }
172 
178  {
179  return _motion_primitive;
180  }
181 
186  inline float getAccumulatedCost()
187  {
188  return _accumulated_cost;
189  }
190 
195  inline void setAccumulatedCost(const float & cost_in)
196  {
197  _accumulated_cost = cost_in;
198  }
199 
204  inline float getCost()
205  {
206  return _cell_cost;
207  }
208 
213  inline bool wasVisited()
214  {
215  return _was_visited;
216  }
217 
221  inline void visited()
222  {
223  _was_visited = true;
224  }
225 
230  inline uint64_t getIndex()
231  {
232  return _index;
233  }
234 
238  inline void backwards(bool back = true)
239  {
240  _backwards = back;
241  }
242 
247  inline bool isBackward()
248  {
249  return _backwards;
250  }
251 
262  bool isNodeValid(
263  const bool & traverse_unknown,
264  GridCollisionChecker * collision_checker,
265  MotionPrimitive * primitive = nullptr,
266  bool is_backwards = false);
267 
273  float getTraversalCost(const NodePtr & child);
274 
282  static inline uint64_t getIndex(
283  const unsigned int & x, const unsigned int & y, const unsigned int & angle)
284  {
285  // Hybrid-A* and State Lattice share a coordinate system
286  return NodeHybrid::getIndex(
287  x, y, angle, motion_table.size_x,
288  motion_table.num_angle_quantization);
289  }
290 
298  static inline Coordinates getCoords(
299  const uint64_t & index,
300  const unsigned int & width, const unsigned int & angle_quantization)
301  {
302  // Hybrid-A* and State Lattice share a coordinate system
304  (index / angle_quantization) % width, // x
305  index / (angle_quantization * width), // y
306  index % angle_quantization); // theta
307  }
308 
315  static float getHeuristicCost(
316  const Coordinates & node_coords,
317  const CoordinateVector & goals_coords);
318 
327  static void initMotionModel(
328  const MotionModel & motion_model,
329  unsigned int & size_x,
330  unsigned int & size_y,
331  unsigned int & angle_quantization,
332  SearchInfo & search_info);
333 
342  static void precomputeDistanceHeuristic(
343  const float & lookup_table_dim,
344  const MotionModel & motion_model,
345  const unsigned int & dim_3_size,
346  const SearchInfo & search_info);
347 
354  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros,
355  const unsigned int & start_x, const unsigned int & start_y,
356  const unsigned int & goal_x, const unsigned int & goal_y)
357  {
358  // State Lattice and Hybrid-A* share this heuristics
359  NodeHybrid::resetObstacleHeuristic(costmap_ros, start_x, start_y, goal_x, goal_y);
360  }
361 
368  static float getObstacleHeuristic(
369  const Coordinates & node_coords,
370  const Coordinates & goal_coords,
371  const double & cost_penalty)
372  {
373  return NodeHybrid::getObstacleHeuristic(node_coords, goal_coords, cost_penalty);
374  }
375 
384  static float getDistanceHeuristic(
385  const Coordinates & node_coords,
386  const Coordinates & goal_coords,
387  const float & obstacle_heuristic);
388 
396  void getNeighbors(
397  std::function<bool(const uint64_t &,
398  nav2_smac_planner::NodeLattice * &)> & validity_checker,
399  GridCollisionChecker * collision_checker,
400  const bool & traverse_unknown,
401  NodeVector & neighbors);
402 
408  bool backtracePath(CoordinateVector & path);
409 
414  void addNodeToPath(NodePtr current_node, CoordinateVector & path);
415 
416  NodeLattice * parent;
417  Coordinates pose;
418  static LatticeMotionTable motion_table;
419  // Dubin / Reeds-Shepp lookup and size for dereferencing
420  static LookupTable dist_heuristic_lookup_table;
421  static float size_lookup;
422 
423 private:
424  float _cell_cost;
425  float _accumulated_cost;
426  uint64_t _index;
427  bool _was_visited;
428  MotionPrimitive * _motion_primitive;
429  bool _backwards;
430  bool _is_node_valid{false};
431 };
432 
433 } // namespace nav2_smac_planner
434 
435 #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