test_mcl_3dl_compat.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018, the mcl_3dl authors
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 copyright holder 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 <ros/ros.h>
31 
32 #include <gtest/gtest.h>
33 
35 
36 TEST(Mcl3DlCompat, ParamRename)
37 {
38  ros::NodeHandle nh;
39 
40  nh.setParam("param1", 1.0);
41  nh.setParam("param2", 2.0);
42  nh.setParam("param2_new", 3.0);
43  nh.setParam("param3_new", 4.0);
44 
45  mcl_3dl_compat::paramRename<double>(nh, "param1_new", "param1");
46  mcl_3dl_compat::paramRename<double>(nh, "param2_new", "param2");
47 
48  ASSERT_TRUE(nh.hasParam("param1_new"));
49  ASSERT_TRUE(nh.hasParam("param2_new"));
50  ASSERT_TRUE(nh.hasParam("param3_new"));
51 
52  double param1;
53  double param2;
54  double param3;
55  nh.getParam("param1_new", param1);
56  nh.getParam("param2_new", param2);
57  nh.getParam("param3_new", param3);
58 
59  // Only old parameter is provided for param1.
60  ASSERT_EQ(param1, 1.0);
61  // Both old and new paramters are provided for param2. New one must be active.
62  ASSERT_EQ(param2, 3.0);
63  // Only new paramter is provided for param3.
64  ASSERT_EQ(param3, 4.0);
65 }
66 
67 int main(int argc, char** argv)
68 {
69  testing::InitGoogleTest(&argc, argv);
70  ros::init(argc, argv, "test_mcl_3dl_compat");
71 
72  return RUN_ALL_TESTS();
73 }
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
TEST(Mcl3DlCompat, ParamRename)
int main(int argc, char **argv)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Mon Jul 8 2019 03:32:36