Skip to content

Commit a9647ad

Browse files
Revert recent smac changes causing regressions (#5221)
* Revert "Prototype solving #5192 Issue 2: Reeds-Shepp reduce small reverse expansions (#5207)" This reverts commit c32873d. * Revert "include bug fix for nav2_smac_planner (#5198)" This reverts commit 6a74ba6. * Revert "Feat/smac planner include orientation flexibility (#4127)" This reverts commit f5543c3.
1 parent 1345c22 commit a9647ad

26 files changed

+169
-5294
lines changed

nav2_bringup/launch/tb3_loopback_simulation_launch.py

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -144,8 +144,6 @@ def generate_launch_description() -> LaunchDescription:
144144
'use_composition': use_composition,
145145
'use_respawn': use_respawn,
146146
'use_localization': 'False', # Don't use SLAM, AMCL
147-
'use_keepout_zones': 'False',
148-
'use_speed_zones': 'False',
149147
}.items(),
150148
)
151149

nav2_bringup/launch/tb3_simulation_launch.py

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -195,8 +195,6 @@ def generate_launch_description() -> LaunchDescription:
195195
'autostart': autostart,
196196
'use_composition': use_composition,
197197
'use_respawn': use_respawn,
198-
'use_keepout_zones': 'False',
199-
'use_speed_zones': 'False',
200198
}.items(),
201199
)
202200
# The SDF file for the world is a xacro file because we wanted to

nav2_smac_planner/include/nav2_smac_planner/a_star.hpp

Lines changed: 17 additions & 30 deletions
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,6 @@
3232
#include "nav2_smac_planner/node_hybrid.hpp"
3333
#include "nav2_smac_planner/node_lattice.hpp"
3434
#include "nav2_smac_planner/node_basic.hpp"
35-
#include "nav2_smac_planner/goal_manager.hpp"
3635
#include "nav2_smac_planner/types.hpp"
3736
#include "nav2_smac_planner/constants.hpp"
3837

@@ -55,9 +54,6 @@ class AStarAlgorithm
5554
typedef typename NodeT::CoordinateVector CoordinateVector;
5655
typedef typename NodeVector::iterator NeighborIterator;
5756
typedef std::function<bool (const uint64_t &, NodeT * &)> NodeGetter;
58-
typedef GoalManager<NodeT> GoalManagerT;
59-
typedef std::vector<GoalState<NodeT>> GoalStateVector;
60-
6157

6258
/**
6359
* @struct nav2_smac_planner::NodeComparator
@@ -94,8 +90,6 @@ class AStarAlgorithm
9490
* or planning time exceeded
9591
* @param max_planning_time Maximum time (in seconds) to wait for a plan, createPath returns
9692
* false after this timeout
97-
* @param lookup_table_size Size of the lookup table to store heuristic values
98-
* @param dim_3_size Number of quantization bins
9993
*/
10094
void initialize(
10195
const bool & allow_unknown,
@@ -131,15 +125,11 @@ class AStarAlgorithm
131125
* @param mx The node X index of the goal
132126
* @param my The node Y index of the goal
133127
* @param dim_3 The node dim_3 index of the goal
134-
* @param goal_heading_mode The goal heading mode to use
135-
* @param coarse_search_resolution The resolution to search for goal heading
136128
*/
137129
void setGoal(
138130
const float & mx,
139131
const float & my,
140-
const unsigned int & dim_3,
141-
const GoalHeadingMode & goal_heading_mode = GoalHeadingMode::DEFAULT,
142-
const int & coarse_search_resolution = 1);
132+
const unsigned int & dim_3);
143133

144134
/**
145135
* @brief Set the starting pose for planning, as a node index
@@ -164,6 +154,12 @@ class AStarAlgorithm
164154
*/
165155
NodePtr & getStart();
166156

157+
/**
158+
* @brief Get pointer reference to goal node
159+
* @return Node pointer reference to goal node
160+
*/
161+
NodePtr & getGoal();
162+
167163
/**
168164
* @brief Get maximum number of on-approach iterations after within threshold
169165
* @return Reference to Maximum on-approach iterations parameter
@@ -194,18 +190,6 @@ class AStarAlgorithm
194190
*/
195191
unsigned int & getSizeDim3();
196192

197-
/**
198-
* @brief Get the resolution of the coarse search
199-
* @return Size of the goals to expand
200-
*/
201-
unsigned int getCoarseSearchResolution();
202-
203-
/**
204-
* @brief Get the goals manager class
205-
* @return Goal manager class
206-
*/
207-
GoalManagerT getGoalManager();
208-
209193
protected:
210194
/**
211195
* @brief Get pointer to next goal in open set
@@ -226,6 +210,13 @@ class AStarAlgorithm
226210
*/
227211
inline NodePtr addToGraph(const uint64_t & index);
228212

213+
/**
214+
* @brief Check if this node is the goal node
215+
* @param node Node pointer to check if its the goal node
216+
* @return if node is goal
217+
*/
218+
inline bool isGoal(NodePtr & node);
219+
229220
/**
230221
* @brief Get cost of heuristic of node
231222
* @param node Node pointer to get heuristic for
@@ -249,11 +240,6 @@ class AStarAlgorithm
249240
*/
250241
inline void clearGraph();
251242

252-
/**
253-
* @brief Check if node has been visited
254-
* @param current_node Node to check if visited
255-
* @return if node has been visited
256-
*/
257243
inline bool onVisitationCheckNode(const NodePtr & node);
258244

259245
/**
@@ -274,11 +260,12 @@ class AStarAlgorithm
274260
unsigned int _x_size;
275261
unsigned int _y_size;
276262
unsigned int _dim3_size;
277-
unsigned int _coarse_search_resolution;
278263
SearchInfo _search_info;
279264

265+
Coordinates _goal_coordinates;
280266
NodePtr _start;
281-
GoalManagerT _goal_manager;
267+
NodePtr _goal;
268+
282269
Graph _graph;
283270
NodeQueue _queue;
284271

nav2_smac_planner/include/nav2_smac_planner/analytic_expansion.hpp

Lines changed: 7 additions & 66 deletions
Original file line numberDiff line numberDiff line change
@@ -15,10 +15,6 @@
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-
2218
#include <functional>
2319
#include <list>
2420
#include <memory>
@@ -39,10 +35,8 @@ class AnalyticExpansion
3935
{
4036
public:
4137
typedef NodeT * NodePtr;
42-
typedef std::vector<NodePtr> NodeVector;
4338
typedef typename NodeT::Coordinates Coordinates;
4439
typedef std::function<bool (const uint64_t &, NodeT * &)> NodeGetter;
45-
typedef typename NodeT::CoordinateVector CoordinateVector;
4640

4741
/**
4842
* @struct nav2_smac_planner::AnalyticExpansion::AnalyticExpansionNodes
@@ -65,33 +59,7 @@ class AnalyticExpansion
6559
Coordinates proposed_coords;
6660
};
6761

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-
};
62+
typedef std::vector<AnalyticExpansionNode> AnalyticExpansionNodes;
9563

9664
/**
9765
* @brief Constructor for analytic expansion object
@@ -111,22 +79,17 @@ class AnalyticExpansion
11179
/**
11280
* @brief Attempt an analytic path completion
11381
* @param node The node to start the analytic path from
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
82+
* @param goal The goal node to plan to
11783
* @param getter Gets a node at a set of coordinates
11884
* @param iterations Iterations to run over
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
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
12288
*/
12389
NodePtr tryAnalyticExpansion(
12490
const NodePtr & current_node,
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);
91+
const NodePtr & goal_node,
92+
const NodeGetter & getter, int & iterations, int & best_cost);
13093

13194
/**
13295
* @brief Perform an analytic path expansion to the goal
@@ -140,21 +103,6 @@ class AnalyticExpansion
140103
const NodePtr & node, const NodePtr & goal,
141104
const NodeGetter & getter, const ompl::base::StateSpacePtr & state_space);
142105

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-
158106
/**
159107
* @brief Takes final analytic expansion and appends to current expanded node
160108
* @param node The node to start the analytic path from
@@ -166,13 +114,6 @@ class AnalyticExpansion
166114
const NodePtr & node, const NodePtr & goal,
167115
const AnalyticExpansionNodes & expanded_nodes);
168116

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-
176117
/**
177118
* @brief Takes an expanded nodes to clean up, if necessary, of any state
178119
* information that may be polluting it from a prior search iteration

nav2_smac_planner/include/nav2_smac_planner/constants.hpp

Lines changed: 0 additions & 35 deletions
Original file line numberDiff line numberDiff line change
@@ -28,14 +28,6 @@ enum class MotionModel
2828
STATE_LATTICE = 4,
2929
};
3030

31-
enum class GoalHeadingMode
32-
{
33-
UNKNOWN = 0,
34-
DEFAULT = 1,
35-
BIDIRECTIONAL = 2,
36-
ALL_DIRECTION = 3,
37-
};
38-
3931
inline std::string toString(const MotionModel & n)
4032
{
4133
switch (n) {
@@ -67,33 +59,6 @@ inline MotionModel fromString(const std::string & n)
6759
}
6860
}
6961

70-
inline std::string toString(const GoalHeadingMode & n)
71-
{
72-
switch (n) {
73-
case GoalHeadingMode::DEFAULT:
74-
return "DEFAULT";
75-
case GoalHeadingMode::BIDIRECTIONAL:
76-
return "BIDIRECTIONAL";
77-
case GoalHeadingMode::ALL_DIRECTION:
78-
return "ALL_DIRECTION";
79-
default:
80-
return "Unknown";
81-
}
82-
}
83-
84-
inline GoalHeadingMode fromStringToGH(const std::string & n)
85-
{
86-
if (n == "DEFAULT") {
87-
return GoalHeadingMode::DEFAULT;
88-
} else if (n == "BIDIRECTIONAL") {
89-
return GoalHeadingMode::BIDIRECTIONAL;
90-
} else if (n == "ALL_DIRECTION") {
91-
return GoalHeadingMode::ALL_DIRECTION;
92-
} else {
93-
return GoalHeadingMode::UNKNOWN;
94-
}
95-
}
96-
9762
const float UNKNOWN_COST = 255.0;
9863
const float OCCUPIED_COST = 254.0;
9964
const float INSCRIBED_COST = 253.0;

0 commit comments

Comments
 (0)