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.hpp"
34 
35 using namespace filters ;
36 
37 TEST(MultiChannelMedianFilterDouble, ConfirmIdentityNRows)
38 {
39  double epsilon = 1e-6;
40  int length = 5;
41  int rows = 5;
42 
44  EXPECT_TRUE(filter->configure(rows, "MultiChannelMedianFilterDouble5"));
45 
46 
47  double input1[] = {1,2,3,4,5};
48  double input1a[] = {11,12,13,14,15};
49  std::vector<double> v1 (input1, input1 + sizeof(input1) / sizeof(double));
50  std::vector<double> v1a (input1a, input1a + sizeof(input1a) / sizeof(double));
51 
52  for (int i =0; i < rows*10; i++)
53  {
54  EXPECT_TRUE(filter->update(v1, v1a));
55 
56  for (int j = 1; j < length; j++)
57  {
58  EXPECT_NEAR(input1[j], v1a[j], epsilon);
59  }
60  }
61 
62  delete filter;
63 }
64 
65 TEST(MultiChannelMedianFilterDouble, ThreeRows)
66 {
67  double epsilon = 1e-6;
68  int length = 5;
69  int rows = 5;
70 
72  EXPECT_TRUE(filter->configure(rows, "MultiChannelMedianFilterDouble5" ));
73 
74  double input1[] = {0,1,2,3,4};
75  std::vector<double> v1 (input1, input1 + sizeof(input1) / sizeof(double));
76  double input2[] = {1,2,3,4,5};
77  std::vector<double> v2 (input2, input2 + sizeof(input2) / sizeof(double));
78  double input3[] = {2,3,4,5,6};
79  std::vector<double> v3 (input3, input3 + sizeof(input3) / sizeof(double));
80  double input1a[] = {1,2,3,4,5};
81  std::vector<double> v1a (input1a, input1a + sizeof(input1a) / sizeof(double));
82 
83  EXPECT_TRUE(filter->update(v1, v1a));
84  EXPECT_TRUE(filter->update(v2, v1a));
85  EXPECT_TRUE(filter->update(v3, v1a));
86 
87  for (int i = 1; i < length; i++)
88  {
89  EXPECT_NEAR(v2[i], v1a[i], epsilon);
90  }
91 
92 }
93 
94 TEST(MultiChannelMedianFilterFloat, ConfirmIdentityNRows)
95 {
96  float epsilon = 1e-6;
97  int length = 5;
98  int rows = 5;
99 
101  EXPECT_TRUE(filter->configure(rows, "MultiChannelMedianFilterFloat5" ));
102 
103  float input1[] = {1,2,3,4,5};
104  float input1a[] = {1,2,3,4,5};
105  std::vector<float> v1 (input1, input1 + sizeof(input1) / sizeof(float));
106  std::vector<float> v1a (input1a, input1a + sizeof(input1a) / sizeof(float));
107 
108  for (int i =0; i < rows*10; i++)
109  {
110  EXPECT_TRUE(filter->update(v1, v1a));
111 
112  for (int j = 1; j < length; j++)
113  {
114  EXPECT_NEAR(input1[j], v1a[j], epsilon);
115  }
116  }
117 
118  delete filter;
119 }
120 
121 TEST(MultiChannelMedianFilterFloat, ThreeRows)
122 {
123  float epsilon = 1e-6;
124  int length = 5;
125  int rows = 5;
126 
128  EXPECT_TRUE(filter->configure(rows, "MultiChannelMedianFilterFloat5"));
129 
130  float input1[] = {0,1,2,3,4};
131  std::vector<float> v1 (input1, input1 + sizeof(input1) / sizeof(float));
132  float input2[] = {1,2,3,4,5};
133  std::vector<float> v2 (input2, input2 + sizeof(input2) / sizeof(float));
134  float input3[] = {2,3,4,5,6};
135  std::vector<float> v3 (input3, input3 + sizeof(input3) / sizeof(float));
136  float input1a[] = {1,2,3,4,5};
137  std::vector<float> v1a (input1a, input1a + sizeof(input1a) / sizeof(float));
138 
139  EXPECT_TRUE(filter->update(v1, v1a));
140  EXPECT_TRUE(filter->update(v2, v1a));
141  EXPECT_TRUE(filter->update(v3, v1a));
142 
143  for (int i = 1; i < length; i++)
144  {
145  EXPECT_NEAR(v2[i], v1a[i], epsilon);
146  }
147 
148 }
149 
150 
151 int main(int argc, char **argv){
152  testing::InitGoogleTest(&argc, argv);
153  ros::init(argc, argv, "test_median");
154  return RUN_ALL_TESTS();
155 }
epsilon
double epsilon
filters
Definition: filter_base.hpp:38
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::MultiChannelMedianFilter
A median filter which works on arrays.
Definition: median.hpp:181
filters::MultiChannelFilterBase
Definition: filter_base.hpp:380
median.hpp
TEST
TEST(MultiChannelMedianFilterDouble, ConfirmIdentityNRows)
Definition: test_median.cpp:37
main
int main(int argc, char **argv)
Definition: test_median.cpp:151


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