4 #include <boost/filesystem.hpp>
6 #include <catch_ros/catch.hpp>
8 #include "../../src/launch/launch_config.h"
17 namespace fs = boost::filesystem;
26 <param name="env_test" value="$(env PATH)" />
41 <param name="env_test" value="$(env ROSMON_UNLIKELY_TO_BE_SET)" />
54 <param name="env_test" value="$(optenv PATH no_such_thing)" />
65 SECTION(
"not present")
70 <param name="env_test" value="$(optenv ROSMON_UNLIKELY_TO_BE_SET no_such_thing)" />
81 SECTION(
"not present - long")
86 <param name="env_test" value="$(optenv ROSMON_UNLIKELY_TO_BE_SET no such thing)" />
100 SECTION(
"regular use")
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" />
119 INFO(
"Looking for /path_to_rosmon_executable");
121 auto it = config.
parameters().find(
"/path_to_rosmon_executable");
124 auto value = it->second;
127 auto string =
static_cast<std::string
>(value);
129 CHECK((fs::status(
string).permissions() & fs::owner_exe));
133 SECTION(
"unknown package")
137 <param name="test" value="$(find rosmon_this_package_is_unlikely_to_be_there)" />
145 SECTION(
"regular use")
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)" />
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");
164 CHECK(test1 == test2);
165 CHECK(test1 != test3);
168 SECTION(
"clash example")
173 <node name="$(anon foo)" pkg="rospy_tutorials" type="talker.py" />
174 <node name="$(anon foo)" pkg="rospy_tutorials" type="talker.py" />
184 <param name="test_1_global" value="$(anon test_1)" />
187 <param name="test_1_local" value="$(anon test_1)" />
188 <param name="test_2_local" value="$(anon test_2)" />
191 <param name="test_2_global" value="$(anon test_2)" />
199 auto test_1_global = getTypedParam<std::string>(config.
parameters(),
"/test_1_global");
200 auto test_1_local = getTypedParam<std::string>(config.
parameters(),
"/test_1_local");
201 auto test_2_global = getTypedParam<std::string>(config.
parameters(),
"/test_2_global");
202 auto test_2_local = getTypedParam<std::string>(config.
parameters(),
"/test_2_local");
204 CHECK(test_1_global == test_1_local);
205 CHECK(test_2_global != test_2_local);
216 <arg name="test_arg" default="hello" />
217 <param name="test" value="$(arg test_arg)" />
223 CHECK(getTypedParam<std::string>(config.parameters(), "/test") ==
"hello");
226 SECTION(
"unknown arg")
230 <arg name="test_arg" default="hello" />
231 <param name="test" value="$(arg test_arg_unknown)" />
246 <arg name="radius" default="2.0" />
247 <param name="circumference" value="$(eval 2.* pi * arg('radius'))"/>
253 auto value = getTypedParam<double>(config.
parameters(),
"/circumference");
254 CHECK(value == Approx(2.0 * M_PI * 2.0));
262 <arg name="foo" default="test" />
263 <param name="test" value="$(eval arg('foo') + env('PATH') + 'bar' + find('rosmon_core'))"/>
269 auto value = getTypedParam<std::string>(config.
parameters(),
"/test");
278 <arg name="foo" default="test" />
279 <param name="test" value="$(eval foo + env('PATH') + 'bar' + find('rosmon_core'))"/>
285 auto value = getTypedParam<std::string>(config.
parameters(),
"/test");
294 <arg name="foo" default="test" />
295 <param name="test" value="$(eval 2 * 20)"/>
301 auto value = getTypedParam<int>(config.
parameters(),
"/test");
302 CHECK(value == 2*20);
305 SECTION(
"python errors")
307 using Catch::Matchers::Contains;
309 std::string input = R
"EOF(
311 <arg name="foo" default="test" />
312 <param name="test" value="$(eval )))"/>
319 Contains("SyntaxError")
324 <arg name="foo" default="test" />
325 <param name="test" value="$(eval acos)"/>
330 SECTION("lowercase booleans")
335 <arg name="input" default="false" />
336 <param name="output" value="$(eval input == true)"/>
342 auto value = getTypedParam<bool>(config.
parameters(),
"/output");
343 CHECK(value ==
false);
349 SECTION(
"basic usage")
354 <param name="test" value="$(dirname)" />
360 auto value = getTypedParam<std::string>(config.
parameters(),
"/test");
362 CHECK(fs::path(value) == fs::current_path());
368 SECTION(
"unknown subst")
372 <param name="test" value="$(unknown_subst parameter)" />