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_smac_planner/nav2_smac_planner_common_visibility_control.hpp"
30 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
31 #include "nav2_costmap_2d/inflation_layer.hpp"
33 namespace nav2_smac_planner
36 typedef std::vector<float> LookupTable;
37 typedef std::pair<double, double> TrigValues;
39 typedef std::pair<float, uint64_t> ObstacleHeuristicElement;
42 bool operator()(
const ObstacleHeuristicElement & a,
const ObstacleHeuristicElement & b)
const
44 return a.first > b.first;
48 typedef std::vector<ObstacleHeuristicElement> ObstacleHeuristicQueue;
72 unsigned int & size_x_in,
73 unsigned int & size_y_in,
74 unsigned int & angle_quantization_in,
85 unsigned int & size_x_in,
86 unsigned int & size_y_in,
87 unsigned int & angle_quantization_in,
116 double getAngle(
const double & theta);
118 MotionModel motion_model = MotionModel::UNKNOWN;
119 MotionPoses projections;
121 unsigned int num_angle_quantization;
122 float num_angle_quantization_float;
123 float min_turning_radius;
125 float change_penalty;
126 float non_straight_penalty;
128 float reverse_penalty;
129 float travel_distance_reward;
130 bool downsample_obstacle_heuristic;
131 bool use_quadratic_cost_penalty;
132 ompl::base::StateSpacePtr state_space;
133 std::vector<std::vector<double>> delta_xs;
134 std::vector<std::vector<double>> delta_ys;
135 std::vector<TrigValues> trig_values;
136 std::vector<float> travel_costs;
147 typedef std::unique_ptr<std::vector<NodeHybrid>> Graph;
148 typedef std::vector<NodePtr> NodeVector;
167 Coordinates(
const float & x_in,
const float & y_in,
const float & theta_in)
168 : x(x_in), y(y_in), theta(theta_in)
171 inline bool operator==(
const Coordinates & rhs)
const
173 return this->x == rhs.x && this->y == rhs.y && this->theta == rhs.theta;
176 inline bool operator!=(
const Coordinates & rhs)
const
178 return !(*
this == rhs);
184 typedef std::vector<Coordinates> CoordinateVector;
204 return this->_index == rhs._index;
227 return _accumulated_cost;
236 _accumulated_cost = cost_in;
245 _motion_primitive_index = idx;
246 _turn_dir = turn_dir;
255 return _motion_primitive_index;
309 const bool & traverse_unknown,
329 const unsigned int & x,
const unsigned int & y,
const unsigned int & angle,
330 const unsigned int & width,
const unsigned int & angle_quantization)
332 return static_cast<uint64_t
>(angle) +
static_cast<uint64_t
>(x) *
333 static_cast<uint64_t
>(angle_quantization) +
334 static_cast<uint64_t
>(y) *
static_cast<uint64_t
>(width) *
335 static_cast<uint64_t
>(angle_quantization);
346 const unsigned int & x,
const unsigned int & y,
const unsigned int & angle)
349 x, y, angle, motion_table.size_x,
350 motion_table.num_angle_quantization);
361 const uint64_t & index,
362 const unsigned int & width,
const unsigned int & angle_quantization)
365 (index / angle_quantization) % width,
366 index / (angle_quantization * width),
367 index % angle_quantization);
377 const Coordinates & node_coords,
378 const CoordinateVector & goals_coords);
389 const MotionModel & motion_model,
390 unsigned int & size_x,
391 unsigned int & size_y,
392 unsigned int & angle_quantization,
404 const float & lookup_table_dim,
405 const MotionModel & motion_model,
406 const unsigned int & dim_3_size,
416 const Coordinates & node_coords,
417 const Coordinates & goal_coords,
418 const float & cost_penalty);
429 const Coordinates & node_coords,
430 const Coordinates & goal_coords,
431 const float & obstacle_heuristic);
439 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros,
440 const unsigned int & start_x,
const unsigned int & start_y,
441 const unsigned int & goal_x,
const unsigned int & goal_y);
451 std::function<
bool(
const uint64_t &,
454 const bool & traverse_unknown,
455 NodeVector & neighbors);
477 NAV2_SMAC_PLANNER_COMMON_EXPORT
static float travel_distance_cost;
480 NAV2_SMAC_PLANNER_COMMON_EXPORT
static LookupTable obstacle_heuristic_lookup_table;
481 NAV2_SMAC_PLANNER_COMMON_EXPORT
static ObstacleHeuristicQueue obstacle_heuristic_queue;
483 NAV2_SMAC_PLANNER_COMMON_EXPORT
static std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros;
485 NAV2_SMAC_PLANNER_COMMON_EXPORT
static LookupTable dist_heuristic_lookup_table;
486 NAV2_SMAC_PLANNER_COMMON_EXPORT
static float size_lookup;
490 float _accumulated_cost;
493 unsigned int _motion_primitive_index;
494 TurnDirection _turn_dir;
495 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.