test_param.cpp
Go to the documentation of this file.
1 // Unit tests for <param> tags
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 "param_utils.h"
9 
10 using namespace rosmon::launch;
11 
12 TEST_CASE("global_param", "[param]")
13 {
14  LaunchConfig config;
15  config.parseString(R"EOF(
16  <launch>
17  <param name="global_param" value="hello_world" />
18  </launch>
19  )EOF");
20 
21  config.evaluateParameters();
22 
23  CAPTURE(config.parameters());
24 
25  auto it = config.parameters().find("/global_param");
26 
27  REQUIRE(it != config.parameters().end());
28 
29  XmlRpc::XmlRpcValue value = it->second;
30  REQUIRE(static_cast<std::string>(value) == "hello_world");
31 }
32 
33 TEST_CASE("param_types", "[param]")
34 {
35  LaunchConfig config;
36  config.parseString(R"EOF(
37  <launch>
38  <param name="int_param_auto" value="0" />
39  <param name="int_param_forced" value="0" type="int" />
40 
41  <param name="double_param_auto" value="0.0" />
42  <param name="double_param_forced" value="0" type="double" />
43 
44  <param name="str_param_auto" value="hello" />
45  <param name="str_param_forced" value="0" type="str" />
46 
47  <param name="bool_param_auto" value="true" />
48  <param name="bool_param_forced" value="true" type="boolean" />
49 
50  <param name="bool_param_auto_nonlowercase" value="True" />
51  <param name="bool_param_forced_nonlowercase" value="True" type="boolean" />
52 
53  <param name="yaml_param" type="yaml" value="test_param: true" />
54  <param name="yaml_param_scalar" type="yaml" value="true" />
55  </launch>
56  )EOF");
57 
58  config.evaluateParameters();
59 
60  auto& params = config.parameters();
61  checkTypedParam<int>(params, "/int_param_auto", XmlRpc::XmlRpcValue::TypeInt, 0);
62  checkTypedParam<int>(params, "/int_param_forced", XmlRpc::XmlRpcValue::TypeInt, 0);
63 
64  checkTypedParam<double>(params, "/double_param_auto", XmlRpc::XmlRpcValue::TypeDouble, 0.0);
65  checkTypedParam<double>(params, "/double_param_forced", XmlRpc::XmlRpcValue::TypeDouble, 0.0);
66 
67  checkTypedParam<std::string>(params, "/str_param_auto", XmlRpc::XmlRpcValue::TypeString, "hello");
68  checkTypedParam<std::string>(params, "/str_param_forced", XmlRpc::XmlRpcValue::TypeString, "0");
69 
70  checkTypedParam<bool>(params, "/bool_param_auto", XmlRpc::XmlRpcValue::TypeBoolean, true);
71  checkTypedParam<bool>(params, "/bool_param_forced", XmlRpc::XmlRpcValue::TypeBoolean, true);
72 
73  checkTypedParam<bool>(params, "/bool_param_auto_nonlowercase", XmlRpc::XmlRpcValue::TypeBoolean, true);
74  checkTypedParam<bool>(params, "/bool_param_forced_nonlowercase", XmlRpc::XmlRpcValue::TypeBoolean, true);
75 
76  checkTypedParam<bool>(params, "/yaml_param/test_param", XmlRpc::XmlRpcValue::TypeBoolean, true);
77  checkTypedParam<bool>(params, "/yaml_param_scalar", XmlRpc::XmlRpcValue::TypeBoolean, true);
78 }
79 
80 TEST_CASE("param command", "[param]")
81 {
82  LaunchConfig config;
83  config.parseString(R"EOF(
84  <launch>
85  <param name="test" command="echo -n hello_world" />
86 
87  <param name="multiline" command="/bin/echo -ne hello\\nworld" />
88 
89  <param name="yaml_param" type="yaml" command="echo test_param: true" />
90  </launch>
91  )EOF");
92 
93  config.evaluateParameters();
94 
95  auto& params = config.parameters();
96 
97  checkTypedParam<std::string>(params, "/test", XmlRpc::XmlRpcValue::TypeString, "hello_world");
98  checkTypedParam<std::string>(params, "/multiline", XmlRpc::XmlRpcValue::TypeString, "hello\nworld");
99 
100  checkTypedParam<bool>(params, "/yaml_param/test_param", XmlRpc::XmlRpcValue::TypeBoolean, true);
101 }
102 
103 TEST_CASE("param failing command", "[param]")
104 {
105  LaunchConfig config;
106  config.parseString(R"EOF(<launch><param name="test" command="false" /></launch>)EOF");
107  REQUIRE_THROWS_AS(
108  config.evaluateParameters(),
110  );
111 }
112 
113 TEST_CASE("param textfile", "[param]")
114 {
115  LaunchConfig config;
116  config.parseString(R"EOF(
117  <launch>
118  <param name="test" textfile="$(find rosmon_core)/test/textfile.txt" />
119  </launch>
120  )EOF");
121 
122  config.evaluateParameters();
123 
124  auto& params = config.parameters();
125 
126  checkTypedParam<std::string>(params, "/test", XmlRpc::XmlRpcValue::TypeString, "hello_world");
127 }
128 
129 TEST_CASE("param textfile does not exist", "[param]")
130 {
131  using Catch::Matchers::Contains;
132 
133  LaunchConfig config;
134  config.parseString(R"EOF(
135  <launch>
136  <param name="test" textfile="$(find rosmon_core)/test/textfile_does_not_exist.txt" />
137  </launch>
138  )EOF");
139 
140  REQUIRE_THROWS_WITH(
141  config.evaluateParameters(),
142  Contains("file")
143  );
144 }
145 
146 TEST_CASE("param binfile", "[param]")
147 {
148  LaunchConfig config;
149  config.parseString(R"EOF(
150  <launch>
151  <param name="test" binfile="$(find rosmon_core)/test/textfile.txt" />
152  </launch>
153  )EOF");
154 
155  config.evaluateParameters();
156 
157  auto& params = config.parameters();
158 
159  CAPTURE(params);
160 
161  auto it = params.find("/test");
162  REQUIRE(it != params.end());
163 
164  XmlRpc::XmlRpcValue value = it->second;
165 
166  REQUIRE(value.getType() == XmlRpc::XmlRpcValue::TypeBase64);
167 
168  std::string expectedData = "hello_world";
169  auto& data = static_cast<XmlRpc::XmlRpcValue::BinaryData&>(value);
170 
171  REQUIRE(expectedData.size() == data.size());
172  for(std::size_t i = 0; i < expectedData.size(); ++i)
173  REQUIRE(data[i] == expectedData[i]);
174 }
175 
176 TEST_CASE("scoped params", "[param]")
177 {
178  LaunchConfig config;
179  config.parseString(R"EOF(
180  <launch>
181  <param name="global/param" value="abc" />
182  <param name="/global/param2" value="def" />
183 
184  <group ns="namespace">
185  <param name="test" value="val1" />
186  <param name="/test2" value="val2" />
187  </group>
188 
189  <node name="test_node" pkg="rosmon_core" type="abort">
190  <param name="private" value="val3" />
191  <param name="~private2" value="val4" />
192  <param name="/leading_slash" value="val5" />
193  </node>
194  </launch>
195  )EOF");
196 
197  config.evaluateParameters();
198 
199  auto& params = config.parameters();
200 
201  checkTypedParam<std::string>(params, "/global/param", XmlRpc::XmlRpcValue::TypeString, "abc");
202  checkTypedParam<std::string>(params, "/global/param2", XmlRpc::XmlRpcValue::TypeString, "def");
203 
204  checkTypedParam<std::string>(params, "/namespace/test", XmlRpc::XmlRpcValue::TypeString, "val1");
205  checkTypedParam<std::string>(params, "/test2", XmlRpc::XmlRpcValue::TypeString, "val2");
206 
207  checkTypedParam<std::string>(params, "/test_node/private", XmlRpc::XmlRpcValue::TypeString, "val3");
208  checkTypedParam<std::string>(params, "/test_node/private2", XmlRpc::XmlRpcValue::TypeString, "val4");
209 
210  checkTypedParam<std::string>(params, "/test_node/leading_slash", XmlRpc::XmlRpcValue::TypeString, "val5");
211 }
212 
213 TEST_CASE("scoped params with double slash (#49)", "[param]")
214 {
215  LaunchConfig config;
216  config.parseString(R"EOF(
217  <launch>
218  <group ns="/">
219  <param name="param1" value="hello" />
220  </group>
221 
222  <node name="test_node" pkg="rosmon_core" type="abort" ns="/racecar">
223  <param name="private_param" value="hello again" />
224  </node>
225  </launch>
226  )EOF");
227 
228  config.evaluateParameters();
229 
230  auto& params = config.parameters();
231 
232  checkTypedParam<std::string>(params, "/param1", XmlRpc::XmlRpcValue::TypeString, "hello");
233  checkTypedParam<std::string>(params, "/racecar/test_node/private_param", XmlRpc::XmlRpcValue::TypeString, "hello again");
234 }
235 
236 TEST_CASE("wrong param types", "[param]")
237 {
238  REQUIRE_THROWS_AS(
239  LaunchConfig().parseString(R"EOF(<launch><param name="test" value="abc" type="int" /></launch>)EOF"),
241  );
242 
243  REQUIRE_THROWS_AS(
244  LaunchConfig().parseString(R"EOF(<launch><param name="test" value="0.5" type="int" /></launch>)EOF"),
246  );
247 
248  REQUIRE_THROWS_AS(
249  LaunchConfig().parseString(R"EOF(<launch><param name="test" value="0.5" type="bool" /></launch>)EOF"),
251  );
252 
253  REQUIRE_THROWS_AS(
254  LaunchConfig().parseString(R"EOF(<launch><param name="test" value="invalid: {{ yaml}} here" type="yaml" /></launch>)EOF"),
256  );
257 
258  {
259  LaunchConfig config;
260 
261  config.parseString(R"EOF(<launch><param name="test" command="echo -ne invalid: {{ yaml}} here" type="yaml" /></launch>)EOF");
262 
263  REQUIRE_THROWS_AS(
264  config.evaluateParameters(),
266  );
267  }
268 
269  REQUIRE_THROWS_AS(
270  LaunchConfig().parseString(R"EOF(<launch><param name="test" value="0.5" type="unknown_type" /></launch>)EOF"),
272  );
273 }
274 
275 TEST_CASE("invalid param input combinations", "[param]")
276 {
277  REQUIRE_THROWS_AS(
278  LaunchConfig().parseString(R"EOF(<launch><param name="test" value="abc" command="echo -ne test" /></launch>)EOF"),
280  );
281 
282  REQUIRE_THROWS_AS(
283  LaunchConfig().parseString(R"EOF(<launch><param name="test" textfile="$(find rosmon_core)/test/textfile.txt" command="echo -ne test" /></launch>)EOF"),
285  );
286 
287  REQUIRE_THROWS_AS(
288  LaunchConfig().parseString(R"EOF(<launch><param name="test" /></launch>)EOF"),
290  );
291 }
292 
293 TEST_CASE("invalid param names", "[param]")
294 {
295  using Catch::Matchers::Contains;
296 
297  REQUIRE_THROWS_WITH(
298  LaunchConfig().parseString(R"EOF(<launch><param name="$%*" value="abc" /></launch>)EOF"),
299  Contains("$%*")
300  );
301 
302  REQUIRE_THROWS_WITH(
303  LaunchConfig().parseString(R"EOF(<launch><param value="abc" /></launch>)EOF"),
304  Contains("name")
305  );
306 }
307 
auto & params
Definition: test_param.cpp:220
const std::map< std::string, XmlRpc::XmlRpcValue > & parameters() const
void parseString(const std::string &input, bool onlyArguments=false)
TEST_CASE("global_param","[param]")
Definition: test_param.cpp:12
config parseString(R"EOF( <launch> <group ns="/"> <param name="param1" value="hello" /> </group> <node name="test_node" pkg="rosmon_core" type="abort" ns="/racecar"> <param name="private_param" value="hello again" /> </node> </launch> )EOF")
std::vector< char > BinaryData


rosmon_core
Author(s): Max Schwarz
autogenerated on Wed Jul 10 2019 03:10:12