test_rosparam.cpp
Go to the documentation of this file.
1 // Unit tests for rosparam tag
2 // Author: Max Schwarz <max.schwarz@ais.uni-bonn.de>
3 
4 #include <catch_ros/catch.hpp>
5 
6 #include "../../src/launch/launch_config.h"
7 
8 #include "core_utils.h"
9 #include "param_utils.h"
10 
11 using namespace rosmon::launch;
12 
13 TEST_CASE("rosparam basic", "[rosparam]")
14 {
15  LaunchConfig config;
16  config.parseString(R"EOF(
17  <launch>
18 <rosparam>
19 test_ns:
20  param1: true
21  param2: hello
22  param3: 3
23  param4: 10.0
24  param5: "3"
25 </rosparam>
26  </launch>
27  )EOF");
28 
29  config.evaluateParameters();
30 
31  CAPTURE(config.parameters());
32 
33  auto& params = config.parameters();
34  checkTypedParam<bool>(params, "/test_ns/param1", XmlRpc::XmlRpcValue::TypeBoolean, true);
35  checkTypedParam<std::string>(params, "/test_ns/param2", XmlRpc::XmlRpcValue::TypeString, "hello");
36  checkTypedParam<int>(params, "/test_ns/param3", XmlRpc::XmlRpcValue::TypeInt, 3);
37  checkTypedParam<double>(params, "/test_ns/param4", XmlRpc::XmlRpcValue::TypeDouble, 10.0);
38  checkTypedParam<std::string>(params, "/test_ns/param5", XmlRpc::XmlRpcValue::TypeString, "3");
39 }
40 
41 TEST_CASE("rosparam empty", "[rosparam]")
42 {
43  LaunchConfig config;
44  config.parseString(R"EOF(
45  <launch>
46 <rosparam>
47 </rosparam>
48 
49  <rosparam command="load" file="$(find rosmon_core)/test/empty.yaml" />
50  </launch>
51  )EOF");
52 }
53 
54 TEST_CASE("rosparam invalid YAML", "[rosparam]")
55 {
57  <launch>
58 <rosparam>
59 hello: {{ invalid }} test
60 </rosparam>
61  </launch>
62  )EOF");
63 }
64 
65 TEST_CASE("rosparam naming", "[rosparam]")
66 {
67  LaunchConfig config;
68  config.parseString(R"EOF(
69  <launch>
70  <rosparam param="a_list">[1, 2, 3, 4]</rosparam>
71 
72  <arg name="whitelist" default="[3, 2]"/>
73  <rosparam param="whitelist" subst_value="True">$(arg whitelist)</rosparam>
74 
75 <rosparam ns="namespace">
76 a: false
77 </rosparam>
78  </launch>
79  )EOF");
80 
81  config.evaluateParameters();
82 
83  CAPTURE(config.parameters());
84 
85  {
86  INFO("looking for: a_list");
87 
88  auto it = config.parameters().find("/a_list");
89  REQUIRE(it != config.parameters().end());
90 
91  auto value = it->second;
92 
93  REQUIRE(value.getType() == XmlRpc::XmlRpcValue::TypeArray);
94  REQUIRE(value.size() == 4);
95  }
96 
97  {
98  INFO("looking for: whitelist");
99 
100  auto it = config.parameters().find("/whitelist");
101  REQUIRE(it != config.parameters().end());
102 
103  auto value = it->second;
104 
105  REQUIRE(value.getType() == XmlRpc::XmlRpcValue::TypeArray);
106  REQUIRE(value.size() == 2);
107  }
108 
109  checkTypedParam<bool>(config.parameters(), "/namespace/a", XmlRpc::XmlRpcValue::TypeBoolean, false);
110 }
111 
112 TEST_CASE("rosparam explicit types", "[rosparam]")
113 {
114  LaunchConfig config;
115  config.parseString(R"EOF(
116  <launch>
117 <rosparam>
118 test_ns:
119  param1: !!str 1
120  param2: !!float 1
121  param3: !!binary "aGVsbG8K"
122 </rosparam>
123  </launch>
124  )EOF");
125 
126  config.evaluateParameters();
127 
128  CAPTURE(config.parameters());
129 
130  auto& params = config.parameters();
131  checkTypedParam<std::string>(params, "/test_ns/param1", XmlRpc::XmlRpcValue::TypeString, "1");
132  checkTypedParam<double>(params, "/test_ns/param2", XmlRpc::XmlRpcValue::TypeDouble, 1.0);
133 
134  auto binParam = getTypedParam<XmlRpc::XmlRpcValue::BinaryData>(params, "/test_ns/param3", XmlRpc::XmlRpcValue::TypeBase64);
135  XmlRpc::XmlRpcValue::BinaryData expected{'h', 'e', 'l', 'l', 'o', '\n'};
136  CHECK(binParam == expected);
137 }
138 
139 TEST_CASE("rosparam angle extensions", "[rosparam]")
140 {
141  LaunchConfig config;
142  config.parseString(R"EOF(
143  <launch>
144 <rosparam>
145 test_ns:
146  param1: rad(2*pi)
147  param2: deg(180)
148  param3: !degrees 181.0
149  param4: !radians 3.14169
150 </rosparam>
151  </launch>
152  )EOF");
153 
154  config.evaluateParameters();
155 
156  CAPTURE(config.parameters());
157 
158  auto& params = config.parameters();
159 
160  double param1 = getTypedParam<double>(params, "/test_ns/param1", XmlRpc::XmlRpcValue::TypeDouble);
161  CHECK(param1 == Approx(2.0 * M_PI));
162 
163  double param2 = getTypedParam<double>(params, "/test_ns/param2", XmlRpc::XmlRpcValue::TypeDouble);
164  CHECK(param2 == Approx(180.0 * M_PI / 180.0));
165 
166  double param3 = getTypedParam<double>(params, "/test_ns/param3", XmlRpc::XmlRpcValue::TypeDouble);
167  CHECK(param3 == Approx(181.0 * M_PI / 180.0));
168 
169  double param4 = getTypedParam<double>(params, "/test_ns/param4", XmlRpc::XmlRpcValue::TypeDouble);
170  CHECK(param4 == Approx(3.14169));
171 }
172 
173 TEST_CASE("merge keys", "[rosparam]")
174 {
175  LaunchConfig config;
176  config.parseString(R"EOF(
177  <launch>
178 <rosparam>
179 common: &amp;common
180  param1: true
181  param2: 5.0
182  param3: hello
183 commonclass: &amp;commonclass
184  testclass:
185  &lt;&lt;: *common
186  testparam: 140
187 class1:
188  &lt;&lt;: *common
189  param4: 514
190 class2:
191  param1: false
192  &lt;&lt;: *common
193 class3:
194  &lt;&lt;: *common
195  param1: false
196 class4:
197  &lt;&lt;: *common
198  param1: 5
199  param2: test
200  param3: 0.1
201 class5:
202  &lt;&lt;: *commonclass
203  param4: sub
204 class6:
205  &lt;&lt;: *commonclass
206  testclass:
207  param2: 10.0
208 </rosparam>
209  </launch>
210  )EOF");
211 
212  config.evaluateParameters();
213 
214  CAPTURE(config.parameters());
215 
216  auto& params = config.parameters();
217 
218  // Class 1 test simple addition
219  std::string class_ns = "/class1";
220  checkTypedParam<bool>(params, class_ns + "/param1", XmlRpc::XmlRpcValue::TypeBoolean, true);
221  checkTypedParam<double>(params, class_ns + "/param2", XmlRpc::XmlRpcValue::TypeDouble, 5.0);
222  checkTypedParam<std::string>(params, class_ns + "/param3", XmlRpc::XmlRpcValue::TypeString, "hello");
223  checkTypedParam<int>(params, class_ns + "/param4", XmlRpc::XmlRpcValue::TypeInt, 514);
224 
225  // Class 2 test override pre-assigned
226  class_ns = "/class2";
227  checkTypedParam<bool>(params, class_ns + "/param1", XmlRpc::XmlRpcValue::TypeBoolean, false);
228  checkTypedParam<double>(params, class_ns + "/param2", XmlRpc::XmlRpcValue::TypeDouble, 5.0);
229  checkTypedParam<std::string>(params, class_ns + "/param3", XmlRpc::XmlRpcValue::TypeString, "hello");
230 
231  // Class 3 test override post-assigned
232  class_ns = "/class3";
233  checkTypedParam<bool>(params, class_ns + "/param1", XmlRpc::XmlRpcValue::TypeBoolean, false);
234  checkTypedParam<double>(params, class_ns + "/param2", XmlRpc::XmlRpcValue::TypeDouble, 5.0);
235  checkTypedParam<std::string>(params, class_ns + "/param3", XmlRpc::XmlRpcValue::TypeString, "hello");
236 
237  // Class 4 test typechange overrides
238  class_ns = "/class4";
239  checkTypedParam<int>(params, class_ns + "/param1", XmlRpc::XmlRpcValue::TypeInt, 5);
240  checkTypedParam<std::string>(params, class_ns + "/param2", XmlRpc::XmlRpcValue::TypeString, "test");
241  checkTypedParam<double>(params, class_ns + "/param3", XmlRpc::XmlRpcValue::TypeDouble, 0.1);
242 
243  // Class 5 test nested merge
244  class_ns = "/class5";
245  checkTypedParam<bool>(params, class_ns + "/testclass/param1", XmlRpc::XmlRpcValue::TypeBoolean, true);
246  checkTypedParam<double>(params, class_ns + "/testclass/param2", XmlRpc::XmlRpcValue::TypeDouble, 5.0);
247  checkTypedParam<std::string>(params, class_ns + "/testclass/param3", XmlRpc::XmlRpcValue::TypeString, "hello");
248  checkTypedParam<int>(params, class_ns + "/testclass/testparam", XmlRpc::XmlRpcValue::TypeInt, 140);
249  checkTypedParam<std::string>(params, class_ns + "/param4", XmlRpc::XmlRpcValue::TypeString, "sub");
250 
251  // Class 6 test override on nested merge
252  class_ns = "/class6";
253  checkTypedParam<bool>(params, class_ns + "/testclass/param1", XmlRpc::XmlRpcValue::TypeBoolean, true);
254  checkTypedParam<double>(params, class_ns + "/testclass/param2", XmlRpc::XmlRpcValue::TypeDouble, 10.0);
255  checkTypedParam<std::string>(params, class_ns + "/testclass/param3", XmlRpc::XmlRpcValue::TypeString, "hello");
256  checkTypedParam<int>(params, class_ns + "/testclass/testparam", XmlRpc::XmlRpcValue::TypeInt, 140);
257 }
258 
259 TEST_CASE("rosparam /param", "[rosparam]")
260 {
261  LaunchConfig config;
262  config.parseString(R"EOF(
263  <launch>
264 <rosparam ns="ns">
265 /fake_param: 20.0
266 namespace:
267  /other_param: 10.0
268  /global_ns:
269  third_param: 5.0
270 </rosparam>
271  </launch>
272  )EOF");
273 
274  config.evaluateParameters();
275 
276  CAPTURE(config.parameters());
277 
278  auto& params = config.parameters();
279 
280  double param1 = getTypedParam<double>(params, "/fake_param", XmlRpc::XmlRpcValue::TypeDouble);
281  CHECK(param1 == Approx(20.0));
282 
283  double param2 = getTypedParam<double>(params, "/other_param", XmlRpc::XmlRpcValue::TypeDouble);
284  CHECK(param2 == Approx(10.0));
285 
286  double param3 = getTypedParam<double>(params, "/global_ns/third_param", XmlRpc::XmlRpcValue::TypeDouble);
287  CHECK(param3 == Approx(5.0));
288 }
auto & params
Definition: test_param.cpp:226
const std::map< std::string, XmlRpc::XmlRpcValue > & parameters() const
static void requireParsingException(const std::string &input)
Definition: core_utils.h:11
void parseString(const std::string &input, bool onlyArguments=false)
std::vector< char > BinaryData
TEST_CASE("rosparam basic","[rosparam]")


rosmon_core
Author(s): Max Schwarz
autogenerated on Sat Jan 9 2021 03:35:43