test_mean.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <gtest/gtest.h>
00031 #include <sys/time.h>
00032 #include "filters/mean.h"
00033 
00034 using namespace filters ;
00035 
00036 void seed_rand()
00037 {
00038   //Seed random number generator with current microseond count
00039   timeval temp_time_struct;
00040   gettimeofday(&temp_time_struct,NULL);
00041   srand(temp_time_struct.tv_usec);
00042 };
00043 
00044 void generate_rand_vectors(double scale, uint64_t runs, std::vector<double>& xvalues, std::vector<double>& yvalues, std::vector<double>&zvalues)
00045 {
00046   seed_rand();
00047   for ( uint64_t i = 0; i < runs ; i++ )
00048   {
00049     xvalues[i] = 1.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
00050     yvalues[i] = 1.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
00051     zvalues[i] = 1.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
00052   }
00053 }
00054 
00055 TEST(MultiChannelMeanFilterDouble, ConfirmIdentityNRows)
00056 {
00057   double epsilon = 1e-6;
00058   int length = 5;
00059   int rows = 5;
00060   
00061   MultiChannelFilterBase<double > * filter = new MultiChannelMeanFilter<double>  ();
00062   EXPECT_TRUE(filter->configure(rows, "MultiChannelMeanFilterDouble5"));
00063 
00064   double input1[] = {1,2,3,4,5};
00065   double input1a[] = {1,2,3,4,5};
00066   std::vector<double> v1 (input1, input1 + sizeof(input1) / sizeof(double));
00067   std::vector<double> v1a (input1a, input1a + sizeof(input1a) / sizeof(double));
00068 
00069 
00070   for (int32_t i =0; i < rows*10; i++)
00071   {
00072     EXPECT_TRUE(filter->update(v1, v1a));
00073 
00074     for (int i = 1; i < length; i++)
00075     {
00076       EXPECT_NEAR(v1[i], v1a[i], epsilon);
00077     }
00078   }
00079 }
00080 
00081 TEST(MultiChannelMeanFilterDouble, ThreeRows)
00082 {
00083   double epsilon = 1e-6;
00084   int length = 5;
00085   int rows = 5;
00086   
00087   MultiChannelFilterBase<double > * filter = new MultiChannelMeanFilter<double> ();
00088   EXPECT_TRUE(filter->configure(rows, "MultiChannelMeanFilterDouble5"));
00089 
00090   double input1[] = {0,1,2,3,4};
00091   std::vector<double> v1 (input1, input1 + sizeof(input1) / sizeof(double));
00092   double input2[] = {1,2,3,4,5};
00093   std::vector<double> v2 (input2, input2 + sizeof(input2) / sizeof(double));
00094   double input3[] = {2,3,4,5,6};
00095   std::vector<double> v3 (input3, input3 + sizeof(input3) / sizeof(double));
00096   double input1a[] = {1,2,3,4,5};
00097   std::vector<double> v1a (input1a, input1a + sizeof(input1a) / sizeof(double));
00098 
00099 
00100   EXPECT_TRUE(filter->update(v1, v1a));
00101   EXPECT_TRUE(filter->update(v2, v1a));
00102   EXPECT_TRUE(filter->update(v3, v1a));
00103 
00104   for (int i = 1; i < length; i++)
00105   {
00106     EXPECT_NEAR(v2[i], v1a[i], epsilon);
00107   }
00108 
00109 }
00110 
00111 TEST(MeanFilterDouble, ConfirmIdentityNRows)
00112 {
00113   double epsilon = 1e-6;
00114   int length = 5;
00115   int rows = 5;
00116   
00117   FilterBase<double > * filter = new MeanFilter<double>  ();
00118   EXPECT_TRUE(filter->configure("MeanFilterDouble5"));
00119 
00120   double input = 1;
00121   double output = 0;
00122 
00123 
00124   for (int32_t i =0; i < rows*10; i++)
00125   {
00126     EXPECT_TRUE(filter->update(input, output));
00127     
00128     for (int i = 1; i < length; i++)
00129     {
00130       EXPECT_NEAR(input, output, epsilon);
00131     }
00132   }
00133 }
00134 
00135 TEST(MeanFilterDouble, ThreeRows)
00136 {
00137   double epsilon = 1e-6;
00138   
00139   FilterBase<double > * filter = new MeanFilter<double> ();
00140   EXPECT_TRUE(filter->configure("MeanFilterDouble5"));
00141 
00142   double input1 = 0;
00143   double input2 =1;
00144   double input3 = 2;
00145   double output = 3;
00146 
00147 
00148   EXPECT_TRUE(filter->update(input1, output));
00149   EXPECT_NEAR(input1, output, epsilon);
00150   EXPECT_TRUE(filter->update(input2, output));
00151   EXPECT_NEAR((input1+ input2)/2.0, output, epsilon);
00152   EXPECT_TRUE(filter->update(input3, output));
00153   EXPECT_NEAR((input1 + input2 + input3)/3, output, epsilon);
00154 
00155 
00156 }
00157 
00158 
00159 int main(int argc, char **argv){
00160   testing::InitGoogleTest(&argc, argv);
00161   ros::init(argc, argv, "test_mean");
00162   return RUN_ALL_TESTS();
00163 }


filters
Author(s):
autogenerated on Sat Jun 8 2019 19:38:00