Skip to content

Commit 16e63a4

Browse files
Refactor common functions in smoother and planner (#5537)
* Refactor common functions in planner and smoother Signed-off-by: mini-1235 <[email protected]> * Add unit tests for smoother utils Signed-off-by: Maurice <[email protected]> * Update cmakelist and linting Signed-off-by: mini-1235 <[email protected]> * Update nav2_util/include/nav2_util/smoother_utils.hpp Co-authored-by: Steve Macenski <[email protected]> Signed-off-by: mini-1235 <[email protected]> * Update nav2_util/include/nav2_util/smoother_utils.hpp Co-authored-by: Steve Macenski <[email protected]> Signed-off-by: mini-1235 <[email protected]> * Update unit tests Signed-off-by: Maurice <[email protected]> --------- Signed-off-by: mini-1235 <[email protected]> Signed-off-by: Maurice <[email protected]> Co-authored-by: Steve Macenski <[email protected]>
1 parent c95673e commit 16e63a4

File tree

14 files changed

+159
-165
lines changed

14 files changed

+159
-165
lines changed

nav2_smac_planner/include/nav2_smac_planner/smoother.hpp

Lines changed: 0 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -27,16 +27,6 @@
2727
namespace nav2_smac_planner
2828
{
2929

30-
/**
31-
* @class nav2_smac_planner::PathSegment
32-
* @brief A segment of a path in start/end indices
33-
*/
34-
struct PathSegment
35-
{
36-
unsigned int start;
37-
unsigned int end;
38-
};
39-
4030
/**
4131
* @struct nav2_smac_planner::BoundaryPoints
4232
* @brief Set of boundary condition points from expansion
@@ -144,14 +134,6 @@ class Smoother
144134
geometry_msgs::msg::PoseStamped & msg, const unsigned int dim,
145135
const double & value);
146136

147-
/**
148-
* @brief Finds the starting and end indices of path segments where
149-
* the robot is traveling in the same direction (e.g. forward vs reverse)
150-
* @param path Path in which to look for cusps
151-
* @return Set of index pairs for each segment of the path in a given direction
152-
*/
153-
std::vector<PathSegment> findDirectionalPathSegments(const nav_msgs::msg::Path & path);
154-
155137
/**
156138
* @brief Enforced minimum curvature boundary conditions on plan output
157139
* the robot is traveling in the same direction (e.g. forward vs reverse)
@@ -214,15 +196,6 @@ class Smoother
214196
template<typename IteratorT>
215197
BoundaryExpansions generateBoundaryExpansionPoints(IteratorT start, IteratorT end);
216198

217-
/**
218-
* @brief For a given path, update the path point orientations based on smoothing
219-
* @param path Path to approximate the path orientation in
220-
* @param reversing_segment Return if this is a reversing segment
221-
*/
222-
inline void updateApproximatePathOrientations(
223-
nav_msgs::msg::Path & path,
224-
bool & reversing_segment);
225-
226199
double min_turning_rad_, tolerance_, data_w_, smooth_w_;
227200
int max_its_, refinement_ctr_, refinement_num_;
228201
bool is_holonomic_, do_refinement_;

nav2_smac_planner/src/smoother.cpp

Lines changed: 8 additions & 91 deletions
Original file line numberDiff line numberDiff line change
@@ -24,11 +24,13 @@
2424
#include "tf2/utils.hpp"
2525

2626
#include "nav2_smac_planner/smoother.hpp"
27+
#include "nav2_util/smoother_utils.hpp"
2728

2829
namespace nav2_smac_planner
2930
{
3031
using namespace nav2_util::geometry_utils; // NOLINT
3132
using namespace std::chrono; // NOLINT
33+
using nav2_util::PathSegment;
3234

3335
Smoother::Smoother(const SmootherParams & params)
3436
{
@@ -62,7 +64,8 @@ bool Smoother::smooth(
6264
bool success = true, reversing_segment;
6365
nav_msgs::msg::Path curr_path_segment;
6466
curr_path_segment.header = path.header;
65-
std::vector<PathSegment> path_segments = findDirectionalPathSegments(path);
67+
std::vector<PathSegment> path_segments = nav2_util::findDirectionalPathSegments(path,
68+
is_holonomic_);
6669

6770
for (unsigned int i = 0; i != path_segments.size(); i++) {
6871
if (path_segments[i].end - path_segments[i].start > 10) {
@@ -130,7 +133,7 @@ bool Smoother::smoothImpl(
130133
rclcpp::get_logger("SmacPlannerSmoother"),
131134
"Number of iterations has exceeded limit of %i.", max_its_);
132135
path = last_path;
133-
updateApproximatePathOrientations(path, reversing_segment);
136+
nav2_util::updateApproximatePathOrientations(path, reversing_segment, is_holonomic_);
134137
return false;
135138
}
136139

@@ -142,7 +145,7 @@ bool Smoother::smoothImpl(
142145
rclcpp::get_logger("SmacPlannerSmoother"),
143146
"Smoothing time exceeded allowed duration of %0.2f.", max_time);
144147
path = last_path;
145-
updateApproximatePathOrientations(path, reversing_segment);
148+
nav2_util::updateApproximatePathOrientations(path, reversing_segment, is_holonomic_);
146149
return false;
147150
}
148151

@@ -176,7 +179,7 @@ bool Smoother::smoothImpl(
176179
"Smoothing process resulted in an infeasible collision. "
177180
"Returning the last path before the infeasibility was introduced.");
178181
path = last_path;
179-
updateApproximatePathOrientations(path, reversing_segment);
182+
nav2_util::updateApproximatePathOrientations(path, reversing_segment, is_holonomic_);
180183
return false;
181184
}
182185
}
@@ -191,7 +194,7 @@ bool Smoother::smoothImpl(
191194
smoothImpl(new_path, reversing_segment, costmap, max_time);
192195
}
193196

194-
updateApproximatePathOrientations(new_path, reversing_segment);
197+
nav2_util::updateApproximatePathOrientations(new_path, reversing_segment, is_holonomic_);
195198
path = new_path;
196199
return true;
197200
}
@@ -221,92 +224,6 @@ void Smoother::setFieldByDim(
221224
}
222225
}
223226

224-
std::vector<PathSegment> Smoother::findDirectionalPathSegments(const nav_msgs::msg::Path & path)
225-
{
226-
std::vector<PathSegment> segments;
227-
PathSegment curr_segment;
228-
curr_segment.start = 0;
229-
230-
// If holonomic, no directional changes and
231-
// may have abrupt angular changes from naive grid search
232-
if (is_holonomic_) {
233-
curr_segment.end = path.poses.size() - 1;
234-
segments.push_back(curr_segment);
235-
return segments;
236-
}
237-
238-
// Iterating through the path to determine the position of the cusp
239-
for (unsigned int idx = 1; idx < path.poses.size() - 1; ++idx) {
240-
// We have two vectors for the dot product OA and AB. Determining the vectors.
241-
double oa_x = path.poses[idx].pose.position.x -
242-
path.poses[idx - 1].pose.position.x;
243-
double oa_y = path.poses[idx].pose.position.y -
244-
path.poses[idx - 1].pose.position.y;
245-
double ab_x = path.poses[idx + 1].pose.position.x -
246-
path.poses[idx].pose.position.x;
247-
double ab_y = path.poses[idx + 1].pose.position.y -
248-
path.poses[idx].pose.position.y;
249-
250-
// Checking for the existence of cusp, in the path, using the dot product.
251-
double dot_product = (oa_x * ab_x) + (oa_y * ab_y);
252-
if (dot_product < 0.0) {
253-
curr_segment.end = idx;
254-
segments.push_back(curr_segment);
255-
curr_segment.start = idx;
256-
}
257-
258-
// Checking for the existence of a differential rotation in place.
259-
double cur_theta = tf2::getYaw(path.poses[idx].pose.orientation);
260-
double next_theta = tf2::getYaw(path.poses[idx + 1].pose.orientation);
261-
double dtheta = angles::shortest_angular_distance(cur_theta, next_theta);
262-
if (fabs(ab_x) < 1e-4 && fabs(ab_y) < 1e-4 && fabs(dtheta) > 1e-4) {
263-
curr_segment.end = idx;
264-
segments.push_back(curr_segment);
265-
curr_segment.start = idx;
266-
}
267-
}
268-
269-
curr_segment.end = path.poses.size() - 1;
270-
segments.push_back(curr_segment);
271-
return segments;
272-
}
273-
274-
void Smoother::updateApproximatePathOrientations(
275-
nav_msgs::msg::Path & path,
276-
bool & reversing_segment)
277-
{
278-
double dx, dy, theta, pt_yaw;
279-
reversing_segment = false;
280-
281-
// Find if this path segment is in reverse
282-
dx = path.poses[2].pose.position.x - path.poses[1].pose.position.x;
283-
dy = path.poses[2].pose.position.y - path.poses[1].pose.position.y;
284-
theta = atan2(dy, dx);
285-
pt_yaw = tf2::getYaw(path.poses[1].pose.orientation);
286-
if (!is_holonomic_ && fabs(angles::shortest_angular_distance(pt_yaw, theta)) > M_PI_2) {
287-
reversing_segment = true;
288-
}
289-
290-
// Find the angle relative the path position vectors
291-
for (unsigned int i = 0; i != path.poses.size() - 1; i++) {
292-
dx = path.poses[i + 1].pose.position.x - path.poses[i].pose.position.x;
293-
dy = path.poses[i + 1].pose.position.y - path.poses[i].pose.position.y;
294-
theta = atan2(dy, dx);
295-
296-
// If points are overlapping, pass
297-
if (fabs(dx) < 1e-4 && fabs(dy) < 1e-4) {
298-
continue;
299-
}
300-
301-
// Flip the angle if this path segment is in reverse
302-
if (reversing_segment) {
303-
theta += M_PI; // orientationAroundZAxis will normalize
304-
}
305-
306-
path.poses[i].pose.orientation = orientationAroundZAxis(theta);
307-
}
308-
}
309-
310227
unsigned int Smoother::findShortestBoundaryExpansionIdx(
311228
const BoundaryExpansions & boundary_expansions)
312229
{

nav2_smac_planner/test/test_smoother.cpp

Lines changed: 0 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -37,11 +37,6 @@ class SmootherWrapper : public nav2_smac_planner::Smoother
3737
explicit SmootherWrapper(const SmootherParams & params)
3838
: nav2_smac_planner::Smoother(params)
3939
{}
40-
41-
std::vector<PathSegment> findDirectionalPathSegmentsWrapper(nav_msgs::msg::Path path)
42-
{
43-
return findDirectionalPathSegments(path);
44-
}
4540
};
4641

4742
TEST(SmootherTest, test_full_smoother)
@@ -133,10 +128,6 @@ TEST(SmootherTest, test_full_smoother)
133128
y_m = path[i].y;
134129
}
135130

136-
// Check that we accurately detect that this path has a reversing segment
137-
auto path_segs = smoother->findDirectionalPathSegmentsWrapper(plan);
138-
EXPECT_TRUE(path_segs.size() == 2u || path_segs.size() == 3u);
139-
140131
// Test smoother, should succeed with same number of points
141132
// and shorter overall length, while still being collision free.
142133
auto path_size_in = plan.poses.size();

nav2_smoother/include/nav2_smoother/savitzky_golay_smoother.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@
2525
#include <utility>
2626

2727
#include "nav2_core/smoother.hpp"
28-
#include "nav2_smoother/smoother_utils.hpp"
28+
#include "nav2_util/smoother_utils.hpp"
2929
#include "nav2_costmap_2d/costmap_2d.hpp"
3030
#include "nav2_costmap_2d/cost_values.hpp"
3131
#include "nav2_util/geometry_utils.hpp"

nav2_smoother/include/nav2_smoother/simple_smoother.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@
2424
#include <utility>
2525

2626
#include "nav2_core/smoother.hpp"
27-
#include "nav2_smoother/smoother_utils.hpp"
27+
#include "nav2_util/smoother_utils.hpp"
2828
#include "nav2_costmap_2d/costmap_2d.hpp"
2929
#include "nav2_costmap_2d/cost_values.hpp"
3030
#include "nav2_util/geometry_utils.hpp"

nav2_smoother/src/savitzky_golay_smoother.cpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -19,11 +19,10 @@
1919

2020
namespace nav2_smoother
2121
{
22-
23-
using namespace smoother_utils; // NOLINT
2422
using namespace nav2_util::geometry_utils; // NOLINT
2523
using namespace std::chrono; // NOLINT
2624
using nav2::declare_parameter_if_not_declared;
25+
using nav2_util::PathSegment;
2726

2827
void SavitzkyGolaySmoother::configure(
2928
const nav2::LifecycleNode::WeakPtr & parent,
@@ -89,7 +88,7 @@ bool SavitzkyGolaySmoother::smooth(
8988
std::vector<PathSegment> path_segments{
9089
PathSegment{0u, static_cast<unsigned int>(path.poses.size() - 1)}};
9190
if (enforce_path_inversion_) {
92-
path_segments = findDirectionalPathSegments(path);
91+
path_segments = nav2_util::findDirectionalPathSegments(path);
9392
}
9493

9594
// Minimum point size to smooth is SG filter size + start + end
@@ -171,7 +170,7 @@ bool SavitzkyGolaySmoother::smoothImpl(
171170
}
172171
}
173172

174-
updateApproximatePathOrientations(path, reversing_segment);
173+
nav2_util::updateApproximatePathOrientations(path, reversing_segment);
175174
return true;
176175
}
177176

nav2_smoother/src/simple_smoother.cpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -19,10 +19,10 @@
1919

2020
namespace nav2_smoother
2121
{
22-
using namespace smoother_utils; // NOLINT
2322
using namespace nav2_util::geometry_utils; // NOLINT
2423
using namespace std::chrono; // NOLINT
2524
using nav2::declare_parameter_if_not_declared;
25+
using nav2_util::PathSegment;
2626

2727
void SimpleSmoother::configure(
2828
const nav2::LifecycleNode::WeakPtr & parent,
@@ -72,10 +72,10 @@ bool SimpleSmoother::smooth(
7272
nav_msgs::msg::Path curr_path_segment;
7373
curr_path_segment.header = path.header;
7474

75-
std::vector<PathSegment> path_segments{PathSegment{
75+
std::vector<nav2_util::PathSegment> path_segments{PathSegment{
7676
0u, static_cast<unsigned int>(path.poses.size() - 1)}};
7777
if (enforce_path_inversion_) {
78-
path_segments = findDirectionalPathSegments(path);
78+
path_segments = nav2_util::findDirectionalPathSegments(path);
7979
}
8080

8181
std::lock_guard<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));
@@ -137,7 +137,7 @@ void SimpleSmoother::smoothImpl(
137137
logger_,
138138
"Number of iterations has exceeded limit of %i.", max_its_);
139139
path = last_path;
140-
updateApproximatePathOrientations(path, reversing_segment);
140+
nav2_util::updateApproximatePathOrientations(path, reversing_segment);
141141
return;
142142
}
143143

@@ -149,7 +149,7 @@ void SimpleSmoother::smoothImpl(
149149
logger_,
150150
"Smoothing time exceeded allowed duration of %0.2f.", max_time);
151151
path = last_path;
152-
updateApproximatePathOrientations(path, reversing_segment);
152+
nav2_util::updateApproximatePathOrientations(path, reversing_segment);
153153
throw nav2_core::SmootherTimedOut("Smoothing time exceed allowed duration");
154154
}
155155

@@ -183,7 +183,7 @@ void SimpleSmoother::smoothImpl(
183183
"Smoothing process resulted in an infeasible collision. "
184184
"Returning the last path before the infeasibility was introduced.");
185185
path = last_path;
186-
updateApproximatePathOrientations(path, reversing_segment);
186+
nav2_util::updateApproximatePathOrientations(path, reversing_segment);
187187
return;
188188
}
189189
}
@@ -198,7 +198,7 @@ void SimpleSmoother::smoothImpl(
198198
smoothImpl(new_path, reversing_segment, costmap, max_time);
199199
}
200200

201-
updateApproximatePathOrientations(new_path, reversing_segment);
201+
nav2_util::updateApproximatePathOrientations(new_path, reversing_segment);
202202
path = new_path;
203203
}
204204

nav2_smoother/test/test_savitzky_golay_smoother.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,6 @@
3030
#include "nav2_smoother/savitzky_golay_smoother.hpp"
3131
#include "ament_index_cpp/get_package_share_directory.hpp"
3232

33-
using namespace smoother_utils; // NOLINT
3433
using namespace nav2_smoother; // NOLINT
3534
using namespace std::chrono_literals; // NOLINT
3635

nav2_smoother/test/test_simple_smoother.cpp

Lines changed: 0 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,6 @@
2424
#include "nav2_smoother/simple_smoother.hpp"
2525
#include "nav2_core/smoother_exceptions.hpp"
2626

27-
using namespace smoother_utils; // NOLINT
2827
using namespace nav2_smoother; // NOLINT
2928
using namespace std::chrono_literals; // NOLINT
3029

@@ -36,11 +35,6 @@ class SmootherWrapper : public nav2_smoother::SimpleSmoother
3635
{
3736
}
3837

39-
std::vector<PathSegment> findDirectionalPathSegmentsWrapper(nav_msgs::msg::Path path)
40-
{
41-
return findDirectionalPathSegments(path);
42-
}
43-
4438
void setMaxItsToInvalid()
4539
{
4640
max_its_ = 0;

nav2_util/CMakeLists.txt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@ find_package(tf2_geometry_msgs REQUIRED)
2121
find_package(tf2_msgs REQUIRED)
2222
find_package(tf2_ros REQUIRED)
2323
find_package(pluginlib REQUIRED)
24+
find_package(angles REQUIRED)
2425

2526
nav2_package()
2627

@@ -61,6 +62,7 @@ ament_export_dependencies(
6162
tf2_ros
6263
pluginlib
6364
nav2_ros_common
65+
angles
6466
)
6567
ament_export_targets(${library_name})
6668

0 commit comments

Comments
 (0)