Nav2 Navigation Stack - humble  humble
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 <math.h>
19 #include <vector>
20 #include <cmath>
21 #include <iostream>
22 #include <functional>
23 #include <queue>
24 #include <memory>
25 #include <utility>
26 #include <limits>
27 
28 #include "ompl/base/StateSpace.h"
29 
30 #include "nav2_smac_planner/constants.hpp"
31 #include "nav2_smac_planner/types.hpp"
32 #include "nav2_smac_planner/collision_checker.hpp"
33 #include "nav2_smac_planner/costmap_downsampler.hpp"
34 
35 namespace nav2_smac_planner
36 {
37 
38 typedef std::vector<float> LookupTable;
39 typedef std::pair<double, double> TrigValues;
40 
41 typedef std::pair<float, unsigned int> ObstacleHeuristicElement;
43 {
44  bool operator()(const ObstacleHeuristicElement & a, const ObstacleHeuristicElement & b) const
45  {
46  return a.first > b.first;
47  }
48 };
49 
50 typedef std::vector<ObstacleHeuristicElement> ObstacleHeuristicQueue;
51 
52 // Must forward declare
53 class NodeHybrid;
54 
60 {
65 
73  void initDubin(
74  unsigned int & size_x_in,
75  unsigned int & size_y_in,
76  unsigned int & angle_quantization_in,
77  SearchInfo & search_info);
78 
86  void initReedsShepp(
87  unsigned int & size_x_in,
88  unsigned int & size_y_in,
89  unsigned int & angle_quantization_in,
90  SearchInfo & search_info);
91 
97  MotionPoses getProjections(const NodeHybrid * node);
98 
104  unsigned int getClosestAngularBin(const double & theta);
105 
111  float getAngleFromBin(const unsigned int & bin_idx);
112 
113  MotionModel motion_model = MotionModel::UNKNOWN;
114  MotionPoses projections;
115  unsigned int size_x;
116  unsigned int num_angle_quantization;
117  float num_angle_quantization_float;
118  float min_turning_radius;
119  float bin_size;
120  float change_penalty;
121  float non_straight_penalty;
122  float cost_penalty;
123  float reverse_penalty;
124  float travel_distance_reward;
125  ompl::base::StateSpacePtr state_space;
126  std::vector<std::vector<double>> delta_xs;
127  std::vector<std::vector<double>> delta_ys;
128  std::vector<TrigValues> trig_values;
129 };
130 
136 {
137 public:
138  typedef NodeHybrid * NodePtr;
139  typedef std::unique_ptr<std::vector<NodeHybrid>> Graph;
140  typedef std::vector<NodePtr> NodeVector;
141 
146  struct Coordinates
147  {
152 
159  Coordinates(const float & x_in, const float & y_in, const float & theta_in)
160  : x(x_in), y(y_in), theta(theta_in)
161  {}
162 
163  inline bool operator==(const Coordinates & rhs)
164  {
165  return this->x == rhs.x && this->y == rhs.y && this->theta == rhs.theta;
166  }
167 
168  inline bool operator!=(const Coordinates & rhs)
169  {
170  return !(*this == rhs);
171  }
172 
173  float x, y, theta;
174  };
175 
176  typedef std::vector<Coordinates> CoordinateVector;
177 
182  explicit NodeHybrid(const unsigned int index);
183 
187  ~NodeHybrid();
188 
194  bool operator==(const NodeHybrid & rhs)
195  {
196  return this->_index == rhs._index;
197  }
198 
203  inline void setPose(const Coordinates & pose_in)
204  {
205  pose = pose_in;
206  }
207 
211  void reset();
212 
217  inline float & getAccumulatedCost()
218  {
219  return _accumulated_cost;
220  }
221 
226  inline void setAccumulatedCost(const float & cost_in)
227  {
228  _accumulated_cost = cost_in;
229  }
230 
235  inline void setMotionPrimitiveIndex(const unsigned int & idx)
236  {
237  _motion_primitive_index = idx;
238  }
239 
244  inline unsigned int & getMotionPrimitiveIndex()
245  {
246  return _motion_primitive_index;
247  }
248 
253  inline float & getCost()
254  {
255  return _cell_cost;
256  }
257 
262  inline bool & wasVisited()
263  {
264  return _was_visited;
265  }
266 
270  inline void visited()
271  {
272  _was_visited = true;
273  }
274 
279  inline unsigned int & getIndex()
280  {
281  return _index;
282  }
283 
289  bool isNodeValid(const bool & traverse_unknown, GridCollisionChecker * collision_checker);
290 
296  float getTraversalCost(const NodePtr & child);
297 
307  static inline unsigned int getIndex(
308  const unsigned int & x, const unsigned int & y, const unsigned int & angle,
309  const unsigned int & width, const unsigned int & angle_quantization)
310  {
311  return angle + x * angle_quantization + y * width * angle_quantization;
312  }
313 
321  static inline unsigned int getIndex(
322  const unsigned int & x, const unsigned int & y, const unsigned int & angle)
323  {
324  return getIndex(
325  x, y, angle, motion_table.size_x,
326  motion_table.num_angle_quantization);
327  }
328 
336  static inline Coordinates getCoords(
337  const unsigned int & index,
338  const unsigned int & width, const unsigned int & angle_quantization)
339  {
340  return Coordinates(
341  (index / angle_quantization) % width, // x
342  index / (angle_quantization * width), // y
343  index % angle_quantization); // theta
344  }
345 
353  static float getHeuristicCost(
354  const Coordinates & node_coords,
355  const Coordinates & goal_coordinates,
356  const nav2_costmap_2d::Costmap2D * costmap);
357 
366  static void initMotionModel(
367  const MotionModel & motion_model,
368  unsigned int & size_x,
369  unsigned int & size_y,
370  unsigned int & angle_quantization,
371  SearchInfo & search_info);
372 
381  static void precomputeDistanceHeuristic(
382  const float & lookup_table_dim,
383  const MotionModel & motion_model,
384  const unsigned int & dim_3_size,
385  const SearchInfo & search_info);
386 
393  static float getObstacleHeuristic(
394  const Coordinates & node_coords,
395  const Coordinates & goal_coords,
396  const double & cost_penalty);
397 
406  static float getDistanceHeuristic(
407  const Coordinates & node_coords,
408  const Coordinates & goal_coords,
409  const float & obstacle_heuristic);
410 
416  static void resetObstacleHeuristic(
417  nav2_costmap_2d::Costmap2D * costmap,
418  const unsigned int & start_x, const unsigned int & start_y,
419  const unsigned int & goal_x, const unsigned int & goal_y);
420 
428  void getNeighbors(
429  std::function<bool(const unsigned int &, nav2_smac_planner::NodeHybrid * &)> & validity_checker,
430  GridCollisionChecker * collision_checker,
431  const bool & traverse_unknown,
432  NodeVector & neighbors);
433 
439  bool backtracePath(CoordinateVector & path);
440 
441  NodeHybrid * parent;
442  Coordinates pose;
443 
444  // Constants required across all nodes but don't want to allocate more than once
445  static double travel_distance_cost;
446  static HybridMotionTable motion_table;
447  // Wavefront lookup and queue for continuing to expand as needed
448  static LookupTable obstacle_heuristic_lookup_table;
449  static ObstacleHeuristicQueue obstacle_heuristic_queue;
450 
451  static nav2_costmap_2d::Costmap2D * sampled_costmap;
452  static CostmapDownsampler downsampler;
453  // Dubin / Reeds-Shepp lookup and size for dereferencing
454  static LookupTable dist_heuristic_lookup_table;
455  static float size_lookup;
456 
457 private:
458  float _cell_cost;
459  float _accumulated_cost;
460  unsigned int _index;
461  bool _was_visited;
462  unsigned int _motion_primitive_index;
463 };
464 
465 } // namespace nav2_smac_planner
466 
467 #endif // NAV2_SMAC_PLANNER__NODE_HYBRID_HPP_
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:68
A costmap downsampler for more efficient path planning.
A costmap grid collision checker.
NodeHybrid implementation for graph, Hybrid-A*.
static float getHeuristicCost(const Coordinates &node_coords, const Coordinates &goal_coordinates, const nav2_costmap_2d::Costmap2D *costmap)
Get cost of heuristic of node.
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 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.
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
void setPose(const Coordinates &pose_in)
setting continuous coordinate search poses (in partial-cells)
~NodeHybrid()
A destructor for nav2_smac_planner::NodeHybrid.
void setMotionPrimitiveIndex(const unsigned int &idx)
Sets the motion primitive index used to achieve node in search.
float & getAccumulatedCost()
Gets the accumulated cost at this node.
static unsigned int getIndex(const unsigned int &x, const unsigned int &y, const unsigned int &angle)
Get index at coordinates.
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
unsigned int & getMotionPrimitiveIndex()
Gets the motion primitive index used to achieve node in search.
static unsigned int 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.
static float getObstacleHeuristic(const Coordinates &node_coords, const Coordinates &goal_coords, const double &cost_penalty)
Compute the Obstacle heuristic.
bool & wasVisited()
Gets if cell has been visited in search.
void getNeighbors(std::function< bool(const unsigned int &, nav2_smac_planner::NodeHybrid *&)> &validity_checker, GridCollisionChecker *collision_checker, const bool &traverse_unknown, NodeVector &neighbors)
Retrieve all valid neighbors of a node.
static float getDistanceHeuristic(const Coordinates &node_coords, const Coordinates &goal_coords, const float &obstacle_heuristic)
Compute the Distance heuristic.
NodeHybrid(const unsigned int index)
A constructor for nav2_smac_planner::NodeHybrid.
unsigned int & getIndex()
Gets cell index.
bool backtracePath(CoordinateVector &path)
Set the starting pose for planning, as a node index.
static Coordinates getCoords(const unsigned int &index, const unsigned int &width, const unsigned int &angle_quantization)
Get coordinates at index.
void visited()
Sets if cell has been visited in search.
float & getCost()
Gets the costmap cost at this node.
A table of motion primitives and related functions.
Definition: node_hybrid.hpp:60
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.
HybridMotionTable()
A constructor for nav2_smac_planner::HybridMotionTable.
Definition: node_hybrid.hpp:64
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:55
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