15 #ifndef NAV2_SMAC_PLANNER__NODE_HYBRID_HPP_
16 #define NAV2_SMAC_PLANNER__NODE_HYBRID_HPP_
28 #include "ompl/base/StateSpace.h"
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"
35 namespace nav2_smac_planner
38 typedef std::vector<float> LookupTable;
39 typedef std::pair<double, double> TrigValues;
41 typedef std::pair<float, unsigned int> ObstacleHeuristicElement;
44 bool operator()(
const ObstacleHeuristicElement & a,
const ObstacleHeuristicElement & b)
const
46 return a.first > b.first;
50 typedef std::vector<ObstacleHeuristicElement> ObstacleHeuristicQueue;
74 unsigned int & size_x_in,
75 unsigned int & size_y_in,
76 unsigned int & angle_quantization_in,
87 unsigned int & size_x_in,
88 unsigned int & size_y_in,
89 unsigned int & angle_quantization_in,
113 MotionModel motion_model = MotionModel::UNKNOWN;
114 MotionPoses projections;
116 unsigned int num_angle_quantization;
117 float num_angle_quantization_float;
118 float min_turning_radius;
120 float change_penalty;
121 float non_straight_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;
139 typedef std::unique_ptr<std::vector<NodeHybrid>> Graph;
140 typedef std::vector<NodePtr> NodeVector;
159 Coordinates(
const float & x_in,
const float & y_in,
const float & theta_in)
160 : x(x_in), y(y_in), theta(theta_in)
165 return this->x == rhs.x && this->y == rhs.y && this->theta == rhs.theta;
170 return !(*
this == rhs);
176 typedef std::vector<Coordinates> CoordinateVector;
182 explicit NodeHybrid(
const unsigned int index);
196 return this->_index == rhs._index;
219 return _accumulated_cost;
228 _accumulated_cost = cost_in;
237 _motion_primitive_index = idx;
246 return _motion_primitive_index;
308 const unsigned int & x,
const unsigned int & y,
const unsigned int & angle,
309 const unsigned int & width,
const unsigned int & angle_quantization)
311 return angle + x * angle_quantization + y * width * angle_quantization;
322 const unsigned int & x,
const unsigned int & y,
const unsigned int & angle)
325 x, y, angle, motion_table.size_x,
326 motion_table.num_angle_quantization);
337 const unsigned int & index,
338 const unsigned int & width,
const unsigned int & angle_quantization)
341 (index / angle_quantization) % width,
342 index / (angle_quantization * width),
343 index % angle_quantization);
354 const Coordinates & node_coords,
355 const Coordinates & goal_coordinates,
367 const MotionModel & motion_model,
368 unsigned int & size_x,
369 unsigned int & size_y,
370 unsigned int & angle_quantization,
382 const float & lookup_table_dim,
383 const MotionModel & motion_model,
384 const unsigned int & dim_3_size,
394 const Coordinates & node_coords,
395 const Coordinates & goal_coords,
396 const double & cost_penalty);
407 const Coordinates & node_coords,
408 const Coordinates & goal_coords,
409 const float & obstacle_heuristic);
418 const unsigned int & start_x,
const unsigned int & start_y,
419 const unsigned int & goal_x,
const unsigned int & goal_y);
431 const bool & traverse_unknown,
432 NodeVector & neighbors);
445 static double travel_distance_cost;
448 static LookupTable obstacle_heuristic_lookup_table;
449 static ObstacleHeuristicQueue obstacle_heuristic_queue;
454 static LookupTable dist_heuristic_lookup_table;
455 static float size_lookup;
459 float _accumulated_cost;
462 unsigned int _motion_primitive_index;
A 2D costmap provides a mapping between points in the world and their associated "costs".
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.
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.
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.
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.