Skip to content

Commit afb9e7d

Browse files
stevedanomodolorSteveMacenskiNils-ChristianIsekedoisygGuillaume Doisy
authored
Fix/smac planner orientation goals (#5235)
* cherry pick Signed-off-by: Stevedan Omodolor <[email protected]> * cherry pick 6a74ba6 Signed-off-by: Stevedan Omodolor <[email protected]> * cherrpy pick Signed-off-by: Stevedan Omodolor <[email protected]> * include x11 forwarding Signed-off-by: Stevedan Omodolor <[email protected]> * kind of working version Signed-off-by: Stevedan Omodolor <[email protected]> * cleanup Signed-off-by: Stevedan Omodolor <[email protected]> * formatting Signed-off-by: Stevedan Omodolor <[email protected]> * minor format change Signed-off-by: Stevedan Omodolor <[email protected]> * change naming Signed-off-by: Stevedan Omodolor <[email protected]> * minor changes Signed-off-by: Stevedan Omodolor <[email protected]> * working with new changes Signed-off-by: Stevedan Omodolor <[email protected]> * Revert "Fix Ci from key signing (#5220)" (#5237) * Revert "Fix Ci from key signing (#5220)" This reverts the changes to the Dockerfile done in 1345c22. Signed-off-by: Nils-Christian Iseke <[email protected]> * Update Cache Version Signed-off-by: Nils-Christian Iseke <[email protected]> --------- Signed-off-by: Nils-Christian Iseke <[email protected]> Signed-off-by: Stevedan Omodolor <[email protected]> * Revert back Signed-off-by: Stevedan Omodolor <[email protected]> * enable_groot_monitoring_ false (#5246) Signed-off-by: Guillaume Doisy <[email protected]> Co-authored-by: Guillaume Doisy <[email protected]> Signed-off-by: Stevedan Omodolor <[email protected]> * Updating readme table for kilted release (#5249) * updating readme table for kilted release Signed-off-by: Steve Macenski <[email protected]> * Updating table lint Signed-off-by: Steve Macenski <[email protected]> --------- Signed-off-by: Steve Macenski <[email protected]> Signed-off-by: Stevedan Omodolor <[email protected]> * Add min_distance_to_obstacle parameter to RPP (#4543) * min_distance_to_obstacle Signed-off-by: Guillaume Doisy <[email protected]> * suggestion to time base and combine Signed-off-by: Guillaume Doisy <[email protected]> * typo Signed-off-by: Guillaume Doisy <[email protected]> * use min_approach_linear_velocity Signed-off-by: Guillaume Doisy <[email protected]> --------- Signed-off-by: Guillaume Doisy <[email protected]> Co-authored-by: Guillaume Doisy <[email protected]> Signed-off-by: Stevedan Omodolor <[email protected]> * Fixing builds for message filters API change while retaining Jazzy, Kilted, and Rolling support (#5251) * Update amcl_node.hpp Signed-off-by: Steve Macenski <[email protected]> * Update amcl_node.cpp Signed-off-by: Steve Macenski <[email protected]> * Working for Kilted, Jazzy Signed-off-by: Steve Macenski <[email protected]> * Update amcl_node.cpp Signed-off-by: Steve Macenski <[email protected]> * Update amcl_node.cpp Signed-off-by: Steve Macenski <[email protected]> * Update amcl_node.cpp Signed-off-by: Steve Macenski <[email protected]> --------- Signed-off-by: Steve Macenski <[email protected]> Signed-off-by: Stevedan Omodolor <[email protected]> * Change max_cost default to 254 (#5256) Signed-off-by: Tony Najjar <[email protected]> Signed-off-by: Stevedan Omodolor <[email protected]> * linter Signed-off-by: Stevedan Omodolor <[email protected]> * remove const Signed-off-by: Stevedan Omodolor <[email protected]> * pass const pointer by value Signed-off-by: Stevedan Omodolor <[email protected]> * pass const pointer by value Signed-off-by: Stevedan Omodolor <[email protected]> * remove unused param Signed-off-by: Stevedan Omodolor <[email protected]> --------- Signed-off-by: Stevedan Omodolor <[email protected]> Signed-off-by: Nils-Christian Iseke <[email protected]> Signed-off-by: Guillaume Doisy <[email protected]> Signed-off-by: Steve Macenski <[email protected]> Signed-off-by: Tony Najjar <[email protected]> Co-authored-by: Steve Macenski <[email protected]> Co-authored-by: Nils-Christian Iseke <[email protected]> Co-authored-by: Guillaume Doisy <[email protected]> Co-authored-by: Guillaume Doisy <[email protected]> Co-authored-by: Tony Najjar <[email protected]>
1 parent 33e78d7 commit afb9e7d

25 files changed

+5329
-170
lines changed

.devcontainer/devcontainer.json

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,8 @@
1414
// "--pid=host", // DDS discovery with host, without --network=host
1515
// "--privileged", // device access to host peripherals, e.g. USB
1616
// "--security-opt=seccomp=unconfined", // enable debugging, e.g. gdb
17+
// "--volume=/tmp/.X11-unix:/tmp/.X11-unix", // X11 socket for GUI applications
18+
// "--gpus=all" // access to all GPUs, e.g. for GPU-accelerated applications
1719
],
1820
"workspaceFolder": "/opt/overlay_ws/src/navigation2",
1921
"workspaceMount": "source=${localWorkspaceFolder},target=${containerWorkspaceFolder},type=bind",
@@ -23,6 +25,8 @@
2325
"remoteEnv": {
2426
"OVERLAY_MIXINS": "release ccache lld",
2527
"CCACHE_DIR": "/tmp/.ccache"
28+
// "QT_X11_NO_MITSHM": "1", // disable MIT-SHM for X11 forwarding
29+
// "DISPLAY": "${localEnv:DISPLAY}", // X11 forwarding
2630
},
2731
"mounts": [
2832
{

nav2_smac_planner/include/nav2_smac_planner/a_star.hpp

Lines changed: 29 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,7 @@
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"
3536
#include "nav2_smac_planner/types.hpp"
3637
#include "nav2_smac_planner/constants.hpp"
3738

@@ -54,6 +55,8 @@ class AStarAlgorithm
5455
typedef typename NodeT::CoordinateVector CoordinateVector;
5556
typedef typename NodeVector::iterator NeighborIterator;
5657
typedef std::function<bool (const uint64_t &, NodeT * &)> NodeGetter;
58+
typedef GoalManager<NodeT> GoalManagerT;
59+
5760

5861
/**
5962
* @struct nav2_smac_planner::NodeComparator
@@ -90,6 +93,8 @@ class AStarAlgorithm
9093
* or planning time exceeded
9194
* @param max_planning_time Maximum time (in seconds) to wait for a plan, createPath returns
9295
* false after this timeout
96+
* @param lookup_table_size Size of the lookup table to store heuristic values
97+
* @param dim_3_size Number of quantization bins
9398
*/
9499
void initialize(
95100
const bool & allow_unknown,
@@ -125,11 +130,15 @@ class AStarAlgorithm
125130
* @param mx The node X index of the goal
126131
* @param my The node Y index of the goal
127132
* @param dim_3 The node dim_3 index of the goal
133+
* @param goal_heading_mode The goal heading mode to use
134+
* @param coarse_search_resolution The resolution to search for goal heading
128135
*/
129136
void setGoal(
130137
const float & mx,
131138
const float & my,
132-
const unsigned int & dim_3);
139+
const unsigned int & dim_3,
140+
const GoalHeadingMode & goal_heading_mode = GoalHeadingMode::DEFAULT,
141+
const int & coarse_search_resolution = 1);
133142

134143
/**
135144
* @brief Set the starting pose for planning, as a node index
@@ -154,12 +163,6 @@ class AStarAlgorithm
154163
*/
155164
NodePtr & getStart();
156165

157-
/**
158-
* @brief Get pointer reference to goal node
159-
* @return Node pointer reference to goal node
160-
*/
161-
NodePtr & getGoal();
162-
163166
/**
164167
* @brief Get maximum number of on-approach iterations after within threshold
165168
* @return Reference to Maximum on-approach iterations parameter
@@ -190,6 +193,18 @@ class AStarAlgorithm
190193
*/
191194
unsigned int & getSizeDim3();
192195

196+
/**
197+
* @brief Get the resolution of the coarse search
198+
* @return Size of the goals to expand
199+
*/
200+
unsigned int getCoarseSearchResolution();
201+
202+
/**
203+
* @brief Get the goals manager class
204+
* @return Goal manager class
205+
*/
206+
GoalManagerT getGoalManager();
207+
193208
protected:
194209
/**
195210
* @brief Get pointer to next goal in open set
@@ -210,13 +225,6 @@ class AStarAlgorithm
210225
*/
211226
inline NodePtr addToGraph(const uint64_t & index);
212227

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-
220228
/**
221229
* @brief Get cost of heuristic of node
222230
* @param node Node pointer to get heuristic for
@@ -240,6 +248,11 @@ class AStarAlgorithm
240248
*/
241249
inline void clearGraph();
242250

251+
/**
252+
* @brief Check if node has been visited
253+
* @param current_node Node to check if visited
254+
* @return if node has been visited
255+
*/
243256
inline bool onVisitationCheckNode(const NodePtr & node);
244257

245258
/**
@@ -260,12 +273,11 @@ class AStarAlgorithm
260273
unsigned int _x_size;
261274
unsigned int _y_size;
262275
unsigned int _dim3_size;
276+
unsigned int _coarse_search_resolution;
263277
SearchInfo _search_info;
264278

265-
Coordinates _goal_coordinates;
266279
NodePtr _start;
267-
NodePtr _goal;
268-
280+
GoalManagerT _goal_manager;
269281
Graph _graph;
270282
NodeQueue _queue;
271283

nav2_smac_planner/include/nav2_smac_planner/analytic_expansion.hpp

Lines changed: 66 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,10 @@
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
{
3640
public:
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

nav2_smac_planner/include/nav2_smac_planner/constants.hpp

Lines changed: 35 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,14 @@ 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+
3139
inline std::string toString(const MotionModel & n)
3240
{
3341
switch (n) {
@@ -59,6 +67,33 @@ inline MotionModel fromString(const std::string & n)
5967
}
6068
}
6169

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+
6297
const float UNKNOWN_COST = 255.0;
6398
const float OCCUPIED_COST = 254.0;
6499
const float INSCRIBED_COST = 253.0;

0 commit comments

Comments
 (0)