$search
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/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 }