1515#ifndef NAV2_SMAC_PLANNER__ANALYTIC_EXPANSION_HPP_
1616#define NAV2_SMAC_PLANNER__ANALYTIC_EXPANSION_HPP_
1717
18+ #include < ompl/base/ScopedState.h>
19+ #include < ompl/base/spaces/DubinsStateSpace.h>
20+ #include < ompl/base/spaces/ReedsSheppStateSpace.h>
21+
1822#include < functional>
1923#include < list>
2024#include < memory>
@@ -35,8 +39,10 @@ class AnalyticExpansion
3539{
3640public:
3741 typedef NodeT * NodePtr;
42+ typedef std::vector<NodePtr> NodeVector;
3843 typedef typename NodeT::Coordinates Coordinates;
3944 typedef std::function<bool (const uint64_t &, NodeT * &)> NodeGetter;
45+ typedef typename NodeT::CoordinateVector CoordinateVector;
4046
4147 /* *
4248 * @struct nav2_smac_planner::AnalyticExpansion::AnalyticExpansionNodes
@@ -59,7 +65,33 @@ class AnalyticExpansion
5965 Coordinates proposed_coords;
6066 };
6167
62- typedef std::vector<AnalyticExpansionNode> AnalyticExpansionNodes;
68+ /* *
69+ * @struct AnalyticExpansionNodes
70+ * @brief Analytic expansion nodes and associated metadata
71+ *
72+ * This structure holds a collection of analytic expansion nodes and the number of direction
73+ * changes encountered during the expansion.
74+ */
75+ struct AnalyticExpansionNodes
76+ {
77+ AnalyticExpansionNodes () = default ;
78+
79+ void add (
80+ NodePtr & node,
81+ Coordinates & initial_coords,
82+ Coordinates & proposed_coords)
83+ {
84+ nodes.emplace_back (node, initial_coords, proposed_coords);
85+ }
86+
87+ void setDirectionChanges (int changes)
88+ {
89+ direction_changes = changes;
90+ }
91+
92+ std::vector<AnalyticExpansionNode> nodes;
93+ int direction_changes{0 };
94+ };
6395
6496 /* *
6597 * @brief Constructor for analytic expansion object
@@ -79,17 +111,22 @@ class AnalyticExpansion
79111 /* *
80112 * @brief Attempt an analytic path completion
81113 * @param node The node to start the analytic path from
82- * @param goal The goal node to plan to
114+ * @param coarse_check_goals Coarse list of goals nodes to plan to
115+ * @param fine_check_goals Fine list of goals nodes to plan to
116+ * @param goals_coords vector of goal coordinates to plan to
83117 * @param getter Gets a node at a set of coordinates
84118 * @param iterations Iterations to run over
85- * @param best_cost Best heuristic cost to propertionally expand more closer to the goal
86- * @return Node pointer reference to goal node if successful, else
87- * return nullptr
119+ * @param closest_distance Closest distance to goal
120+ * @return Node pointer reference to goal node with the best score out of the goals node if
121+ * successful, else return nullptr
88122 */
89123 NodePtr tryAnalyticExpansion (
90124 const NodePtr & current_node,
91- const NodePtr & goal_node,
92- const NodeGetter & getter, int & iterations, int & best_cost);
125+ const NodeVector & coarse_check_goals,
126+ const NodeVector & fine_check_goals,
127+ const CoordinateVector & goals_coords,
128+ const NodeGetter & getter, int & iterations,
129+ int & closest_distance);
93130
94131 /* *
95132 * @brief Perform an analytic path expansion to the goal
@@ -103,6 +140,21 @@ class AnalyticExpansion
103140 const NodePtr & node, const NodePtr & goal,
104141 const NodeGetter & getter, const ompl::base::StateSpacePtr & state_space);
105142
143+ /* *
144+ * @brief Refined analytic path from the current node to the goal
145+ * @param node The node to start the analytic path from. Node head may
146+ * change as a result of refinement
147+ * @param goal_node The goal node to plan to
148+ * @param getter The function object that gets valid nodes from the graph
149+ * @param analytic_nodes The set of analytic nodes to refine
150+ * @return The score of the refined path
151+ */
152+ float refineAnalyticPath (
153+ NodePtr & node,
154+ const NodePtr & goal_node,
155+ const NodeGetter & getter,
156+ AnalyticExpansionNodes & analytic_nodes);
157+
106158 /* *
107159 * @brief Takes final analytic expansion and appends to current expanded node
108160 * @param node The node to start the analytic path from
@@ -114,6 +166,13 @@ class AnalyticExpansion
114166 const NodePtr & node, const NodePtr & goal,
115167 const AnalyticExpansionNodes & expanded_nodes);
116168
169+ /* *
170+ * @brief Counts the number of direction changes in a Reeds-Shepp path
171+ * @param path The Reeds-Shepp path to count direction changes in
172+ * @return The number of direction changes in the path
173+ */
174+ int countDirectionChanges (const ompl::base::ReedsSheppStateSpace::ReedsSheppPath & path);
175+
117176 /* *
118177 * @brief Takes an expanded nodes to clean up, if necessary, of any state
119178 * information that may be polluting it from a prior search iteration
0 commit comments