test_chain.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 "gtest/gtest.h"
31 #include "filters/filter_chain.hpp"
32 
33 
34 
35 TEST(MultiChannelFilterChain, configuring){
36  double epsilon = 1e-9;
38 
39  EXPECT_TRUE(chain.configure(5, "MultiChannelMeanFilterDouble5"));
40 
41  double input1[] = {1,2,3,4,5};
42  double input1a[] = {9,9,9,9,9};//seed w/incorrect values
43  std::vector<double> v1 (input1, input1 + sizeof(input1) / sizeof(double));
44  std::vector<double> v1a (input1a, input1a + sizeof(input1a) / sizeof(double));
45 
46 
47  EXPECT_TRUE(chain.update(v1, v1a));
48 
49  chain.clear();
50 
51  for (unsigned int i = 1; i < v1.size(); i++)
52  {
53  EXPECT_NEAR(input1[i], v1a[i], epsilon);
54  }
55 }
56 TEST(FilterChain, configuring){
57  double epsilon = 1e-9;
58  filters::FilterChain<float> chain("float");
59 
60  EXPECT_TRUE(chain.configure("MeanFilterFloat5"));
61 
62  float v1 = 1;
63  float v1a = 9;
64 
65  EXPECT_TRUE(chain.update(v1, v1a));
66 
67  chain.clear();
68 
69  EXPECT_NEAR(v1, v1a, epsilon);
70 
71  }
72 
73 TEST(MultiChannelFilterChain, MisconfiguredNumberOfChannels){
75 
76  EXPECT_TRUE(chain.configure(10, "MultiChannelMedianFilterDouble5"));
77 
78  // EXPECT_TRUE(chain.configure(10));
79 
80  double input1[] = {1,2,3,4,5};
81  double input1a[] = {1,2,3,4,5};
82  std::vector<double> v1 (input1, input1 + sizeof(input1) / sizeof(double));
83  std::vector<double> v1a (input1a, input1a + sizeof(input1a) / sizeof(double));
84 
85 
86  EXPECT_FALSE(chain.update(v1, v1a));
87 
88  chain.clear();
89 
90 }
91 
92 TEST(MultiChannelFilterChain, TwoFilters){
93  double epsilon = 1e-9;
95 
96  EXPECT_TRUE(chain.configure(5, "TwoFilters"));
97 
98  double input1[] = {1,2,3,4,5};
99  double input1a[] = {9,9,9,9,9};//seed w/incorrect values
100  std::vector<double> v1 (input1, input1 + sizeof(input1) / sizeof(double));
101  std::vector<double> v1a (input1a, input1a + sizeof(input1a) / sizeof(double));
102 
103 
104  EXPECT_TRUE(chain.update(v1, v1a));
105 
106  chain.clear();
107 
108  for (unsigned int i = 1; i < v1.size(); i++)
109  {
110  EXPECT_NEAR(input1[i], v1a[i], epsilon);
111  }
112 }
113 
114 TEST(MultiChannelFilterChain, GetFilters){
116 
117  EXPECT_EQ(0u, chain.getFilters().size());
118 
119  auto filtersBefore = chain.getFilters();
120 
121  EXPECT_TRUE(chain.configure(5, "TwoFilters"));
122 
123  auto filtersAfter = chain.getFilters();
124 
125  ASSERT_EQ(2u, chain.getFilters().size());
126  ASSERT_EQ(2u, filtersAfter.size());
127  EXPECT_EQ(0u, filtersBefore.size()); // Test that getFilters() returns a copy of the vector
128  EXPECT_EQ("median_test_unique", chain.getFilters()[0]->getName());
129  EXPECT_EQ("filters/MultiChannelMedianFilterDouble", chain.getFilters()[0]->getType());
130  EXPECT_EQ("median_test2", chain.getFilters()[1]->getName());
131  EXPECT_EQ("filters/MultiChannelMedianFilterDouble", chain.getFilters()[1]->getType());
132 
133  // Check that changing our copy of the list of filters does not change the
134  // filters handled by the chain.
135  filtersAfter.clear();
136  EXPECT_EQ(2u, chain.getFilters().size());
137 
138  filtersAfter = chain.getFilters();
139 
140  chain.clear();
141 
142  EXPECT_EQ(0u, chain.getFilters().size());
143  ASSERT_EQ(2u, filtersAfter.size());
144 
145  // Check that the filter pointers survive clearing the filter chain (if we
146  // hold a copy of the filter vector).
147  EXPECT_EQ("median_test_unique", filtersAfter[0]->getName());
148  EXPECT_EQ("median_test2", filtersAfter[1]->getName());
149 }
150 
151 
152 TEST(MultiChannelFilterChain, TransferFunction){
153  double epsilon = 1e-4;
154 
156  EXPECT_TRUE(chain.configure(3, "TransferFunction" ));
157 
158  std::vector<double> in1,in2,in3,in4,in5,in6,in7;
159  std::vector<double> out1;
160 
161  in1.push_back(10.0);
162  in1.push_back(10.0);
163  in1.push_back(10.0);
164  //
165  in2.push_back(70.0);
166  in2.push_back(30.0);
167  in2.push_back(8.0);
168  //
169  in3.push_back(-1.0);
170  in3.push_back(5.0);
171  in3.push_back(22.0);
172  //
173  in4.push_back(44.0);
174  in4.push_back(23.0);
175  in4.push_back(8.0);
176  //
177  in5.push_back(10.0);
178  in5.push_back(10.0);
179  in5.push_back(10.0);
180  //
181  in6.push_back(5.0);
182  in6.push_back(-1.0);
183  in6.push_back(5.0);
184  //
185  in7.push_back(6.0);
186  in7.push_back(-30.0);
187  in7.push_back(2.0);
188  //
189  out1.push_back(17.1112);
190  out1.push_back(9.0285);
191  out1.push_back(8.3102);
192  EXPECT_TRUE(chain.update(in1, in1));
193  EXPECT_TRUE(chain.update(in2, in2));
194  EXPECT_TRUE(chain.update(in3, in3));
195  EXPECT_TRUE(chain.update(in4, in4));
196  EXPECT_TRUE(chain.update(in5, in5));
197  EXPECT_TRUE(chain.update(in6, in6));
198  EXPECT_TRUE(chain.update(in7, in7));
199 
200  chain.clear();
201 
202  for(unsigned int i=0; i<out1.size(); i++)
203  {
204  EXPECT_NEAR(out1[i], in7[i], epsilon);
205  }
206 }
207 
208 TEST(FilterChain, ReconfiguringChain){
209  filters::FilterChain<int> chain("int");
210 
211  int v1 = 1;
212  int v1a = 9;
213 
214  EXPECT_TRUE(chain.configure("OneIncrements"));
215  EXPECT_TRUE(chain.update(v1, v1a));
216  EXPECT_EQ(2, v1a);
217  chain.clear();
218 
219  EXPECT_TRUE(chain.configure("TwoIncrements"));
220  EXPECT_TRUE(chain.update(v1, v1a));
221  EXPECT_EQ(3, v1a);
222  chain.clear();
223 }
224 
225 TEST(FilterChain, GetFilters){
226  filters::FilterChain<int> chain("int");
227 
228  EXPECT_EQ(0u, chain.getFilters().size());
229 
230  auto filtersBefore = chain.getFilters();
231 
232  EXPECT_TRUE(chain.configure("TwoIncrements"));
233 
234  auto filtersAfter = chain.getFilters();
235 
236  ASSERT_EQ(2u, chain.getFilters().size());
237  ASSERT_EQ(2u, filtersAfter.size());
238  EXPECT_EQ(0u, filtersBefore.size()); // Test that getFilters() returns a copy of the vector
239  EXPECT_EQ("increment1", chain.getFilters()[0]->getName());
240  EXPECT_EQ("filters/IncrementFilterInt", chain.getFilters()[0]->getType());
241  EXPECT_EQ("increment2", chain.getFilters()[1]->getName());
242  EXPECT_EQ("filters/IncrementFilterInt", chain.getFilters()[1]->getType());
243 
244  // Check that changing our copy of the list of filters does not change the
245  // filters handled by the chain.
246  filtersAfter.clear();
247  EXPECT_EQ(2u, chain.getFilters().size());
248 
249  filtersAfter = chain.getFilters();
250 
251  chain.clear();
252 
253  EXPECT_EQ(0u, chain.getFilters().size());
254  ASSERT_EQ(2u, filtersAfter.size());
255 
256  // Check that the filter pointers survive clearing the filter chain (if we
257  // hold a copy of the filter vector).
258  EXPECT_EQ("increment1", filtersAfter[0]->getName());
259  EXPECT_EQ("increment2", filtersAfter[1]->getName());
260 }
261 
262 TEST(FilterChain, ThreeIncrementChains){
263  filters::FilterChain<int> chain("int");
264  int v1 = 1;
265  int v1a = 9;
266 
267  EXPECT_TRUE(chain.configure("ThreeIncrements"));
268  EXPECT_TRUE(chain.update(v1, v1a));
269  EXPECT_EQ(4, v1a);
270  chain.clear();
271 
272 }
273 
274 TEST(FilterChain, TenIncrementChains){
275  filters::FilterChain<int> chain("int");
276  int v1 = 1;
277  int v1a = 9;
278 
279  EXPECT_TRUE(chain.configure("TenIncrements"));
280  EXPECT_TRUE(chain.update(v1, v1a));
281  EXPECT_EQ(11, v1a);
282  chain.clear();
283 
284 }
285 
286 TEST(MultiChannelFilterChain, TenMultiChannelIncrementChains){
288  std::vector<int> v1;
289  v1.push_back(1);
290  v1.push_back(1);
291  v1.push_back(1);
292  std::vector<int> v1a = v1;
293 
294  EXPECT_TRUE(chain.configure(3, "TenMultiChannelIncrements"));
295  EXPECT_TRUE(chain.update(v1, v1a));
296  for (unsigned int i = 0; i < 3; i++)
297  {
298  EXPECT_EQ(11, v1a[i]);
299  }
300  chain.clear();
301 
302 }
303 
304 
305 int main(int argc, char **argv){
306  testing::InitGoogleTest(&argc, argv);
307  ros::init(argc, argv, "test_chain");
308  return RUN_ALL_TESTS();
309 }
filter_chain.hpp
filters::MultiChannelFilterChain::update
bool update(const std::vector< T > &data_in, std::vector< T > &data_out)
process data through each of the filters added sequentially
Definition: filter_chain.hpp:317
epsilon
double epsilon
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
filters::MultiChannelFilterChain
A class which will construct and sequentially call Filters according to xml This is the primary way i...
Definition: filter_chain.hpp:275
filters::MultiChannelFilterChain::clear
bool clear()
Clear all filters from this chain.
Definition: filter_chain.hpp:363
filters::MultiChannelFilterChain::configure
bool configure(unsigned int size, std::string param_name, ros::NodeHandle node=ros::NodeHandle())
Configure the filter chain from a configuration stored on the parameter server.
Definition: filter_chain.hpp:296
getName
ROSCONSOLE_CONSOLE_IMPL_DECL std::string getName(void *handle)
filters::FilterChain::getFilters
std::vector< std::shared_ptr< filters::FilterBase< T > > > getFilters() const
Return a copy of the vector of loaded filters (the pointers point to the actual filters used by the c...
Definition: filter_chain.hpp:256
filters::FilterChain::clear
bool clear()
Clear all filters from this chain.
Definition: filter_chain.hpp:130
filters::MultiChannelFilterChain::getFilters
std::vector< std::shared_ptr< filters::MultiChannelFilterBase< T > > > getFilters() const
Return a copy of the vector of loaded filters (the pointers point to the actual filters used by the c...
Definition: filter_chain.hpp:504
filters::FilterChain::configure
bool configure(std::string param_name, ros::NodeHandle node=ros::NodeHandle())
Configure the filter chain from a configuration stored on the parameter server.
Definition: filter_chain.hpp:74
filters::FilterChain
A class which will construct and sequentially call Filters according to xml This is the primary way i...
Definition: filter_chain.hpp:47
filters::FilterChain::update
bool update(const T &data_in, T &data_out)
process data through each of the filters added sequentially
Definition: filter_chain.hpp:92
main
int main(int argc, char **argv)
Definition: test_chain.cpp:305
TEST
TEST(MultiChannelFilterChain, configuring)
Definition: test_chain.cpp:35


filters
Author(s):
autogenerated on Fri Apr 11 2025 02:08:40