31 #include <gtest/gtest.h> 39 TEST(MultiChannelTransferFunctionDoubleFilter, LowPass)
44 EXPECT_TRUE(filter->
configure(1,
"LowPass" ));
47 std::vector<double> in1,in2,in3,in4,in5,in6,in7;
48 std::vector<double> out1;
57 out1.push_back(11.8008);
58 EXPECT_TRUE(filter->
update(in1, in1));
59 EXPECT_TRUE(filter->
update(in2, in2));
60 EXPECT_TRUE(filter->
update(in3, in3));
61 EXPECT_TRUE(filter->
update(in4, in4));
62 EXPECT_TRUE(filter->
update(in5, in5));
63 EXPECT_TRUE(filter->
update(in6, in6));
64 EXPECT_TRUE(filter->
update(in7, in7));
66 EXPECT_NEAR(out1[0], in7[0], epsilon);
69 TEST(SingleChannelTransferFunctionDoubleFilter, SingleLowPass)
74 EXPECT_TRUE(filter->
configure(
"LowPassSingle" ));
77 double in1,in2,in3,in4,in5,in6,in7;
88 EXPECT_TRUE(filter->
update(in1, in1));
89 EXPECT_TRUE(filter->
update(in2, in2));
90 EXPECT_TRUE(filter->
update(in3, in3));
91 EXPECT_TRUE(filter->
update(in4, in4));
92 EXPECT_TRUE(filter->
update(in5, in5));
93 EXPECT_TRUE(filter->
update(in6, in6));
94 EXPECT_TRUE(filter->
update(in7, in7));
96 EXPECT_NEAR(out1, in7, epsilon);
100 TEST(MultiChannelTransferFunctionDoubleFilter, LowPassNonUnity)
105 EXPECT_TRUE(filter->
configure(1,
"LowPassNonUnity" ));
107 std::vector<double> in1,in2,in3,in4,in5,in6,in7;
108 std::vector<double> out1;
117 out1.push_back(2.4088);
118 EXPECT_TRUE(filter->
update(in1, in1));
119 EXPECT_TRUE(filter->
update(in2, in2));
120 EXPECT_TRUE(filter->
update(in3, in3));
121 EXPECT_TRUE(filter->
update(in4, in4));
122 EXPECT_TRUE(filter->
update(in5, in5));
123 EXPECT_TRUE(filter->
update(in6, in6));
124 EXPECT_TRUE(filter->
update(in7, in7));
126 EXPECT_NEAR(out1[0], in7[0], epsilon);
129 TEST(MultiChannelTransferFunctionDoubleFilter, LowPassMulti)
134 EXPECT_TRUE(filter->
configure(3,
"LowPassMulti" ));
136 std::vector<double> in1,in2,in3,in4,in5,in6,in7;
137 std::vector<double> out1;
164 in7.push_back(-30.0);
167 out1.push_back(60.6216);
168 out1.push_back(33.9829);
169 out1.push_back(28.1027);
170 EXPECT_TRUE(filter->
update(in1, in1));
171 EXPECT_TRUE(filter->
update(in2, in2));
172 EXPECT_TRUE(filter->
update(in3, in3));
173 EXPECT_TRUE(filter->
update(in4, in4));
174 EXPECT_TRUE(filter->
update(in5, in5));
175 EXPECT_TRUE(filter->
update(in6, in6));
176 EXPECT_TRUE(filter->
update(in7, in7));
178 for(
unsigned int i=0; i<out1.size(); i++)
180 EXPECT_NEAR(out1[i], in7[i], epsilon);
184 TEST(MultiChannelTransferFunctionDoubleFilter, LowPassIrrational)
189 EXPECT_TRUE(filter->
configure(3,
"LowPassIrrational" ));
191 std::vector<double> in1,in2,in3,in4,in5,in6,in7;
192 std::vector<double> out1;
219 in7.push_back(-30.0);
222 out1.push_back(17.1112);
223 out1.push_back(9.0285);
224 out1.push_back(8.3102);
225 EXPECT_TRUE(filter->
update(in1, in1));
226 EXPECT_TRUE(filter->
update(in2, in2));
227 EXPECT_TRUE(filter->
update(in3, in3));
228 EXPECT_TRUE(filter->
update(in4, in4));
229 EXPECT_TRUE(filter->
update(in5, in5));
230 EXPECT_TRUE(filter->
update(in6, in6));
231 EXPECT_TRUE(filter->
update(in7, in7));
233 for(
unsigned int i=0; i<out1.size(); i++)
235 EXPECT_NEAR(out1[i], in7[i], epsilon);
239 int main(
int argc,
char **argv){
240 testing::InitGoogleTest(&argc, argv);
241 ros::init(argc, argv,
"test_transfer_function");
242 return RUN_ALL_TESTS();
bool configure(const std::string ¶m_name, ros::NodeHandle node_handle=ros::NodeHandle())
Configure the filter from the parameter server.
virtual bool update(const std::vector< T > &data_in, std::vector< T > &data_out)=0
Update the filter and return the data seperately.
A Base filter class to provide a standard interface for all filters.
bool configure(unsigned int number_of_channels, const std::string ¶m_name, ros::NodeHandle node_handle=ros::NodeHandle())
Configure the filter from the parameter server.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
TEST(MultiChannelTransferFunctionDoubleFilter, LowPass)
virtual bool update(const T &data_in, T &data_out)=0
Update the filter and return the data seperately This is an inefficient way to do this and can be ove...
One-dimensional digital filter class.
One-dimensional digital filter class.
int main(int argc, char **argv)