Skip to content

Commit 3c081db

Browse files
authored
Add custom window size and poly order for SG filter (#5489)
* Add custom window size and poly order in SG filter Signed-off-by: mini-1235 <[email protected]> * Fix linting and benchmark tool Signed-off-by: mini-1235 <[email protected]> * Cmakelist Signed-off-by: mini-1235 <[email protected]> * Adding comments Signed-off-by: mini-1235 <[email protected]> * Add blog Signed-off-by: mini-1235 <[email protected]> --------- Signed-off-by: mini-1235 <[email protected]>
1 parent 2b8cc4d commit 3c081db

File tree

5 files changed

+72
-46
lines changed

5 files changed

+72
-46
lines changed

nav2_smoother/CMakeLists.txt

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@ find_package(rclcpp_lifecycle REQUIRED)
1616
find_package(tf2 REQUIRED)
1717
find_package(tf2_ros REQUIRED)
1818
find_package(nav2_ros_common REQUIRED)
19+
find_package(Eigen3 REQUIRED)
1920

2021
nav2_package()
2122

@@ -42,6 +43,7 @@ target_link_libraries(${library_name} PUBLIC
4243
rclcpp_lifecycle::rclcpp_lifecycle
4344
tf2_ros::tf2_ros
4445
nav2_ros_common::nav2_ros_common
46+
Eigen3::Eigen
4547
)
4648
target_link_libraries(${library_name} PRIVATE
4749
rclcpp_components::component
@@ -157,6 +159,7 @@ ament_export_dependencies(
157159
rclcpp_lifecycle
158160
tf2
159161
tf2_ros
162+
Eigen3
160163
)
161164
ament_export_targets(${library_name})
162165
ament_package()

nav2_smoother/include/nav2_smoother/savitzky_golay_smoother.hpp

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#ifndef NAV2_SMOOTHER__SAVITZKY_GOLAY_SMOOTHER_HPP_
1616
#define NAV2_SMOOTHER__SAVITZKY_GOLAY_SMOOTHER_HPP_
1717

18+
#include <Eigen/Dense>
1819
#include <cmath>
1920
#include <vector>
2021
#include <string>
@@ -85,6 +86,11 @@ class SavitzkyGolaySmoother : public nav2_core::Smoother
8586
nav_msgs::msg::Path & path,
8687
const rclcpp::Duration & max_time) override;
8788

89+
/**
90+
* @brief Method to calculate SavitzkyGolay Coefficients
91+
*/
92+
void calculateCoefficients();
93+
8894
protected:
8995
/**
9096
* @brief Smoother method - does the smoothing on a segment
@@ -99,7 +105,8 @@ class SavitzkyGolaySmoother : public nav2_core::Smoother
99105
bool & reversing_segment);
100106

101107
bool do_refinement_, enforce_path_inversion_;
102-
int refinement_num_;
108+
int refinement_num_, window_size_, half_window_size_, poly_order_;
109+
Eigen::VectorXd sg_coeffs_;
103110
rclcpp::Logger logger_{rclcpp::get_logger("SGSmoother")};
104111
};
105112

nav2_smoother/package.xml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,8 @@
2424
<depend>tf2</depend>
2525
<depend>tf2_ros</depend>
2626
<depend>nav2_ros_common</depend>
27+
<depend>eigen3_cmake_module</depend>
28+
<depend>eigen</depend>
2729

2830
<test_depend>ament_cmake_gtest</test_depend>
2931
<test_depend>ament_index_cpp</test_depend>

nav2_smoother/src/savitzky_golay_smoother.cpp

Lines changed: 50 additions & 45 deletions
Original file line numberDiff line numberDiff line change
@@ -40,9 +40,39 @@ void SavitzkyGolaySmoother::configure(
4040
node, name + ".refinement_num", rclcpp::ParameterValue(2));
4141
declare_parameter_if_not_declared(
4242
node, name + ".enforce_path_inversion", rclcpp::ParameterValue(true));
43+
declare_parameter_if_not_declared(
44+
node, name + ".window_size", rclcpp::ParameterValue(7));
45+
declare_parameter_if_not_declared(
46+
node, name + ".poly_order", rclcpp::ParameterValue(3));
4347
node->get_parameter(name + ".do_refinement", do_refinement_);
4448
node->get_parameter(name + ".refinement_num", refinement_num_);
4549
node->get_parameter(name + ".enforce_path_inversion", enforce_path_inversion_);
50+
node->get_parameter(name + ".window_size", window_size_);
51+
node->get_parameter(name + ".poly_order", poly_order_);
52+
if (window_size_ % 2 == 0 || window_size_ <= 2) {
53+
throw nav2_core::SmootherException(
54+
"Savitzky-Golay Smoother requires an odd window size of 3 or greater");
55+
}
56+
half_window_size_ = (window_size_ - 1) / 2;
57+
calculateCoefficients();
58+
}
59+
60+
// For more details on calculating Savitzky–Golay filter coefficients,
61+
// see: https://www.colmryan.org/posts/savitsky_golay/
62+
void SavitzkyGolaySmoother::calculateCoefficients()
63+
{
64+
// We construct the Vandermonde matrix here
65+
Eigen::VectorXd v = Eigen::VectorXd::LinSpaced(window_size_, -half_window_size_,
66+
half_window_size_);
67+
Eigen::MatrixXd x = Eigen::MatrixXd::Ones(window_size_, poly_order_ + 1);
68+
for(int i = 1; i <= poly_order_; i++) {
69+
x.col(i) = (x.col(i - 1).array() * v.array()).matrix();
70+
}
71+
// Compute the pseudoinverse of X, (X^T * X)^-1 * X^T
72+
Eigen::MatrixXd coeff_mat = (x.transpose() * x).inverse() * x.transpose();
73+
74+
// Extract the smoothing coefficients
75+
sg_coeffs_ = coeff_mat.row(0).transpose();
4676
}
4777

4878
bool SavitzkyGolaySmoother::smooth(
@@ -62,8 +92,10 @@ bool SavitzkyGolaySmoother::smooth(
6292
path_segments = findDirectionalPathSegments(path);
6393
}
6494

95+
// Minimum point size to smooth is SG filter size + start + end
96+
unsigned int minimum_points = window_size_ + 2;
6597
for (unsigned int i = 0; i != path_segments.size(); i++) {
66-
if (path_segments[i].end - path_segments[i].start > 9) {
98+
if (path_segments[i].end - path_segments[i].start > minimum_points) {
6799
// Populate path segment
68100
curr_path_segment.poses.clear();
69101
std::copy(
@@ -100,68 +132,41 @@ bool SavitzkyGolaySmoother::smoothImpl(
100132
nav_msgs::msg::Path & path,
101133
bool & reversing_segment)
102134
{
103-
// Must be at least 10 in length to enter function
104135
const unsigned int & path_size = path.poses.size();
105136

106-
// 7-point SG filter
107-
const std::array<double, 7> filter = {
108-
-2.0 / 21.0,
109-
3.0 / 21.0,
110-
6.0 / 21.0,
111-
7.0 / 21.0,
112-
6.0 / 21.0,
113-
3.0 / 21.0,
114-
-2.0 / 21.0};
115-
116-
auto applyFilter = [&](const std::vector<geometry_msgs::msg::Point> & data)
117-
-> geometry_msgs::msg::Point
118-
{
119-
geometry_msgs::msg::Point val;
120-
for (unsigned int i = 0; i != filter.size(); i++) {
121-
val.x += filter[i] * data[i].x;
122-
val.y += filter[i] * data[i].y;
123-
}
124-
return val;
137+
// Convert PoseStamped to Eigen
138+
auto toEigenVec = [](const geometry_msgs::msg::PoseStamped & pose) -> Eigen::Vector2d {
139+
return {pose.pose.position.x, pose.pose.position.y};
125140
};
126141

127142
auto applyFilterOverAxes =
128143
[&](std::vector<geometry_msgs::msg::PoseStamped> & plan_pts,
129-
const std::vector<geometry_msgs::msg::PoseStamped> & init_plan_pts) -> void
144+
const std::vector<Eigen::Vector2d> & init_plan_pts) -> void
130145
{
131-
auto pt_m3 = init_plan_pts[0].pose.position;
132-
auto pt_m2 = init_plan_pts[0].pose.position;
133-
auto pt_m1 = init_plan_pts[0].pose.position;
134-
auto pt = init_plan_pts[1].pose.position;
135-
auto pt_p1 = init_plan_pts[2].pose.position;
136-
auto pt_p2 = init_plan_pts[3].pose.position;
137-
auto pt_p3 = init_plan_pts[4].pose.position;
138-
139146
// First point is fixed
140147
for (unsigned int idx = 1; idx != path_size - 1; idx++) {
141-
plan_pts[idx].pose.position = applyFilter({pt_m3, pt_m2, pt_m1, pt, pt_p1, pt_p2, pt_p3});
142-
pt_m3 = pt_m2;
143-
pt_m2 = pt_m1;
144-
pt_m1 = pt;
145-
pt = pt_p1;
146-
pt_p1 = pt_p2;
147-
pt_p2 = pt_p3;
148-
149-
if (idx + 4 < path_size - 1) {
150-
pt_p3 = init_plan_pts[idx + 4].pose.position;
151-
} else {
152-
// Return the last point
153-
pt_p3 = init_plan_pts[path_size - 1].pose.position;
148+
Eigen::Vector2d accum(0.0, 0.0);
149+
150+
for(int j = -half_window_size_; j <= half_window_size_; j++) {
151+
int path_idx = std::clamp<int>(idx + j, 0, path_size - 1);
152+
accum += sg_coeffs_(j + half_window_size_) * init_plan_pts[path_idx];
154153
}
154+
plan_pts[idx].pose.position.x = accum.x();
155+
plan_pts[idx].pose.position.y = accum.y();
155156
}
156157
};
157158

158-
const auto initial_path_poses = path.poses;
159+
std::vector<Eigen::Vector2d> initial_path_poses(path.poses.size());
160+
std::transform(path.poses.begin(), path.poses.end(),
161+
initial_path_poses.begin(), toEigenVec);
159162
applyFilterOverAxes(path.poses, initial_path_poses);
160163

161164
// Let's do additional refinement, it shouldn't take more than a couple milliseconds
162165
if (do_refinement_) {
163166
for (int i = 0; i < refinement_num_; i++) {
164-
const auto reined_initial_path_poses = path.poses;
167+
std::vector<Eigen::Vector2d> reined_initial_path_poses(path.poses.size());
168+
std::transform(path.poses.begin(), path.poses.end(),
169+
reined_initial_path_poses.begin(), toEigenVec);
165170
applyFilterOverAxes(path.poses, reined_initial_path_poses);
166171
}
167172
}

tools/smoother_benchmarking/smoother_benchmark_bringup.py

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
from launch.actions import ExecuteProcess, IncludeLaunchDescription
2020
from launch.launch_description_sources import PythonLaunchDescriptionSource
2121
from launch_ros.actions import Node
22+
from nav2_common.launch import RewrittenYaml
2223

2324

2425
def generate_launch_description() -> LaunchDescription:
@@ -30,6 +31,14 @@ def generate_launch_description() -> LaunchDescription:
3031
)
3132
map_file = os.path.join(benchmark_dir, 'maps', 'smoothers_world.yaml')
3233
lifecycle_nodes = ['map_server', 'planner_server', 'smoother_server']
34+
config = RewrittenYaml(
35+
source_file=config, root_key='', param_rewrites={},
36+
value_rewrites={
37+
'KEEPOUT_ZONE_ENABLED': 'False',
38+
'SPEED_ZONE_ENABLED': 'False',
39+
},
40+
convert_types=True
41+
)
3342

3443
static_transform_one = Node(
3544
package='tf2_ros',

0 commit comments

Comments
 (0)