test_dynamic_parameters.cpp
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2020, Southwest Research Institute® (SwRI®)
4 // All rights reserved.
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
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 Southwest Research Institute® (SwRI®) nor the
14 // names of its contributors may be used to endorse or promote products
15 // derived from 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 SOUTHWEST RESEARCH INSTITUTE BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //
28 // *****************************************************************************
29 
30 #include <gtest/gtest.h>
31 
32 #include <ros/ros.h>
33 
34 #include <dynamic_reconfigure/IntParameter.h>
35 #include <dynamic_reconfigure/Reconfigure.h>
36 #include <dynamic_reconfigure/ConfigDescription.h>
37 
38 #include <yaml-cpp/yaml.h>
39 
44 void checkValues(const dynamic_reconfigure::ReconfigureResponse& srv_resp, int int_value, double double_value, std::string string_value, bool bool_value)
45 {
46  bool got_int = false;
47  ASSERT_EQ(srv_resp.config.ints.size(), 1);
48  for (auto& value : srv_resp.config.ints)
49  {
50  if (value.name == "test_int")
51  {
52  ASSERT_EQ(value.value, int_value);
53  got_int = true;
54  }
55  }
56  ASSERT_TRUE(got_int);
57 
58  bool got_str = false;
59  ASSERT_EQ(srv_resp.config.strs.size(), 1);
60  for (auto& value : srv_resp.config.strs)
61  {
62  if (value.name == "test_string")
63  {
64  ASSERT_EQ(value.value, string_value);
65  got_str = true;
66  }
67  }
68  ASSERT_TRUE(got_str);
69 
70  bool got_bool = false;
71  ASSERT_EQ(srv_resp.config.bools.size(), 1);
72  for (auto& value : srv_resp.config.bools)
73  {
74  if (value.name == "test_bool")
75  {
76  ASSERT_EQ(value.value, bool_value);
77  got_bool = true;
78  }
79  }
80  ASSERT_TRUE(got_bool);
81 
82  bool got_double = false;
83  bool got_float = false;
84  ASSERT_EQ(srv_resp.config.doubles.size(), 2);
85  for (auto& value : srv_resp.config.doubles)
86  {
87  if (value.name == "test_double")
88  {
89  ASSERT_DOUBLE_EQ(value.value, double_value);
90  got_double = true;
91  }
92  if (value.name == "test_float")
93  {
94  got_float = true;
95  }
96  }
97  ASSERT_TRUE(got_double);
98  ASSERT_TRUE(got_float);
99 }
100 
108 TEST(DynamicParameters, testGetAndSetParams)
109 {
110  ros::NodeHandle nh;
111  dynamic_reconfigure::ReconfigureRequest srv_req;
112  dynamic_reconfigure::ReconfigureResponse srv_resp;
113 
114  ros::ServiceClient client =
115  nh.serviceClient<dynamic_reconfigure::Reconfigure>("/dynamic_parameters_test/set_parameters");
116  bool result = client.waitForExistence(ros::Duration(5.0));
117  ASSERT_TRUE(result);
118  result = client.call(srv_req, srv_resp);
119  ASSERT_TRUE(result);
120 
121  checkValues(srv_resp, 0, 0.0, "", false);
122 
123  dynamic_reconfigure::Config config = srv_resp.config;
124  config.doubles[0].value = 1.0;
125  config.ints[0].value = 2;
126  config.strs[0].value = "test";
127  config.bools[0].value = true;
128 
129  srv_req.config = config;
130  result = client.call(srv_req, srv_resp);
131  ASSERT_TRUE(result);
132 
133  checkValues(srv_resp, 2, 1.0, "test", true);
134 }
135 
139 TEST(DynamicParameters, testParamDescriptions)
140 {
141  ros::NodeHandle nh("~");
142  bool got_description = false;
143  dynamic_reconfigure::ConfigDescription desc;
144 
145  ros::Subscriber sub = nh.subscribe<dynamic_reconfigure::ConfigDescription>(
146  "/dynamic_parameters_test/parameter_descriptions",
147  1,
148  [&got_description, &desc](const dynamic_reconfigure::ConfigDescriptionConstPtr& msg) {
149  got_description = true;
150  desc = *msg;
151  });
152 
153  ros::Rate rate(10);
155  while (!got_description && ros::Time::now() - start < ros::Duration(5))
156  {
157  ros::spinOnce();
158  rate.sleep();
159  }
160 
161  ASSERT_TRUE(got_description);
162 
163  bool got_edit_method = false;
164  ASSERT_EQ(desc.groups.size(), 1);
165  for (const auto& group : desc.groups)
166  {
167  ASSERT_EQ(group.name, "Default");
168  ASSERT_EQ(group.parameters.size(), 5);
169  for (const auto& param : group.parameters)
170  {
171  if (param.name == "test_int" && !param.edit_method.empty())
172  {
173  got_edit_method = true;
174  YAML::Node node = YAML::Load(param.edit_method);
175  ASSERT_TRUE(node.IsMap());
176  ASSERT_TRUE(node["enum_description"]);
177  ASSERT_TRUE(node["enum"]);
178  YAML::Node enums = node["enum"];
179  ASSERT_EQ(enums.size(), 4);
180  YAML::Node first = enums[0];
181  ASSERT_EQ(first["srcline"].as<int>(), 0);
182  ASSERT_EQ(first["description"].as<std::string>(), "Unknown");
183  ASSERT_EQ(first["srcfile"].as<std::string>(), "dynamic_parameters.h");
184  ASSERT_EQ(first["cconsttype"].as<std::string>(), "const int");
185  ASSERT_EQ(first["value"].as<int>(), 1);
186  ASSERT_EQ(first["ctype"].as<std::string>(), "int");
187  ASSERT_EQ(first["type"].as<std::string>(), "int");
188  ASSERT_EQ(first["name"].as<std::string>(), "First");
189  first = enums[1];
190  ASSERT_EQ(first["srcline"].as<int>(), 0);
191  ASSERT_EQ(first["description"].as<std::string>(), "Unknown");
192  ASSERT_EQ(first["srcfile"].as<std::string>(), "dynamic_parameters.h");
193  ASSERT_EQ(first["cconsttype"].as<std::string>(), "const int");
194  ASSERT_EQ(first["value"].as<int>(), 2);
195  ASSERT_EQ(first["ctype"].as<std::string>(), "int");
196  ASSERT_EQ(first["type"].as<std::string>(), "int");
197  ASSERT_EQ(first["name"].as<std::string>(), "Second");
198  }
199  }
200  }
201  ASSERT_TRUE(got_edit_method);
202 }
203 
204 int main(int argc, char **argv)
205 {
206  ros::init(argc, argv, "dynamic_parameters_test");
207  testing::InitGoogleTest(&argc, argv);
208 
209  ros::start();
210  int result = RUN_ALL_TESTS();
211  ros::shutdown();
212 
213  return result;
214 }
msg
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
int main(int argc, char **argv)
ROSCPP_DECL void start()
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
static void param(const ros::NodeHandle &nh, const std::string &name, int &variable, const int default_value)
Definition: parameters.h:102
TEST(DynamicParameters, testGetAndSetParams)
static Time now()
ROSCPP_DECL void shutdown()
void checkValues(const dynamic_reconfigure::ReconfigureResponse &srv_resp, int int_value, double double_value, std::string string_value, bool bool_value)
ROSCPP_DECL void spinOnce()


swri_roscpp
Author(s):
autogenerated on Tue Apr 6 2021 02:50:35