test_transfer_function.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <ros/ros.h>
31 #include <gtest/gtest.h>
32 #include <sys/time.h>
33 #include <vector>
35 
36 using namespace filters ;
37 
38 
39 TEST(MultiChannelTransferFunctionDoubleFilter, LowPass)
40 {
41  double epsilon = 1e-4;
42 
44  EXPECT_TRUE(filter->configure(1, "LowPass" ));
45 
46 
47  std::vector<double> in1,in2,in3,in4,in5,in6,in7;
48  std::vector<double> out1;
49 
50  in1.push_back(10.0);
51  in2.push_back(70.0);
52  in3.push_back(10.0);
53  in4.push_back(44.0);
54  in5.push_back(10.0);
55  in6.push_back(5.0);
56  in7.push_back(6.0);
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));
65 
66  EXPECT_NEAR(out1[0], in7[0], epsilon);
67 }
68 
69 TEST(SingleChannelTransferFunctionDoubleFilter, SingleLowPass)
70 {
71  double epsilon = 1e-4;
72 
74  EXPECT_TRUE(filter->configure("LowPassSingle" ));
75 
76 
77  double in1,in2,in3,in4,in5,in6,in7;
78  double out1;
79 
80  in1=10.0;
81  in2=70.0;
82  in3=10.0;
83  in4=44.0;
84  in5=10.0;
85  in6=5.0;
86  in7=6.0;
87  out1=11.8008;
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));
95 
96  EXPECT_NEAR(out1, in7, epsilon);
97 }
98 
99 
100 TEST(MultiChannelTransferFunctionDoubleFilter, LowPassNonUnity)
101 {
102  double epsilon = 1e-4;
103 
105  EXPECT_TRUE(filter->configure(1, "LowPassNonUnity" ));
106 
107  std::vector<double> in1,in2,in3,in4,in5,in6,in7;
108  std::vector<double> out1;
109 
110  in1.push_back(10.0);
111  in2.push_back(70.0);
112  in3.push_back(10.0);
113  in4.push_back(44.0);
114  in5.push_back(10.0);
115  in6.push_back(5.0);
116  in7.push_back(6.0);
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));
125 
126  EXPECT_NEAR(out1[0], in7[0], epsilon);
127 }
128 
129 TEST(MultiChannelTransferFunctionDoubleFilter, LowPassMulti)
130 {
131  double epsilon = 1e-4;
132 
134  EXPECT_TRUE(filter->configure(3, "LowPassMulti" ));
135 
136  std::vector<double> in1,in2,in3,in4,in5,in6,in7;
137  std::vector<double> out1;
138 
139  in1.push_back(10.0);
140  in1.push_back(10.0);
141  in1.push_back(10.0);
142  //
143  in2.push_back(70.0);
144  in2.push_back(30.0);
145  in2.push_back(8.0);
146  //
147  in3.push_back(-1.0);
148  in3.push_back(5.0);
149  in3.push_back(22.0);
150  //
151  in4.push_back(44.0);
152  in4.push_back(23.0);
153  in4.push_back(8.0);
154  //
155  in5.push_back(10.0);
156  in5.push_back(10.0);
157  in5.push_back(10.0);
158  //
159  in6.push_back(5.0);
160  in6.push_back(-1.0);
161  in6.push_back(5.0);
162  //
163  in7.push_back(6.0);
164  in7.push_back(-30.0);
165  in7.push_back(2.0);
166  //
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));
177 
178  for(unsigned int i=0; i<out1.size(); i++)
179  {
180  EXPECT_NEAR(out1[i], in7[i], epsilon);
181  }
182 }
183 
184 TEST(MultiChannelTransferFunctionDoubleFilter, LowPassIrrational)
185 {
186  double epsilon = 1e-4;
187 
189  EXPECT_TRUE(filter->configure(3, "LowPassIrrational" ));
190 
191  std::vector<double> in1,in2,in3,in4,in5,in6,in7;
192  std::vector<double> out1;
193 
194  in1.push_back(10.0);
195  in1.push_back(10.0);
196  in1.push_back(10.0);
197  //
198  in2.push_back(70.0);
199  in2.push_back(30.0);
200  in2.push_back(8.0);
201  //
202  in3.push_back(-1.0);
203  in3.push_back(5.0);
204  in3.push_back(22.0);
205  //
206  in4.push_back(44.0);
207  in4.push_back(23.0);
208  in4.push_back(8.0);
209  //
210  in5.push_back(10.0);
211  in5.push_back(10.0);
212  in5.push_back(10.0);
213  //
214  in6.push_back(5.0);
215  in6.push_back(-1.0);
216  in6.push_back(5.0);
217  //
218  in7.push_back(6.0);
219  in7.push_back(-30.0);
220  in7.push_back(2.0);
221  //
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));
232 
233  for(unsigned int i=0; i<out1.size(); i++)
234  {
235  EXPECT_NEAR(out1[i], in7[i], epsilon);
236  }
237 }
238 
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();
243 }
bool configure(const std::string &param_name, ros::NodeHandle node_handle=ros::NodeHandle())
Configure the filter from the parameter server.
Definition: filter_base.h:65
double epsilon
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.
Definition: filter_base.h:50
bool configure(unsigned int number_of_channels, const std::string &param_name, ros::NodeHandle node_handle=ros::NodeHandle())
Configure the filter from the parameter server.
Definition: filter_base.h:388
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)


filters
Author(s):
autogenerated on Sat Jun 8 2019 04:37:52