@@ -40,9 +40,39 @@ void SavitzkyGolaySmoother::configure(
40
40
node, name + " .refinement_num" , rclcpp::ParameterValue (2 ));
41
41
declare_parameter_if_not_declared (
42
42
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 ));
43
47
node->get_parameter (name + " .do_refinement" , do_refinement_);
44
48
node->get_parameter (name + " .refinement_num" , refinement_num_);
45
49
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 ();
46
76
}
47
77
48
78
bool SavitzkyGolaySmoother::smooth (
@@ -62,8 +92,10 @@ bool SavitzkyGolaySmoother::smooth(
62
92
path_segments = findDirectionalPathSegments (path);
63
93
}
64
94
95
+ // Minimum point size to smooth is SG filter size + start + end
96
+ unsigned int minimum_points = window_size_ + 2 ;
65
97
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 ) {
67
99
// Populate path segment
68
100
curr_path_segment.poses .clear ();
69
101
std::copy (
@@ -100,68 +132,41 @@ bool SavitzkyGolaySmoother::smoothImpl(
100
132
nav_msgs::msg::Path & path,
101
133
bool & reversing_segment)
102
134
{
103
- // Must be at least 10 in length to enter function
104
135
const unsigned int & path_size = path.poses .size ();
105
136
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 };
125
140
};
126
141
127
142
auto applyFilterOverAxes =
128
143
[&](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
130
145
{
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
-
139
146
// First point is fixed
140
147
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];
154
153
}
154
+ plan_pts[idx].pose .position .x = accum.x ();
155
+ plan_pts[idx].pose .position .y = accum.y ();
155
156
}
156
157
};
157
158
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);
159
162
applyFilterOverAxes (path.poses , initial_path_poses);
160
163
161
164
// Let's do additional refinement, it shouldn't take more than a couple milliseconds
162
165
if (do_refinement_) {
163
166
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);
165
170
applyFilterOverAxes (path.poses , reined_initial_path_poses);
166
171
}
167
172
}
0 commit comments