test_subst.cpp
Go to the documentation of this file.
1 // Unit tests for substitution args
2 // Author: Max Schwarz <max.schwarz@ais.uni-bonn.de>
3 
4 #include <boost/filesystem.hpp>
5 
6 #include <catch_ros/catch.hpp>
7 
8 #include "../../src/launch/launch_config.h"
9 
10 #include "core_utils.h"
11 #include "param_utils.h"
12 
13 #include <ros/package.h>
14 
15 using namespace rosmon::launch;
16 
17 namespace fs = boost::filesystem;
18 
19 TEST_CASE("env", "[subst]")
20 {
21  SECTION("basic")
22  {
23  LaunchConfig config;
24  config.parseString(R"EOF(
25  <launch>
26  <param name="env_test" value="$(env PATH)" />
27  </launch>
28  )EOF");
29 
30  config.evaluateParameters();
31 
32  CAPTURE(config.parameters());
33 
34  checkTypedParam<std::string>(config.parameters(), "/env_test", XmlRpc::XmlRpcValue::TypeString, getenv("PATH"));
35  }
36 
37  SECTION("failure")
38  {
40  <launch>
41  <param name="env_test" value="$(env ROSMON_UNLIKELY_TO_BE_SET)" />
42  </launch>
43  )EOF");
44  }
45 }
46 
47 TEST_CASE("optenv", "[subst]")
48 {
49  SECTION("present")
50  {
51  LaunchConfig config;
52  config.parseString(R"EOF(
53  <launch>
54  <param name="env_test" value="$(optenv PATH no_such_thing)" />
55  </launch>
56  )EOF");
57 
58  config.evaluateParameters();
59 
60  CAPTURE(config.parameters());
61 
62  checkTypedParam<std::string>(config.parameters(), "/env_test", XmlRpc::XmlRpcValue::TypeString, getenv("PATH"));
63  }
64 
65  SECTION("not present")
66  {
67  LaunchConfig config;
68  config.parseString(R"EOF(
69  <launch>
70  <param name="env_test" value="$(optenv ROSMON_UNLIKELY_TO_BE_SET no_such_thing)" />
71  </launch>
72  )EOF");
73 
74  config.evaluateParameters();
75 
76  CAPTURE(config.parameters());
77 
78  checkTypedParam<std::string>(config.parameters(), "/env_test", XmlRpc::XmlRpcValue::TypeString, "no_such_thing");
79  }
80 
81  SECTION("not present - long")
82  {
83  LaunchConfig config;
84  config.parseString(R"EOF(
85  <launch>
86  <param name="env_test" value="$(optenv ROSMON_UNLIKELY_TO_BE_SET no such thing)" />
87  </launch>
88  )EOF");
89 
90  config.evaluateParameters();
91 
92  CAPTURE(config.parameters());
93 
94  checkTypedParam<std::string>(config.parameters(), "/env_test", XmlRpc::XmlRpcValue::TypeString, "no such thing");
95  }
96 }
97 
98 TEST_CASE("find", "[subst]")
99 {
100  SECTION("regular use")
101  {
102  LaunchConfig config;
103  config.parseString(R"EOF(
104  <launch>
105  <param name="path_to_rosmon" value="$(find rosmon_core)" />
106  <param name="path_to_launch_file" value="$(find rosmon_core)/test/basic.launch" />
107  <param name="path_to_rosmon_executable" value="$(find rosmon_core)/rosmon" />
108  </launch>
109  )EOF");
110 
111  config.evaluateParameters();
112 
113  CAPTURE(config.parameters());
114 
115  checkTypedParam<std::string>(config.parameters(), "/path_to_rosmon", XmlRpc::XmlRpcValue::TypeString, ros::package::getPath("rosmon_core"));
116  checkTypedParam<std::string>(config.parameters(), "/path_to_launch_file", XmlRpc::XmlRpcValue::TypeString, ros::package::getPath("rosmon_core") + "/test/basic.launch");
117 
118  {
119  INFO("Looking for /path_to_rosmon_executable");
120 
121  auto it = config.parameters().find("/path_to_rosmon_executable");
122  REQUIRE(it != config.parameters().end());
123 
124  auto value = it->second;
125 
126  REQUIRE(value.getType() == XmlRpc::XmlRpcValue::TypeString);
127  auto string = static_cast<std::string>(value);
128 
129  CHECK((fs::status(string).permissions() & fs::owner_exe));
130  }
131  }
132 
133  SECTION("unknown package")
134  {
136  <launch>
137  <param name="test" value="$(find rosmon_this_package_is_unlikely_to_be_there)" />
138  </launch>
139  )EOF");
140  }
141 }
142 
143 TEST_CASE("anon", "[subst]")
144 {
145  SECTION("regular use")
146  {
147  LaunchConfig config;
148  config.parseString(R"EOF(
149  <launch>
150  <param name="test_1" value="$(anon rviz-1)" />
151  <param name="test_2" value="$(anon rviz-1)" />
152  <param name="test_3" value="$(anon rviz-2)" />
153  </launch>
154  )EOF");
155 
156  config.evaluateParameters();
157 
158  CAPTURE(config.parameters());
159 
160  auto test1 = getTypedParam<std::string>(config.parameters(), "/test_1");
161  auto test2 = getTypedParam<std::string>(config.parameters(), "/test_2");
162  auto test3 = getTypedParam<std::string>(config.parameters(), "/test_3");
163 
164  CHECK(test1 == test2);
165  CHECK(test1 != test3);
166  }
167 
168  SECTION("clash example")
169  {
170  // from http://wiki.ros.org/roslaunch/XML
172  <launch>
173  <node name="$(anon foo)" pkg="rospy_tutorials" type="talker.py" />
174  <node name="$(anon foo)" pkg="rospy_tutorials" type="talker.py" />
175  </launch>
176  )EOF");
177  }
178 }
179 
180 TEST_CASE("arg", "[subst]")
181 {
182  SECTION("basic use")
183  {
184  LaunchConfig config;
185  config.parseString(R"EOF(
186  <launch>
187  <arg name="test_arg" default="hello" />
188  <param name="test" value="$(arg test_arg)" />
189  </launch>
190  )EOF");
191 
192  config.evaluateParameters();
193 
194  CHECK(getTypedParam<std::string>(config.parameters(), "/test") == "hello");
195  }
196 
197  SECTION("unknown arg")
198  {
200  <launch>
201  <arg name="test_arg" default="hello" />
202  <param name="test" value="$(arg test_arg_unknown)" />
203  </launch>
204  )EOF");
205  }
206 
207  // more complicated tests may be in test_arg.cpp
208 }
209 
210 TEST_CASE("eval", "[subst]")
211 {
212  SECTION("example 1")
213  {
214  LaunchConfig config;
215  config.parseString(R"EOF(
216  <launch>
217  <arg name="radius" default="2.0" />
218  <param name="circumference" value="$(eval 2.* pi * arg('radius'))"/>
219  </launch>
220  )EOF");
221 
222  config.evaluateParameters();
223 
224  auto value = getTypedParam<double>(config.parameters(), "/circumference");
225  CHECK(value == Approx(2.0 * M_PI * 2.0));
226  }
227 
228  SECTION("example 2")
229  {
230  LaunchConfig config;
231  config.parseString(R"EOF(
232  <launch>
233  <arg name="foo" default="test" />
234  <param name="test" value="$(eval arg('foo') + env('PATH') + 'bar' + find('rosmon_core'))"/>
235  </launch>
236  )EOF");
237 
238  config.evaluateParameters();
239 
240  auto value = getTypedParam<std::string>(config.parameters(), "/test");
241  CHECK(value == std::string("test") + getenv("PATH") + "bar" + ros::package::getPath("rosmon_core"));
242  }
243 
244  SECTION("example 3")
245  {
246  LaunchConfig config;
247  config.parseString(R"EOF(
248  <launch>
249  <arg name="foo" default="test" />
250  <param name="test" value="$(eval foo + env('PATH') + 'bar' + find('rosmon_core'))"/>
251  </launch>
252  )EOF");
253 
254  config.evaluateParameters();
255 
256  auto value = getTypedParam<std::string>(config.parameters(), "/test");
257  CHECK(value == std::string("test") + getenv("PATH") + "bar" + ros::package::getPath("rosmon_core"));
258  }
259 
260  SECTION("example 4")
261  {
262  LaunchConfig config;
263  config.parseString(R"EOF(
264  <launch>
265  <arg name="foo" default="test" />
266  <param name="test" value="$(eval 2 * 20)"/>
267  </launch>
268  )EOF");
269 
270  config.evaluateParameters();
271 
272  auto value = getTypedParam<int>(config.parameters(), "/test");
273  CHECK(value == 2*20);
274  }
275 
276  SECTION("python errors")
277  {
278  using Catch::Matchers::Contains;
279 
280  std::string input = R"EOF(
281  <launch>
282  <arg name="foo" default="test" />
283  <param name="test" value="$(eval )))"/>
284  </launch>
285  )EOF";
286  CAPTURE(input);
287 
288  REQUIRE_THROWS_WITH(
289  LaunchConfig().parseString(input),
290  Contains("SyntaxError")
291  );
292 
294  <launch>
295  <arg name="foo" default="test" />
296  <param name="test" value="$(eval acos)"/>
297  </launch>
298  )EOF");
299  }
300 
301  SECTION("lowercase booleans")
302  {
303  LaunchConfig config;
304  config.parseString(R"EOF(
305  <launch>
306  <arg name="input" default="false" />
307  <param name="output" value="$(eval input == true)"/>
308  </launch>
309  )EOF");
310 
311  config.evaluateParameters();
312 
313  auto value = getTypedParam<bool>(config.parameters(), "/output");
314  CHECK(value == false);
315  }
316 }
317 
318 TEST_CASE("dirname", "[subst]")
319 {
320  SECTION("basic usage")
321  {
322  LaunchConfig config;
323  config.parseString(R"EOF(
324  <launch>
325  <param name="test" value="$(dirname)" />
326  </launch>
327  )EOF");
328 
329  config.evaluateParameters();
330 
331  auto value = getTypedParam<std::string>(config.parameters(), "/test");
332 
333  CHECK(fs::path(value) == fs::current_path());
334  }
335 }
336 
337 TEST_CASE("subst invalid", "[subst]")
338 {
339  SECTION("unknown subst")
340  {
342  <launch>
343  <param name="test" value="$(unknown_subst parameter)" />
344  </launch>
345  )EOF");
346  }
347 }
TEST_CASE("env","[subst]")
Definition: test_subst.cpp:19
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)
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")
ROSLIB_DECL std::string getPath(const std::string &package_name)


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