test/test_params.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/param_test.h"
33 
34 using namespace filters ;
35 
36 
37 
38 TEST(Parameters, Double)
39 {
40  ros::NodeHandle nh;
41  double epsilon = 1e-6;
42 
43  FilterBase<double > * filter = new ParamTest<double> ();
44  EXPECT_TRUE(filter->configure("TestDouble", nh));
45  double out;
46  filter -> update(out, out);
47  EXPECT_NEAR(4, out, epsilon);
48 }
49 
50 TEST(Parameters, Int)
51 {
52  ros::NodeHandle nh;
53 
54  FilterBase<int> * filter = new ParamTest<int> ();
55  EXPECT_TRUE(filter->configure("TestInt", nh));
56  int out;
57  filter -> update(out, out);
58  EXPECT_EQ(4, out);
59 }
60 
61 TEST(Parameters, UInt)
62 {
63  ros::NodeHandle nh;
64 
66  EXPECT_TRUE(filter->configure("TestUInt", nh));
67  unsigned int out;
68  filter -> update(out, out);
69  EXPECT_EQ(4, out);
70 }
71 
72 TEST(Parameters, String)
73 {
74  ros::NodeHandle nh;
75 
77  EXPECT_TRUE(filter->configure("TestString", nh));
78  std::string out;
79  filter -> update(out, out);
80  EXPECT_STREQ("four", out.c_str());
81 }
82 
83 TEST(Parameters, DoubleVector)
84 {
85  ros::NodeHandle nh;
86  double epsilon = 1e-6;
87 
89  EXPECT_TRUE(filter->configure("TestDoubleVector", nh));
90  std::vector<double> out;
91  filter -> update(out, out);
92  for (std::vector<double>::iterator it = out.begin(); it != out.end(); ++it)
93  {
94  EXPECT_NEAR(4, *it, epsilon);
95  }
96 }
97 
98 TEST(Parameters, StringVector)
99 {
100  ros::NodeHandle nh;
101 
103  EXPECT_TRUE(filter->configure("TestStringVector", nh));
104  std::vector<std::string> out;
105  filter -> update(out, out);
106  for (std::vector<std::string>::iterator it = out.begin(); it != out.end(); ++it)
107  {
108  EXPECT_STREQ("four", it->c_str());
109  }
110 }
111 
112 
113 int main(int argc, char **argv){
114  testing::InitGoogleTest(&argc, argv);
115  ros::init(argc, argv, "test_mean");
116  return RUN_ALL_TESTS();
117 }
bool configure(const std::string &param_name, ros::NodeHandle node_handle=ros::NodeHandle())
Configure the filter from the parameter server.
Definition: filter_base.h:65
double epsilon
TEST(Parameters, Double)
A Base filter class to provide a standard interface for all filters.
Definition: filter_base.h:50
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
A mean filter which works on doubles.
Definition: param_test.h:50
int main(int argc, char **argv)


filters
Author(s):
autogenerated on Sat Jun 8 2019 04:37:52