test_median.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 <sys/time.h>
32 
33 #include "filters/median.h"
34 
35 using namespace filters ;
36 
37 void seed_rand()
38 {
39  //Seed random number generator with current microseond count
40  timeval temp_time_struct;
41  gettimeofday(&temp_time_struct,NULL);
42  srand(temp_time_struct.tv_usec);
43 };
44 
45 void generate_rand_vectors(double scale, uint64_t runs, std::vector<double>& xvalues, std::vector<double>& yvalues, std::vector<double>&zvalues)
46 {
47  seed_rand();
48  for ( uint64_t i = 0; i < runs ; i++ )
49  {
50  xvalues[i] = 1.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
51  yvalues[i] = 1.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
52  zvalues[i] = 1.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
53  }
54 }
55 
56 TEST(MultiChannelMedianFilterDouble, ConfirmIdentityNRows)
57 {
58  double epsilon = 1e-6;
59  int length = 5;
60  int rows = 5;
61 
63  EXPECT_TRUE(filter->configure(rows, "MultiChannelMedianFilterDouble5"));
64 
65 
66  double input1[] = {1,2,3,4,5};
67  double input1a[] = {11,12,13,14,15};
68  std::vector<double> v1 (input1, input1 + sizeof(input1) / sizeof(double));
69  std::vector<double> v1a (input1a, input1a + sizeof(input1a) / sizeof(double));
70 
71  for (int i =0; i < rows*10; i++)
72  {
73  EXPECT_TRUE(filter->update(v1, v1a));
74 
75  for (int j = 1; j < length; j++)
76  {
77  EXPECT_NEAR(input1[j], v1a[j], epsilon);
78  }
79  }
80 
81  delete filter;
82 }
83 
84 TEST(MultiChannelMedianFilterDouble, ThreeRows)
85 {
86  double epsilon = 1e-6;
87  int length = 5;
88  int rows = 5;
89 
91  EXPECT_TRUE(filter->configure(rows, "MultiChannelMedianFilterDouble5" ));
92 
93  double input1[] = {0,1,2,3,4};
94  std::vector<double> v1 (input1, input1 + sizeof(input1) / sizeof(double));
95  double input2[] = {1,2,3,4,5};
96  std::vector<double> v2 (input2, input2 + sizeof(input2) / sizeof(double));
97  double input3[] = {2,3,4,5,6};
98  std::vector<double> v3 (input3, input3 + sizeof(input3) / sizeof(double));
99  double input1a[] = {1,2,3,4,5};
100  std::vector<double> v1a (input1a, input1a + sizeof(input1a) / sizeof(double));
101 
102  EXPECT_TRUE(filter->update(v1, v1a));
103  EXPECT_TRUE(filter->update(v2, v1a));
104  EXPECT_TRUE(filter->update(v3, v1a));
105 
106  for (int i = 1; i < length; i++)
107  {
108  EXPECT_NEAR(v2[i], v1a[i], epsilon);
109  }
110 
111 }
112 
113 TEST(MultiChannelMedianFilterFloat, ConfirmIdentityNRows)
114 {
115  float epsilon = 1e-6;
116  int length = 5;
117  int rows = 5;
118 
120  EXPECT_TRUE(filter->configure(rows, "MultiChannelMedianFilterFloat5" ));
121 
122  float input1[] = {1,2,3,4,5};
123  float input1a[] = {1,2,3,4,5};
124  std::vector<float> v1 (input1, input1 + sizeof(input1) / sizeof(float));
125  std::vector<float> v1a (input1a, input1a + sizeof(input1a) / sizeof(float));
126 
127  for (int i =0; i < rows*10; i++)
128  {
129  EXPECT_TRUE(filter->update(v1, v1a));
130 
131  for (int j = 1; j < length; j++)
132  {
133  EXPECT_NEAR(input1[j], v1a[j], epsilon);
134  }
135  }
136 
137  delete filter;
138 }
139 
140 TEST(MultiChannelMedianFilterFloat, ThreeRows)
141 {
142  float epsilon = 1e-6;
143  int length = 5;
144  int rows = 5;
145 
147  EXPECT_TRUE(filter->configure(rows, "MultiChannelMedianFilterFloat5"));
148 
149  float input1[] = {0,1,2,3,4};
150  std::vector<float> v1 (input1, input1 + sizeof(input1) / sizeof(float));
151  float input2[] = {1,2,3,4,5};
152  std::vector<float> v2 (input2, input2 + sizeof(input2) / sizeof(float));
153  float input3[] = {2,3,4,5,6};
154  std::vector<float> v3 (input3, input3 + sizeof(input3) / sizeof(float));
155  float input1a[] = {1,2,3,4,5};
156  std::vector<float> v1a (input1a, input1a + sizeof(input1a) / sizeof(float));
157 
158  EXPECT_TRUE(filter->update(v1, v1a));
159  EXPECT_TRUE(filter->update(v2, v1a));
160  EXPECT_TRUE(filter->update(v3, v1a));
161 
162  for (int i = 1; i < length; i++)
163  {
164  EXPECT_NEAR(v2[i], v1a[i], epsilon);
165  }
166 
167 }
168 
169 
170 int main(int argc, char **argv){
171  testing::InitGoogleTest(&argc, argv);
172  ros::init(argc, argv, "test_median");
173  return RUN_ALL_TESTS();
174 }
void generate_rand_vectors(double scale, uint64_t runs, std::vector< double > &xvalues, std::vector< double > &yvalues, std::vector< double > &zvalues)
Definition: test_median.cpp:45
double epsilon
void seed_rand()
Definition: test_median.cpp:37
virtual bool update(const std::vector< T > &data_in, std::vector< T > &data_out)=0
Update the filter and return the data seperately.
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)
int main(int argc, char **argv)
TEST(MultiChannelMedianFilterDouble, ConfirmIdentityNRows)
Definition: test_median.cpp:56
A median filter which works on arrays.
Definition: median.h:181


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