15 #ifndef NAV2_SMAC_PLANNER__NODE_LATTICE_HPP_
16 #define NAV2_SMAC_PLANNER__NODE_LATTICE_HPP_
30 #include "nlohmann/json.hpp"
31 #include "ompl/base/StateSpace.h"
32 #include "angles/angles.h"
34 #include "nav2_smac_planner/constants.hpp"
35 #include "nav2_smac_planner/types.hpp"
36 #include "nav2_smac_planner/collision_checker.hpp"
37 #include "nav2_smac_planner/node_hybrid.hpp"
38 #include "nav2_smac_planner/utils.hpp"
40 namespace nav2_smac_planner
64 unsigned int & size_x_in,
98 unsigned int num_angle_quantization;
100 float non_straight_penalty;
102 float reverse_penalty;
103 float travel_distance_reward;
104 float rotation_penalty;
105 bool allow_reverse_expansion;
106 std::vector<std::vector<MotionPrimitive>> motion_primitives;
107 ompl::base::StateSpacePtr state_space;
108 std::vector<TrigValues> trig_values;
109 std::string current_lattice_filepath;
121 typedef std::unique_ptr<std::vector<NodeLattice>> Graph;
122 typedef std::vector<NodePtr> NodeVector;
124 typedef NodeHybrid::CoordinateVector CoordinateVector;
144 return this->_index == rhs._index;
167 _motion_primitive = prim;
176 return _motion_primitive;
185 return _accumulated_cost;
194 _accumulated_cost = cost_in;
260 const bool & traverse_unknown,
263 bool is_backwards =
false);
280 const unsigned int & x,
const unsigned int & y,
const unsigned int & angle)
284 x, y, angle, motion_table.size_x,
285 motion_table.num_angle_quantization);
296 const unsigned int & index,
297 const unsigned int & width,
const unsigned int & angle_quantization)
301 (index / angle_quantization) % width,
302 index / (angle_quantization * width),
303 index % angle_quantization);
314 const Coordinates & node_coords,
315 const Coordinates & goal_coordinates,
327 const MotionModel & motion_model,
328 unsigned int & size_x,
329 unsigned int & size_y,
330 unsigned int & angle_quantization,
342 const float & lookup_table_dim,
343 const MotionModel & motion_model,
344 const unsigned int & dim_3_size,
354 const unsigned int & start_x,
const unsigned int & start_y,
355 const unsigned int & goal_x,
const unsigned int & goal_y)
370 const double & cost_penalty)
384 const Coordinates & node_coords,
385 const Coordinates & goal_coords,
386 const float & obstacle_heuristic);
396 std::function<
bool(
const unsigned int &,
399 const bool & traverse_unknown,
400 NodeVector & neighbors);
413 void addNodeToPath(NodePtr current_node, CoordinateVector & path);
419 static LookupTable dist_heuristic_lookup_table;
420 static float size_lookup;
424 float _accumulated_cost;
A 2D costmap provides a mapping between points in the world and their associated "costs".
A costmap grid collision checker.
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
static float getObstacleHeuristic(const Coordinates &node_coords, const Coordinates &goal_coords, const double &cost_penalty)
Compute the Obstacle heuristic.
unsigned int & getIndex()
Gets cell index.
NodeLattice implementation for graph, Hybrid-A*.
void backwards(bool back=true)
Sets that this primitive is moving in reverse.
void setAccumulatedCost(const float &cost_in)
Sets the accumulated cost at this node.
~NodeLattice()
A destructor for nav2_smac_planner::NodeLattice.
void reset()
Reset method for new search.
bool backtracePath(CoordinateVector &path)
Set the starting pose for planning, as a node index.
float getTraversalCost(const NodePtr &child)
Get traversal cost of parent node to child node.
void visited()
Sets if cell has been visited in search.
float & getAccumulatedCost()
Gets the accumulated cost at this node.
bool isNodeValid(const bool &traverse_unknown, GridCollisionChecker *collision_checker, MotionPrimitive *primitive=nullptr, bool is_backwards=false)
Check if this node is valid.
static float getHeuristicCost(const Coordinates &node_coords, const Coordinates &goal_coordinates, const nav2_costmap_2d::Costmap2D *costmap)
Get cost of heuristic of node.
unsigned int & getIndex()
Gets cell index.
void addNodeToPath(NodePtr current_node, CoordinateVector &path)
add node to the path
bool isBackward()
Gets if this primitive is moving in reverse.
float & getCost()
Gets the costmap 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.
MotionPrimitive *& getMotionPrimitive()
Gets the motion primitive used to achieve node in search.
static Coordinates getCoords(const unsigned int &index, const unsigned int &width, const unsigned int &angle_quantization)
Get coordinates at index.
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.
void getNeighbors(std::function< bool(const unsigned int &, nav2_smac_planner::NodeLattice *&)> &validity_checker, GridCollisionChecker *collision_checker, const bool &traverse_unknown, NodeVector &neighbors)
Retrieve all valid neighbors of a node.
bool operator==(const NodeLattice &rhs)
operator== for comparisons
static unsigned int getIndex(const unsigned int &x, const unsigned int &y, const unsigned int &angle)
Get index at coordinates.
NodeLattice(const unsigned int index)
A constructor for nav2_smac_planner::NodeLattice.
static float getObstacleHeuristic(const Coordinates &node_coords, const Coordinates &goal_coords, const double &cost_penalty)
Compute the Obstacle heuristic.
void setMotionPrimitive(MotionPrimitive *prim)
Sets the motion primitive used to achieve node in search.
bool & wasVisited()
Gets if cell has been visited in search.
static float getDistanceHeuristic(const Coordinates &node_coords, const Coordinates &goal_coords, const float &obstacle_heuristic)
Compute the Distance heuristic.
void setPose(const Coordinates &pose_in)
setting continuous coordinate search poses (in partial-cells)
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)
Compute the wavefront heuristic.
A table of motion primitives and related functions.
static LatticeMetadata getLatticeMetadata(const std::string &lattice_filepath)
Get file metadata needed.
MotionPrimitivePtrs getMotionPrimitives(const NodeLattice *node)
Get projections of motion models.
unsigned int getClosestAngularBin(const double &theta)
Get the angular bin to use from a raw orientation.
void initMotionModel(unsigned int &size_x_in, SearchInfo &search_info)
Initializing state lattice planner's motion model.
float & getAngleFromBin(const unsigned int &bin_idx)
Get the raw orientation from an angular bin.
LatticeMotionTable()
A constructor for nav2_smac_planner::LatticeMotionTable.
A struct of all motion primitive data.
NodeHybrid implementation of coordinate structure.
Search properties and penalties.