test_mean.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 #include "filters/mean.h"
33 
34 using namespace filters ;
35 
36 void seed_rand()
37 {
38  //Seed random number generator with current microseond count
39  timeval temp_time_struct;
40  gettimeofday(&temp_time_struct,NULL);
41  srand(temp_time_struct.tv_usec);
42 };
43 
44 void generate_rand_vectors(double scale, uint64_t runs, std::vector<double>& xvalues, std::vector<double>& yvalues, std::vector<double>&zvalues)
45 {
46  seed_rand();
47  for ( uint64_t i = 0; i < runs ; i++ )
48  {
49  xvalues[i] = 1.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
50  yvalues[i] = 1.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
51  zvalues[i] = 1.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
52  }
53 }
54 
55 TEST(MultiChannelMeanFilterDouble, ConfirmIdentityNRows)
56 {
57  double epsilon = 1e-6;
58  int length = 5;
59  int rows = 5;
60 
62  EXPECT_TRUE(filter->configure(rows, "MultiChannelMeanFilterDouble5"));
63 
64  double input1[] = {1,2,3,4,5};
65  double input1a[] = {1,2,3,4,5};
66  std::vector<double> v1 (input1, input1 + sizeof(input1) / sizeof(double));
67  std::vector<double> v1a (input1a, input1a + sizeof(input1a) / sizeof(double));
68 
69 
70  for (int32_t i =0; i < rows*10; i++)
71  {
72  EXPECT_TRUE(filter->update(v1, v1a));
73 
74  for (int i = 1; i < length; i++)
75  {
76  EXPECT_NEAR(v1[i], v1a[i], epsilon);
77  }
78  }
79 }
80 
81 TEST(MultiChannelMeanFilterDouble, ThreeRows)
82 {
83  double epsilon = 1e-6;
84  int length = 5;
85  int rows = 5;
86 
88  EXPECT_TRUE(filter->configure(rows, "MultiChannelMeanFilterDouble5"));
89 
90  double input1[] = {0,1,2,3,4};
91  std::vector<double> v1 (input1, input1 + sizeof(input1) / sizeof(double));
92  double input2[] = {1,2,3,4,5};
93  std::vector<double> v2 (input2, input2 + sizeof(input2) / sizeof(double));
94  double input3[] = {2,3,4,5,6};
95  std::vector<double> v3 (input3, input3 + sizeof(input3) / sizeof(double));
96  double input1a[] = {1,2,3,4,5};
97  std::vector<double> v1a (input1a, input1a + sizeof(input1a) / sizeof(double));
98 
99 
100  EXPECT_TRUE(filter->update(v1, v1a));
101  EXPECT_TRUE(filter->update(v2, v1a));
102  EXPECT_TRUE(filter->update(v3, v1a));
103 
104  for (int i = 1; i < length; i++)
105  {
106  EXPECT_NEAR(v2[i], v1a[i], epsilon);
107  }
108 
109 }
110 
111 TEST(MeanFilterDouble, ConfirmIdentityNRows)
112 {
113  double epsilon = 1e-6;
114  int length = 5;
115  int rows = 5;
116 
117  FilterBase<double > * filter = new MeanFilter<double> ();
118  EXPECT_TRUE(filter->configure("MeanFilterDouble5"));
119 
120  double input = 1;
121  double output = 0;
122 
123 
124  for (int32_t i =0; i < rows*10; i++)
125  {
126  EXPECT_TRUE(filter->update(input, output));
127 
128  for (int i = 1; i < length; i++)
129  {
130  EXPECT_NEAR(input, output, epsilon);
131  }
132  }
133 }
134 
135 TEST(MeanFilterDouble, ThreeRows)
136 {
137  double epsilon = 1e-6;
138 
139  FilterBase<double > * filter = new MeanFilter<double> ();
140  EXPECT_TRUE(filter->configure("MeanFilterDouble5"));
141 
142  double input1 = 0;
143  double input2 =1;
144  double input3 = 2;
145  double output = 3;
146 
147 
148  EXPECT_TRUE(filter->update(input1, output));
149  EXPECT_NEAR(input1, output, epsilon);
150  EXPECT_TRUE(filter->update(input2, output));
151  EXPECT_NEAR((input1+ input2)/2.0, output, epsilon);
152  EXPECT_TRUE(filter->update(input3, output));
153  EXPECT_NEAR((input1 + input2 + input3)/3, output, epsilon);
154 
155 
156 }
157 
158 
159 int main(int argc, char **argv){
160  testing::InitGoogleTest(&argc, argv);
161  ros::init(argc, argv, "test_mean");
162  return RUN_ALL_TESTS();
163 }
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)
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...
TEST(MultiChannelMeanFilterDouble, ConfirmIdentityNRows)
Definition: test_mean.cpp:55
A mean filter which works on double arrays.
Definition: mean.h:134
void seed_rand()
Definition: test_mean.cpp:36
void generate_rand_vectors(double scale, uint64_t runs, std::vector< double > &xvalues, std::vector< double > &yvalues, std::vector< double > &zvalues)
Definition: test_mean.cpp:44
A mean filter which works on doubles.
Definition: mean.h:51
int main(int argc, char **argv)
Definition: test_mean.cpp:159


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