Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
node_hybrid.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_HYBRID_HPP_
16 #define NAV2_SMAC_PLANNER__NODE_HYBRID_HPP_
17 
18 #include <functional>
19 #include <memory>
20 #include <utility>
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/costmap_downsampler.hpp"
29 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
30 #include "nav2_costmap_2d/inflation_layer.hpp"
31 
32 namespace nav2_smac_planner
33 {
34 
35 typedef std::vector<float> LookupTable;
36 typedef std::pair<double, double> TrigValues;
37 
38 typedef std::pair<float, uint64_t> ObstacleHeuristicElement;
40 {
41  bool operator()(const ObstacleHeuristicElement & a, const ObstacleHeuristicElement & b) const
42  {
43  return a.first > b.first;
44  }
45 };
46 
47 typedef std::vector<ObstacleHeuristicElement> ObstacleHeuristicQueue;
48 
49 // Must forward declare
50 class NodeHybrid;
51 
57 {
62 
70  void initDubin(
71  unsigned int & size_x_in,
72  unsigned int & size_y_in,
73  unsigned int & angle_quantization_in,
74  SearchInfo & search_info);
75 
83  void initReedsShepp(
84  unsigned int & size_x_in,
85  unsigned int & size_y_in,
86  unsigned int & angle_quantization_in,
87  SearchInfo & search_info);
88 
94  MotionPoses getProjections(const NodeHybrid * node);
95 
101  unsigned int getClosestAngularBin(const double & theta);
102 
108  float getAngleFromBin(const unsigned int & bin_idx);
109 
115  double getAngle(const double & theta);
116 
117  MotionModel motion_model = MotionModel::UNKNOWN;
118  MotionPoses projections;
119  unsigned int size_x;
120  unsigned int num_angle_quantization;
121  float num_angle_quantization_float;
122  float min_turning_radius;
123  float bin_size;
124  float change_penalty;
125  float non_straight_penalty;
126  float cost_penalty;
127  float reverse_penalty;
128  float travel_distance_reward;
129  bool downsample_obstacle_heuristic;
130  bool use_quadratic_cost_penalty;
131  ompl::base::StateSpacePtr state_space;
132  std::vector<std::vector<double>> delta_xs;
133  std::vector<std::vector<double>> delta_ys;
134  std::vector<TrigValues> trig_values;
135  std::vector<float> travel_costs;
136 };
137 
143 {
144 public:
145  typedef NodeHybrid * NodePtr;
146  typedef std::unique_ptr<std::vector<NodeHybrid>> Graph;
147  typedef std::vector<NodePtr> NodeVector;
148 
153  struct Coordinates
154  {
159 
166  Coordinates(const float & x_in, const float & y_in, const float & theta_in)
167  : x(x_in), y(y_in), theta(theta_in)
168  {}
169 
170  inline bool operator==(const Coordinates & rhs) const
171  {
172  return this->x == rhs.x && this->y == rhs.y && this->theta == rhs.theta;
173  }
174 
175  inline bool operator!=(const Coordinates & rhs) const
176  {
177  return !(*this == rhs);
178  }
179 
180  float x, y, theta;
181  };
182 
183  typedef std::vector<Coordinates> CoordinateVector;
184 
189  explicit NodeHybrid(const uint64_t index);
190 
194  ~NodeHybrid();
195 
201  bool operator==(const NodeHybrid & rhs)
202  {
203  return this->_index == rhs._index;
204  }
205 
210  inline void setPose(const Coordinates & pose_in)
211  {
212  pose = pose_in;
213  }
214 
218  void reset();
219 
224  inline float getAccumulatedCost()
225  {
226  return _accumulated_cost;
227  }
228 
233  inline void setAccumulatedCost(const float & cost_in)
234  {
235  _accumulated_cost = cost_in;
236  }
237 
242  inline void setMotionPrimitiveIndex(const unsigned int & idx, const TurnDirection & turn_dir)
243  {
244  _motion_primitive_index = idx;
245  _turn_dir = turn_dir;
246  }
247 
252  inline unsigned int & getMotionPrimitiveIndex()
253  {
254  return _motion_primitive_index;
255  }
256 
261  inline TurnDirection & getTurnDirection()
262  {
263  return _turn_dir;
264  }
265 
270  inline float getCost()
271  {
272  return _cell_cost;
273  }
274 
279  inline bool wasVisited()
280  {
281  return _was_visited;
282  }
283 
287  inline void visited()
288  {
289  _was_visited = true;
290  }
291 
296  inline uint64_t getIndex()
297  {
298  return _index;
299  }
300 
307  bool isNodeValid(
308  const bool & traverse_unknown,
309  GridCollisionChecker * collision_checker);
310 
316  float getTraversalCost(const NodePtr & child);
317 
327  static inline uint64_t getIndex(
328  const unsigned int & x, const unsigned int & y, const unsigned int & angle,
329  const unsigned int & width, const unsigned int & angle_quantization)
330  {
331  return static_cast<uint64_t>(angle) + static_cast<uint64_t>(x) *
332  static_cast<uint64_t>(angle_quantization) +
333  static_cast<uint64_t>(y) * static_cast<uint64_t>(width) *
334  static_cast<uint64_t>(angle_quantization);
335  }
336 
344  static inline uint64_t getIndex(
345  const unsigned int & x, const unsigned int & y, const unsigned int & angle)
346  {
347  return getIndex(
348  x, y, angle, motion_table.size_x,
349  motion_table.num_angle_quantization);
350  }
351 
359  static inline Coordinates getCoords(
360  const uint64_t & index,
361  const unsigned int & width, const unsigned int & angle_quantization)
362  {
363  return Coordinates(
364  (index / angle_quantization) % width, // x
365  index / (angle_quantization * width), // y
366  index % angle_quantization); // theta
367  }
368 
375  static float getHeuristicCost(
376  const Coordinates & node_coords,
377  const CoordinateVector & goals_coords);
378 
387  static void initMotionModel(
388  const MotionModel & motion_model,
389  unsigned int & size_x,
390  unsigned int & size_y,
391  unsigned int & angle_quantization,
392  SearchInfo & search_info);
393 
402  static void precomputeDistanceHeuristic(
403  const float & lookup_table_dim,
404  const MotionModel & motion_model,
405  const unsigned int & dim_3_size,
406  const SearchInfo & search_info);
407 
414  static float getObstacleHeuristic(
415  const Coordinates & node_coords,
416  const Coordinates & goal_coords,
417  const float & cost_penalty);
418 
427  static float getDistanceHeuristic(
428  const Coordinates & node_coords,
429  const Coordinates & goal_coords,
430  const float & obstacle_heuristic);
431 
437  static void resetObstacleHeuristic(
438  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros,
439  const unsigned int & start_x, const unsigned int & start_y,
440  const unsigned int & goal_x, const unsigned int & goal_y);
441 
449  void getNeighbors(
450  std::function<bool(const uint64_t &,
451  nav2_smac_planner::NodeHybrid * &)> & validity_checker,
452  GridCollisionChecker * collision_checker,
453  const bool & traverse_unknown,
454  NodeVector & neighbors);
455 
461  bool backtracePath(CoordinateVector & path);
462 
467  static void destroyStaticAssets()
468  {
469  costmap_ros.reset();
470  }
471 
472  NodeHybrid * parent;
473  Coordinates pose;
474 
475  // Constants required across all nodes but don't want to allocate more than once
476  static float travel_distance_cost;
477  static HybridMotionTable motion_table;
478  // Wavefront lookup and queue for continuing to expand as needed
479  static LookupTable obstacle_heuristic_lookup_table;
480  static ObstacleHeuristicQueue obstacle_heuristic_queue;
481 
482  static std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros;
483  // Dubin / Reeds-Shepp lookup and size for dereferencing
484  static LookupTable dist_heuristic_lookup_table;
485  static float size_lookup;
486 
487 private:
488  float _cell_cost;
489  float _accumulated_cost;
490  uint64_t _index;
491  bool _was_visited;
492  unsigned int _motion_primitive_index;
493  TurnDirection _turn_dir;
494  bool _is_node_valid{false};
495 };
496 
497 } // namespace nav2_smac_planner
498 
499 #endif // NAV2_SMAC_PLANNER__NODE_HYBRID_HPP_
A costmap grid collision checker.
NodeHybrid implementation for graph, Hybrid-A*.
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.
uint64_t getIndex()
Gets cell index.
bool isNodeValid(const bool &traverse_unknown, GridCollisionChecker *collision_checker)
Check if this node is valid.
void setAccumulatedCost(const float &cost_in)
Sets the accumulated cost at this node.
float getTraversalCost(const NodePtr &child)
Get traversal cost of parent node to child node.
void setPose(const Coordinates &pose_in)
setting continuous coordinate search poses (in partial-cells)
~NodeHybrid()
A destructor for nav2_smac_planner::NodeHybrid.
void getNeighbors(std::function< bool(const uint64_t &, nav2_smac_planner::NodeHybrid *&)> &validity_checker, GridCollisionChecker *collision_checker, const bool &traverse_unknown, NodeVector &neighbors)
Retrieve all valid neighbors of a node.
float getCost()
Gets the costmap cost at this node.
static void destroyStaticAssets()
Destroy shared pointer assets at the end of the process that don't require normal destruction handlin...
float getAccumulatedCost()
Gets the accumulated 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.
void reset()
Reset method for new search.
bool operator==(const NodeHybrid &rhs)
operator== for comparisons
static uint64_t getIndex(const unsigned int &x, const unsigned int &y, const unsigned int &angle, const unsigned int &width, const unsigned int &angle_quantization)
Get index at coordinates.
void setMotionPrimitiveIndex(const unsigned int &idx, const TurnDirection &turn_dir)
Sets the motion primitive index used to achieve node in search.
unsigned int & getMotionPrimitiveIndex()
Gets the motion primitive index used to achieve node in search.
NodeHybrid(const uint64_t index)
A constructor for nav2_smac_planner::NodeHybrid.
static Coordinates getCoords(const uint64_t &index, const unsigned int &width, const unsigned int &angle_quantization)
Get coordinates at index.
static float getObstacleHeuristic(const Coordinates &node_coords, const Coordinates &goal_coords, const float &cost_penalty)
Compute the Obstacle heuristic.
static uint64_t getIndex(const unsigned int &x, const unsigned int &y, const unsigned int &angle)
Get index at coordinates.
static float getDistanceHeuristic(const Coordinates &node_coords, const Coordinates &goal_coords, const float &obstacle_heuristic)
Compute the Distance heuristic.
bool wasVisited()
Gets if cell has been visited in search.
static float getHeuristicCost(const Coordinates &node_coords, const CoordinateVector &goals_coords)
Get cost of heuristic of node.
TurnDirection & getTurnDirection()
Gets the motion primitive turning direction used to achieve node in search.
bool backtracePath(CoordinateVector &path)
Set the starting pose for planning, as a node index.
void visited()
Sets if cell has been visited in search.
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
A table of motion primitives and related functions.
Definition: node_hybrid.hpp:57
void initReedsShepp(unsigned int &size_x_in, unsigned int &size_y_in, unsigned int &angle_quantization_in, SearchInfo &search_info)
Initializing using Reeds-Shepp model.
MotionPoses getProjections(const NodeHybrid *node)
Get projections of motion models.
double getAngle(const double &theta)
Get the angle scaled across bins from a raw orientation.
HybridMotionTable()
A constructor for nav2_smac_planner::HybridMotionTable.
Definition: node_hybrid.hpp:61
float getAngleFromBin(const unsigned int &bin_idx)
Get the raw orientation from an angular bin.
unsigned int getClosestAngularBin(const double &theta)
Get the angular bin to use from a raw orientation.
void initDubin(unsigned int &size_x_in, unsigned int &size_y_in, unsigned int &angle_quantization_in, SearchInfo &search_info)
Initializing using Dubin model.
Definition: node_hybrid.cpp:56
NodeHybrid implementation of coordinate structure.
Coordinates()
A constructor for nav2_smac_planner::NodeHybrid::Coordinates.
Coordinates(const float &x_in, const float &y_in, const float &theta_in)
A constructor for nav2_smac_planner::NodeHybrid::Coordinates.
Search properties and penalties.
Definition: types.hpp:36