00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <gtest/gtest.h>
00031 #include <sys/time.h>
00032 #include "filters/param_test.h"
00033
00034 using namespace filters ;
00035
00036
00037
00038 TEST(Parameters, Double)
00039 {
00040 ros::NodeHandle nh;
00041 double epsilon = 1e-6;
00042
00043 FilterBase<double > * filter = new ParamTest<double> ();
00044 EXPECT_TRUE(filter->configure("TestDouble", nh));
00045 double out;
00046 filter -> update(out, out);
00047 EXPECT_NEAR(4, out, epsilon);
00048 }
00049
00050 TEST(Parameters, Int)
00051 {
00052 ros::NodeHandle nh;
00053
00054 FilterBase<int> * filter = new ParamTest<int> ();
00055 EXPECT_TRUE(filter->configure("TestInt", nh));
00056 int out;
00057 filter -> update(out, out);
00058 EXPECT_EQ(4, out);
00059 }
00060
00061 TEST(Parameters, UInt)
00062 {
00063 ros::NodeHandle nh;
00064
00065 FilterBase<unsigned int> * filter = new ParamTest<unsigned int> ();
00066 EXPECT_TRUE(filter->configure("TestUInt", nh));
00067 unsigned int out;
00068 filter -> update(out, out);
00069 EXPECT_EQ(4, out);
00070 }
00071
00072 TEST(Parameters, String)
00073 {
00074 ros::NodeHandle nh;
00075
00076 FilterBase<std::string> * filter = new ParamTest<std::string> ();
00077 EXPECT_TRUE(filter->configure("TestString", nh));
00078 std::string out;
00079 filter -> update(out, out);
00080 EXPECT_STREQ("four", out.c_str());
00081 }
00082
00083 TEST(Parameters, DoubleVector)
00084 {
00085 ros::NodeHandle nh;
00086 double epsilon = 1e-6;
00087
00088 FilterBase<std::vector<double> > * filter = new ParamTest<std::vector<double> > ();
00089 EXPECT_TRUE(filter->configure("TestDoubleVector", nh));
00090 std::vector<double> out;
00091 filter -> update(out, out);
00092 for (std::vector<double>::iterator it = out.begin(); it != out.end(); ++it)
00093 {
00094 EXPECT_NEAR(4, *it, epsilon);
00095 }
00096 }
00097
00098 TEST(Parameters, StringVector)
00099 {
00100 ros::NodeHandle nh;
00101
00102 FilterBase<std::vector<std::string> > * filter = new ParamTest<std::vector<std::string> > ();
00103 EXPECT_TRUE(filter->configure("TestStringVector", nh));
00104 std::vector<std::string> out;
00105 filter -> update(out, out);
00106 for (std::vector<std::string>::iterator it = out.begin(); it != out.end(); ++it)
00107 {
00108 EXPECT_STREQ("four", it->c_str());
00109 }
00110 }
00111
00112
00113 int main(int argc, char **argv){
00114 testing::InitGoogleTest(&argc, argv);
00115 ros::init(argc, argv, "test_mean");
00116 return RUN_ALL_TESTS();
00117 }