15 #ifndef NAV2_SMAC_PLANNER__NODE_HYBRID_HPP_
16 #define NAV2_SMAC_PLANNER__NODE_HYBRID_HPP_
23 #include "ompl/base/StateSpace.h"
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"
32 namespace nav2_smac_planner
35 typedef std::vector<float> LookupTable;
36 typedef std::pair<double, double> TrigValues;
38 typedef std::pair<float, uint64_t> ObstacleHeuristicElement;
41 bool operator()(
const ObstacleHeuristicElement & a,
const ObstacleHeuristicElement & b)
const
43 return a.first > b.first;
47 typedef std::vector<ObstacleHeuristicElement> ObstacleHeuristicQueue;
71 unsigned int & size_x_in,
72 unsigned int & size_y_in,
73 unsigned int & angle_quantization_in,
84 unsigned int & size_x_in,
85 unsigned int & size_y_in,
86 unsigned int & angle_quantization_in,
115 double getAngle(
const double & theta);
117 MotionModel motion_model = MotionModel::UNKNOWN;
118 MotionPoses projections;
120 unsigned int num_angle_quantization;
121 float num_angle_quantization_float;
122 float min_turning_radius;
124 float change_penalty;
125 float non_straight_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;
146 typedef std::unique_ptr<std::vector<NodeHybrid>> Graph;
147 typedef std::vector<NodePtr> NodeVector;
166 Coordinates(
const float & x_in,
const float & y_in,
const float & theta_in)
167 : x(x_in), y(y_in), theta(theta_in)
170 inline bool operator==(
const Coordinates & rhs)
const
172 return this->x == rhs.x && this->y == rhs.y && this->theta == rhs.theta;
175 inline bool operator!=(
const Coordinates & rhs)
const
177 return !(*
this == rhs);
183 typedef std::vector<Coordinates> CoordinateVector;
203 return this->_index == rhs._index;
226 return _accumulated_cost;
235 _accumulated_cost = cost_in;
244 _motion_primitive_index = idx;
245 _turn_dir = turn_dir;
254 return _motion_primitive_index;
308 const bool & traverse_unknown,
328 const unsigned int & x,
const unsigned int & y,
const unsigned int & angle,
329 const unsigned int & width,
const unsigned int & angle_quantization)
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);
345 const unsigned int & x,
const unsigned int & y,
const unsigned int & angle)
348 x, y, angle, motion_table.size_x,
349 motion_table.num_angle_quantization);
360 const uint64_t & index,
361 const unsigned int & width,
const unsigned int & angle_quantization)
364 (index / angle_quantization) % width,
365 index / (angle_quantization * width),
366 index % angle_quantization);
376 const Coordinates & node_coords,
377 const CoordinateVector & goals_coords);
388 const MotionModel & motion_model,
389 unsigned int & size_x,
390 unsigned int & size_y,
391 unsigned int & angle_quantization,
403 const float & lookup_table_dim,
404 const MotionModel & motion_model,
405 const unsigned int & dim_3_size,
415 const Coordinates & node_coords,
416 const Coordinates & goal_coords,
417 const float & cost_penalty);
428 const Coordinates & node_coords,
429 const Coordinates & goal_coords,
430 const float & obstacle_heuristic);
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);
450 std::function<
bool(
const uint64_t &,
453 const bool & traverse_unknown,
454 NodeVector & neighbors);
476 static float travel_distance_cost;
479 static LookupTable obstacle_heuristic_lookup_table;
480 static ObstacleHeuristicQueue obstacle_heuristic_queue;
482 static std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros;
484 static LookupTable dist_heuristic_lookup_table;
485 static float size_lookup;
489 float _accumulated_cost;
492 unsigned int _motion_primitive_index;
493 TurnDirection _turn_dir;
494 bool _is_node_valid{
false};
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.
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.
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.