Skip to content

Commit b1f2619

Browse files
authored
Add std::vector<double> option to the low pass filter (#340)
1 parent 24cf0d8 commit b1f2619

File tree

6 files changed

+175
-32
lines changed

6 files changed

+175
-32
lines changed

control_toolbox/control_filters.xml

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,13 @@
1818
This is a low pass filter working with a double value.
1919
</description>
2020
</class>
21+
<class name="control_filters/LowPassFilterVectorDouble"
22+
type="control_filters::LowPassFilter&lt;std::vector&lt;double&gt;&gt;"
23+
base_class_type="filters::FilterBase&lt;std::vector&lt;double&gt;&gt;">
24+
<description>
25+
This is a low pass filter working with a std::vector double value.
26+
</description>
27+
</class>
2128
<class name="control_filters/LowPassFilterWrench"
2229
type="control_filters::LowPassFilter&lt;geometry_msgs::msg::WrenchStamped&gt;"
2330
base_class_type="filters::FilterBase&lt;geometry_msgs::msg::WrenchStamped&gt;">

control_toolbox/include/control_filters/low_pass_filter.hpp

Lines changed: 21 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717

1818
#include <memory>
1919
#include <string>
20+
#include <vector>
2021

2122
#include "filters/filter_base.hpp"
2223
#include "geometry_msgs/msg/wrench_stamped.hpp"
@@ -153,6 +154,26 @@ inline bool LowPassFilter<geometry_msgs::msg::WrenchStamped>::update(
153154
return lpf_->update(data_in, data_out);
154155
}
155156

157+
template <>
158+
inline bool LowPassFilter<std::vector<double>>::update(
159+
const std::vector<double> & data_in, std::vector<double> & data_out)
160+
{
161+
if (!this->configured_ || !lpf_ || !lpf_->is_configured())
162+
{
163+
throw std::runtime_error("Filter is not configured");
164+
}
165+
166+
// Update internal parameters if required
167+
if (parameter_handler_->is_old(parameters_))
168+
{
169+
parameters_ = parameter_handler_->get_params();
170+
lpf_->set_params(
171+
parameters_.sampling_frequency, parameters_.damping_frequency, parameters_.damping_intensity);
172+
}
173+
174+
return lpf_->update(data_in, data_out);
175+
}
176+
156177
template <typename T>
157178
bool LowPassFilter<T>::update(const T & data_in, T & data_out)
158179
{

control_toolbox/include/control_toolbox/low_pass_filter.hpp

Lines changed: 63 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
#include <Eigen/Dense>
1919

2020
#include <cmath>
21+
#include <limits>
2122
#include <memory>
2223
#include <stdexcept>
2324
#include <string>
@@ -122,8 +123,8 @@ class LowPassFilter
122123
// Filter parameters
123124
double a1_; /** feedbackward coefficient. */
124125
double b1_; /** feedforward coefficient. */
125-
/** internal data storage (double). */
126-
double filtered_value, filtered_old_value, old_value;
126+
/** internal data storage of template type. */
127+
T filtered_value, filtered_old_value, old_value;
127128
/** internal data storage (wrench). */
128129
Eigen::Matrix<double, 6, 1> msg_filtered, msg_filtered_old, msg_old;
129130
bool configured_ = false;
@@ -143,11 +144,11 @@ template <typename T>
143144
bool LowPassFilter<T>::configure()
144145
{
145146
// Initialize storage Vectors
146-
filtered_value = filtered_old_value = old_value = 0;
147+
filtered_value = filtered_old_value = old_value = std::numeric_limits<T>::quiet_NaN();
147148
// TODO(destogl): make the size parameterizable and more intelligent is using complex types
148149
for (Eigen::Index i = 0; i < 6; ++i)
149150
{
150-
msg_filtered[i] = msg_filtered_old[i] = msg_old[i] = 0;
151+
msg_filtered[i] = msg_filtered_old[i] = msg_old[i] = std::numeric_limits<double>::quiet_NaN();
151152
}
152153

153154
return configured_ = true;
@@ -161,6 +162,19 @@ inline bool LowPassFilter<geometry_msgs::msg::WrenchStamped>::update(
161162
{
162163
throw std::runtime_error("Filter is not configured");
163164
}
165+
// If this is the first call to update initialize the filter at the current state
166+
// so that we dont apply an impulse to the data.
167+
if (msg_filtered.hasNaN())
168+
{
169+
msg_filtered[0] = data_in.wrench.force.x;
170+
msg_filtered[1] = data_in.wrench.force.y;
171+
msg_filtered[2] = data_in.wrench.force.z;
172+
msg_filtered[3] = data_in.wrench.torque.x;
173+
msg_filtered[4] = data_in.wrench.torque.y;
174+
msg_filtered[5] = data_in.wrench.torque.z;
175+
msg_filtered_old = msg_filtered;
176+
msg_old = msg_filtered;
177+
}
164178

165179
// IIR Filter
166180
msg_filtered = b1_ * msg_old + a1_ * msg_filtered_old;
@@ -186,18 +200,62 @@ inline bool LowPassFilter<geometry_msgs::msg::WrenchStamped>::update(
186200
return true;
187201
}
188202

203+
template <>
204+
inline bool LowPassFilter<std::vector<double>>::update(
205+
const std::vector<double> & data_in, std::vector<double> & data_out)
206+
{
207+
if (!configured_)
208+
{
209+
throw std::runtime_error("Filter is not configured");
210+
}
211+
// If this is the first call to update initialize the filter at the current state
212+
// so that we dont apply an impulse to the data.
213+
// This also sets the size of the member variables to match the input data.
214+
if (filtered_value.empty())
215+
{
216+
filtered_value = data_in;
217+
filtered_old_value = data_in;
218+
old_value = data_in;
219+
}
220+
else
221+
{
222+
assert(
223+
data_in.size() == filtered_value.size() &&
224+
"Internal data and the data_in doesn't hold the same size");
225+
assert(data_out.size() == data_in.size() && "data_in and data_out doesn't hold same size");
226+
}
227+
228+
// Filter each value in the vector
229+
for (std::size_t i = 0; i < data_in.size(); i++)
230+
{
231+
data_out[i] = b1_ * old_value[i] + a1_ * filtered_old_value[i];
232+
filtered_old_value[i] = data_out[i];
233+
if (std::isfinite(data_in[i])) old_value[i] = data_in[i];
234+
}
235+
236+
return true;
237+
}
238+
189239
template <typename T>
190240
bool LowPassFilter<T>::update(const T & data_in, T & data_out)
191241
{
192242
if (!configured_)
193243
{
194244
throw std::runtime_error("Filter is not configured");
195245
}
246+
// If this is the first call to update initialize the filter at the current state
247+
// so that we dont apply an impulse to the data.
248+
if (std::isnan(filtered_value))
249+
{
250+
filtered_value = data_in;
251+
filtered_old_value = data_in;
252+
old_value = data_in;
253+
}
196254

197255
// Filter
198256
data_out = b1_ * old_value + a1_ * filtered_old_value;
199257
filtered_old_value = data_out;
200-
old_value = data_in;
258+
if (std::isfinite(data_in)) old_value = data_in;
201259

202260
return true;
203261
}

control_toolbox/src/control_filters/low_pass_filter.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,9 @@
1818

1919
PLUGINLIB_EXPORT_CLASS(control_filters::LowPassFilter<double>, filters::FilterBase<double>)
2020

21+
PLUGINLIB_EXPORT_CLASS(
22+
control_filters::LowPassFilter<std::vector<double>>, filters::FilterBase<std::vector<double>>)
23+
2124
PLUGINLIB_EXPORT_CLASS(
2225
control_filters::LowPassFilter<geometry_msgs::msg::WrenchStamped>,
2326
filters::FilterBase<geometry_msgs::msg::WrenchStamped>)

control_toolbox/test/control_filters/test_load_low_pass_filter.cpp

Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,28 @@ TEST(TestLoadLowPassFilter, load_low_pass_filter_double)
4343
rclcpp::shutdown();
4444
}
4545

46+
TEST(TestLoadLowPassFilter, load_low_pass_filter_vector_double)
47+
{
48+
rclcpp::init(0, nullptr);
49+
50+
pluginlib::ClassLoader<filters::FilterBase<std::vector<double>>> filter_loader(
51+
"filters", "filters::FilterBase<std::vector<double>>");
52+
std::shared_ptr<filters::FilterBase<std::vector<double>>> filter;
53+
auto available_classes = filter_loader.getDeclaredClasses();
54+
std::stringstream sstr;
55+
sstr << "available filters:" << std::endl;
56+
for (const auto & available_class : available_classes)
57+
{
58+
sstr << " " << available_class << std::endl;
59+
}
60+
61+
std::string filter_type = "control_filters/LowPassFilterVectorDouble";
62+
ASSERT_TRUE(filter_loader.isClassAvailable(filter_type)) << sstr.str();
63+
EXPECT_NO_THROW(filter = filter_loader.createSharedInstance(filter_type));
64+
65+
rclcpp::shutdown();
66+
}
67+
4668
TEST(TestLoadLowPassFilter, load_low_pass_filter_wrench)
4769
{
4870
rclcpp::init(0, nullptr);

control_toolbox/test/control_filters/test_low_pass_filter.cpp

Lines changed: 59 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -110,23 +110,28 @@ TEST_F(FilterTest, TestLowPassWrenchFilterComputation)
110110
"", "TestLowPassFilter", node_->get_node_logging_interface(),
111111
node_->get_node_parameters_interface()));
112112

113-
// first filter pass, output should be zero as no old wrench was stored
113+
// first filter pass, output should be equal to the input
114114
ASSERT_TRUE(filter_->update(in, out));
115-
ASSERT_EQ(out.wrench.force.x, 0.0);
116-
ASSERT_EQ(out.wrench.force.y, 0.0);
117-
ASSERT_EQ(out.wrench.force.z, 0.0);
118-
ASSERT_EQ(out.wrench.torque.x, 0.0);
119-
ASSERT_EQ(out.wrench.torque.y, 0.0);
120-
ASSERT_EQ(out.wrench.torque.z, 0.0);
121-
122-
// second filter pass with same values:
115+
ASSERT_EQ(out.wrench.force.x, in.wrench.force.x);
116+
ASSERT_EQ(out.wrench.force.y, in.wrench.force.y);
117+
ASSERT_EQ(out.wrench.force.z, in.wrench.force.z);
118+
ASSERT_EQ(out.wrench.torque.x, in.wrench.torque.x);
119+
ASSERT_EQ(out.wrench.torque.y, in.wrench.torque.y);
120+
ASSERT_EQ(out.wrench.torque.z, in.wrench.torque.z);
121+
122+
// second filter pass with a step in values (otherwise there is nothing to filter):
123+
in.wrench.force.x = 2.0;
124+
in.wrench.torque.x = 20.0;
125+
ASSERT_TRUE(filter_->update(in, out));
126+
127+
// update once again and check results
123128
// calculate wrench by hand
124-
calculated.wrench.force.x = b1 * in.wrench.force.x;
125-
calculated.wrench.force.y = b1 * in.wrench.force.y;
126-
calculated.wrench.force.z = b1 * in.wrench.force.z;
127-
calculated.wrench.torque.x = b1 * in.wrench.torque.x;
128-
calculated.wrench.torque.y = b1 * in.wrench.torque.y;
129-
calculated.wrench.torque.z = b1 * in.wrench.torque.z;
129+
calculated.wrench.force.x = b1 * in.wrench.force.x + a1 * out.wrench.force.x;
130+
calculated.wrench.force.y = b1 * in.wrench.force.y + a1 * out.wrench.force.y;
131+
calculated.wrench.force.z = b1 * in.wrench.force.z + a1 * out.wrench.force.z;
132+
calculated.wrench.torque.x = b1 * in.wrench.torque.x + a1 * out.wrench.torque.x;
133+
calculated.wrench.torque.y = b1 * in.wrench.torque.y + a1 * out.wrench.torque.y;
134+
calculated.wrench.torque.z = b1 * in.wrench.torque.z + a1 * out.wrench.torque.z;
130135
// check equality with low-pass-filter
131136
ASSERT_TRUE(filter_->update(in, out));
132137
ASSERT_EQ(out.wrench.force.x, calculated.wrench.force.x);
@@ -135,23 +140,50 @@ TEST_F(FilterTest, TestLowPassWrenchFilterComputation)
135140
ASSERT_EQ(out.wrench.torque.x, calculated.wrench.torque.x);
136141
ASSERT_EQ(out.wrench.torque.y, calculated.wrench.torque.y);
137142
ASSERT_EQ(out.wrench.torque.z, calculated.wrench.torque.z);
143+
}
144+
145+
TEST_F(FilterTest, TestLowPassVectorDoubleFilterComputation)
146+
{
147+
// parameters should match the test yaml file
148+
double sampling_freq = 1000.0;
149+
double damping_freq = 20.5;
150+
double damping_intensity = 1.25;
151+
152+
double a1, b1;
153+
a1 = exp(
154+
-1.0 / sampling_freq * (2.0 * M_PI * damping_freq) / (pow(10.0, damping_intensity / -10.0)));
155+
b1 = 1.0 - a1;
156+
157+
std::vector<double> in{1.0, 2.0, 3.0};
158+
std::vector<double> calculated, out;
159+
calculated.resize(in.size());
160+
out.resize(in.size());
161+
162+
std::shared_ptr<filters::FilterBase<std::vector<double>>> filter_ =
163+
std::make_shared<control_filters::LowPassFilter<std::vector<double>>>();
164+
165+
node_->declare_parameter("sampling_frequency", rclcpp::ParameterValue(sampling_freq));
166+
node_->declare_parameter("damping_frequency", rclcpp::ParameterValue(damping_freq));
167+
node_->declare_parameter("damping_intensity", rclcpp::ParameterValue(damping_intensity));
168+
ASSERT_TRUE(filter_->configure(
169+
"", "TestLowPassFilter", node_->get_node_logging_interface(),
170+
node_->get_node_parameters_interface()));
171+
172+
ASSERT_TRUE(filter_->update(in, out));
173+
ASSERT_TRUE(std::equal(in.begin(), in.end(), out.begin()));
174+
175+
// second filter pass with a step in values (otherwise there is nothing to filter):
176+
in = {2.0, 4.0, 6.0};
177+
ASSERT_TRUE(filter_->update(in, out));
138178

139179
// update once again and check results
140180
// calculate wrench by hand
141-
calculated.wrench.force.x = b1 * in.wrench.force.x + a1 * calculated.wrench.force.x;
142-
calculated.wrench.force.y = b1 * in.wrench.force.y + a1 * calculated.wrench.force.y;
143-
calculated.wrench.force.z = b1 * in.wrench.force.z + a1 * calculated.wrench.force.z;
144-
calculated.wrench.torque.x = b1 * in.wrench.torque.x + a1 * calculated.wrench.torque.x;
145-
calculated.wrench.torque.y = b1 * in.wrench.torque.y + a1 * calculated.wrench.torque.y;
146-
calculated.wrench.torque.z = b1 * in.wrench.torque.z + a1 * calculated.wrench.torque.z;
181+
calculated[0] = b1 * in[0] + a1 * out[0];
182+
calculated[1] = b1 * in[1] + a1 * out[1];
183+
calculated[2] = b1 * in[2] + a1 * out[2];
147184
// check equality with low-pass-filter
148185
ASSERT_TRUE(filter_->update(in, out));
149-
ASSERT_EQ(out.wrench.force.x, calculated.wrench.force.x);
150-
ASSERT_EQ(out.wrench.force.y, calculated.wrench.force.y);
151-
ASSERT_EQ(out.wrench.force.z, calculated.wrench.force.z);
152-
ASSERT_EQ(out.wrench.torque.x, calculated.wrench.torque.x);
153-
ASSERT_EQ(out.wrench.torque.y, calculated.wrench.torque.y);
154-
ASSERT_EQ(out.wrench.torque.z, calculated.wrench.torque.z);
186+
ASSERT_TRUE(std::equal(out.begin(), out.end(), calculated.begin()));
155187
}
156188

157189
int main(int argc, char ** argv)

0 commit comments

Comments
 (0)