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.hpp"
33 
34 using namespace filters ;
35 
36 TEST(MultiChannelMeanFilterDouble, ConfirmIdentityNRows)
37 {
38  double epsilon = 1e-6;
39  int length = 5;
40  int rows = 5;
41 
43  EXPECT_TRUE(filter->configure(rows, "MultiChannelMeanFilterDouble5"));
44 
45  double input1[] = {1,2,3,4,5};
46  double input1a[] = {1,2,3,4,5};
47  std::vector<double> v1 (input1, input1 + sizeof(input1) / sizeof(double));
48  std::vector<double> v1a (input1a, input1a + sizeof(input1a) / sizeof(double));
49 
50 
51  for (int32_t i =0; i < rows*10; i++)
52  {
53  EXPECT_TRUE(filter->update(v1, v1a));
54 
55  for (int i = 1; i < length; i++)
56  {
57  EXPECT_NEAR(v1[i], v1a[i], epsilon);
58  }
59  }
60 }
61 
62 TEST(MultiChannelMeanFilterDouble, ThreeRows)
63 {
64  double epsilon = 1e-6;
65  int length = 5;
66  int rows = 5;
67 
69  EXPECT_TRUE(filter->configure(rows, "MultiChannelMeanFilterDouble5"));
70 
71  double input1[] = {0,1,2,3,4};
72  std::vector<double> v1 (input1, input1 + sizeof(input1) / sizeof(double));
73  double input2[] = {1,2,3,4,5};
74  std::vector<double> v2 (input2, input2 + sizeof(input2) / sizeof(double));
75  double input3[] = {2,3,4,5,6};
76  std::vector<double> v3 (input3, input3 + sizeof(input3) / sizeof(double));
77  double input1a[] = {1,2,3,4,5};
78  std::vector<double> v1a (input1a, input1a + sizeof(input1a) / sizeof(double));
79 
80 
81  EXPECT_TRUE(filter->update(v1, v1a));
82  EXPECT_TRUE(filter->update(v2, v1a));
83  EXPECT_TRUE(filter->update(v3, v1a));
84 
85  for (int i = 1; i < length; i++)
86  {
87  EXPECT_NEAR(v2[i], v1a[i], epsilon);
88  }
89 
90 }
91 
92 TEST(MeanFilterDouble, ConfirmIdentityNRows)
93 {
94  double epsilon = 1e-6;
95  int length = 5;
96  int rows = 5;
97 
98  FilterBase<double > * filter = new MeanFilter<double> ();
99  EXPECT_TRUE(filter->configure("MeanFilterDouble5"));
100 
101  double input = 1;
102  double output = 0;
103 
104 
105  for (int32_t i =0; i < rows*10; i++)
106  {
107  EXPECT_TRUE(filter->update(input, output));
108 
109  for (int i = 1; i < length; i++)
110  {
111  EXPECT_NEAR(input, output, epsilon);
112  }
113  }
114 }
115 
116 TEST(MeanFilterDouble, ThreeRows)
117 {
118  double epsilon = 1e-6;
119 
120  FilterBase<double > * filter = new MeanFilter<double> ();
121  EXPECT_TRUE(filter->configure("MeanFilterDouble5"));
122 
123  double input1 = 0;
124  double input2 =1;
125  double input3 = 2;
126  double output = 3;
127 
128 
129  EXPECT_TRUE(filter->update(input1, output));
130  EXPECT_NEAR(input1, output, epsilon);
131  EXPECT_TRUE(filter->update(input2, output));
132  EXPECT_NEAR((input1+ input2)/2.0, output, epsilon);
133  EXPECT_TRUE(filter->update(input3, output));
134  EXPECT_NEAR((input1 + input2 + input3)/3, output, epsilon);
135 
136 
137 }
138 
139 
140 int main(int argc, char **argv){
141  testing::InitGoogleTest(&argc, argv);
142  ros::init(argc, argv, "test_mean");
143  return RUN_ALL_TESTS();
144 }
filters::FilterBase
A Base filter class to provide a standard interface for all filters.
Definition: filter_base.hpp:47
epsilon
double epsilon
filters::FilterBase::configure
bool configure(const std::string &param_name, ros::NodeHandle node_handle=ros::NodeHandle())
Configure the filter from the parameter server.
Definition: filter_base.hpp:62
filters
Definition: filter_base.hpp:38
TEST
TEST(MultiChannelMeanFilterDouble, ConfirmIdentityNRows)
Definition: test_mean.cpp:36
filters::MultiChannelFilterBase::configure
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.hpp:390
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
filters::MultiChannelFilterBase::update
virtual bool update(const std::vector< T > &data_in, std::vector< T > &data_out)=0
Update the filter and return the data seperately.
filters::FilterBase::update
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...
main
int main(int argc, char **argv)
Definition: test_mean.cpp:140
filters::MultiChannelFilterBase
Definition: filter_base.hpp:380
filters::MultiChannelMeanFilter
A mean filter which works on double arrays.
Definition: mean.hpp:134
filters::MeanFilter
A mean filter which works on doubles.
Definition: mean.hpp:51
mean.hpp


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