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" /> 187 <arg name="test_arg" default="hello" /> 188 <param name="test" value="$(arg test_arg)" /> 194 CHECK(getTypedParam<std::string>(config.parameters(), "/test") ==
"hello");
197 SECTION(
"unknown arg")
201 <arg name="test_arg" default="hello" /> 202 <param name="test" value="$(arg test_arg_unknown)" /> 217 <arg name="radius" default="2.0" /> 218 <param name="circumference" value="$(eval 2.* pi * arg('radius'))"/> 224 auto value = getTypedParam<double>(config.
parameters(),
"/circumference");
225 CHECK(value == Approx(2.0 * M_PI * 2.0));
233 <arg name="foo" default="test" /> 234 <param name="test" value="$(eval arg('foo') + env('PATH') + 'bar' + find('rosmon_core'))"/> 240 auto value = getTypedParam<std::string>(config.
parameters(),
"/test");
249 <arg name="foo" default="test" /> 250 <param name="test" value="$(eval foo + env('PATH') + 'bar' + find('rosmon_core'))"/> 256 auto value = getTypedParam<std::string>(config.
parameters(),
"/test");
265 <arg name="foo" default="test" /> 266 <param name="test" value="$(eval 2 * 20)"/> 272 auto value = getTypedParam<int>(config.
parameters(),
"/test");
273 CHECK(value == 2*20);
276 SECTION(
"python errors")
278 using Catch::Matchers::Contains;
280 std::string input = R
"EOF( 282 <arg name="foo" default="test" /> 283 <param name="test" value="$(eval )))"/> 290 Contains("SyntaxError")
295 <arg name="foo" default="test" /> 296 <param name="test" value="$(eval acos)"/> 301 SECTION("lowercase booleans")
306 <arg name="input" default="false" /> 307 <param name="output" value="$(eval input == true)"/> 313 auto value = getTypedParam<bool>(config.
parameters(),
"/output");
314 CHECK(value ==
false);
320 SECTION(
"basic usage")
325 <param name="test" value="$(dirname)" /> 331 auto value = getTypedParam<std::string>(config.
parameters(),
"/test");
333 CHECK(fs::path(value) == fs::current_path());
339 SECTION(
"unknown subst")
343 <param name="test" value="$(unknown_subst parameter)" />
TEST_CASE("env","[subst]")
const std::map< std::string, XmlRpc::XmlRpcValue > & parameters() const
void evaluateParameters()
static void requireParsingException(const std::string &input)
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)