15 #ifndef NAV2_SMAC_PLANNER__ANALYTIC_EXPANSION_HPP_
16 #define NAV2_SMAC_PLANNER__ANALYTIC_EXPANSION_HPP_
23 #include "nav2_smac_planner/node_2d.hpp"
24 #include "nav2_smac_planner/node_hybrid.hpp"
25 #include "nav2_smac_planner/node_lattice.hpp"
26 #include "nav2_smac_planner/types.hpp"
27 #include "nav2_smac_planner/constants.hpp"
29 namespace nav2_smac_planner
32 template<
typename NodeT>
36 typedef NodeT * NodePtr;
37 typedef typename NodeT::Coordinates Coordinates;
38 typedef std::function<bool (
const uint64_t &, NodeT * &)> NodeGetter;
48 Coordinates & initial_coords_in,
49 Coordinates & proposed_coords_in)
51 initial_coords(initial_coords_in),
52 proposed_coords(proposed_coords_in)
57 Coordinates initial_coords;
58 Coordinates proposed_coords;
61 typedef std::vector<AnalyticExpansionNode> AnalyticExpansionNodes;
67 const MotionModel & motion_model,
69 const bool & traverse_unknown,
70 const unsigned int & dim_3_size);
89 const NodePtr & current_node,
90 const NodePtr & goal_node,
91 const NodeGetter & getter,
int & iterations,
int & best_cost);
102 const NodePtr & node,
const NodePtr & goal,
103 const NodeGetter & getter,
const ompl::base::StateSpacePtr & state_space);
113 const NodePtr & node,
const NodePtr & goal,
114 const AnalyticExpansionNodes & expanded_nodes);
124 MotionModel _motion_model;
126 bool _traverse_unknown;
127 unsigned int _dim_3_size;
129 std::list<std::unique_ptr<NodeT>> _detached_nodes;
AnalyticExpansionNodes getAnalyticPath(const NodePtr &node, const NodePtr &goal, const NodeGetter &getter, const ompl::base::StateSpacePtr &state_space)
Perform an analytic path expansion to the goal.
NodePtr tryAnalyticExpansion(const NodePtr ¤t_node, const NodePtr &goal_node, const NodeGetter &getter, int &iterations, int &best_cost)
Attempt an analytic path completion.
void cleanNode(const NodePtr &nodes)
Takes an expanded nodes to clean up, if necessary, of any state information that may be poluting it f...
void setCollisionChecker(GridCollisionChecker *collision_checker)
Sets the collision checker and costmap to use in expansion validation.
AnalyticExpansion(const MotionModel &motion_model, const SearchInfo &search_info, const bool &traverse_unknown, const unsigned int &dim_3_size)
Constructor for analytic expansion object.
NodePtr setAnalyticPath(const NodePtr &node, const NodePtr &goal, const AnalyticExpansionNodes &expanded_nodes)
Takes final analytic expansion and appends to current expanded node.
A costmap grid collision checker.
Search properties and penalties.