4 #include <catch_ros/catch.hpp> 6 #include "../../src/launch/launch_config.h" 17 <param name="global_param" value="hello_world" /> 25 auto it = config.
parameters().find(
"/global_param");
30 REQUIRE(static_cast<std::string>(value) ==
"hello_world");
38 <param name="int_param_auto" value="0" /> 39 <param name="int_param_forced" value="0" type="int" /> 41 <param name="double_param_auto" value="0.0" /> 42 <param name="double_param_forced" value="0" type="double" /> 44 <param name="str_param_auto" value="hello" /> 45 <param name="str_param_forced" value="0" type="str" /> 47 <param name="bool_param_auto" value="true" /> 48 <param name="bool_param_forced" value="true" type="boolean" /> 50 <param name="bool_param_auto_nonlowercase" value="True" /> 51 <param name="bool_param_forced_nonlowercase" value="True" type="boolean" /> 53 <param name="yaml_param" type="yaml" value="test_param: true" /> 54 <param name="yaml_param_scalar" type="yaml" value="true" /> 85 <param name="test" command="echo -n hello_world" /> 87 <param name="multiline" command="/bin/echo -ne hello\\nworld" /> 89 <param name="yaml_param" type="yaml" command="echo test_param: true" /> 106 config.
parseString(R
"EOF(<launch><param name="test" command="false" /></launch>)EOF"); 118 <param name="test" textfile="$(find rosmon_core)/test/textfile.txt" /> 131 using Catch::Matchers::Contains;
136 <param name="test" textfile="$(find rosmon_core)/test/textfile_does_not_exist.txt" /> 151 <param name="test" binfile="$(find rosmon_core)/test/textfile.txt" /> 161 auto it =
params.find(
"/test");
162 REQUIRE(it !=
params.end());
168 std::string expectedData =
"hello_world";
171 REQUIRE(expectedData.size() == data.size());
172 for(std::size_t i = 0; i < expectedData.size(); ++i)
173 REQUIRE(data[i] == expectedData[i]);
178 std::stringstream warnings;
184 <param name="global/param" value="abc" /> 185 <param name="/global/param2" value="def" /> 187 <group ns="namespace"> 188 <param name="test" value="val1" /> 189 <param name="/test2" value="val2" /> 192 <node name="test_node" pkg="rosmon_core" type="abort"> 193 <param name="private" value="val3" /> 194 <param name="~private2" value="val4" /> 195 <param name="/leading_slash" value="val5" /> 215 CAPTURE(warnings.str());
216 CHECK(warnings.str().find(
"leading slash") != std::string::npos);
219 TEST_CASE(
"scoped params with double slash (#49)",
"[param]")
225 <param name="param1" value="hello" /> 228 <node name="test_node" pkg="rosmon_core" type="abort" ns="/racecar"> 229 <param name="private_param" value="hello again" /> 242 TEST_CASE(
"wrong param types",
"[param]")
260 LaunchConfig().parseString(R"EOF(<launch><param name="test" value="invalid: {{ yaml}} here" type="yaml" /></launch>)EOF"), 267 config.parseString(R"EOF(<launch><param name="test" command="echo -ne invalid: {{ yaml}} here" type="yaml" /></launch>)EOF"); 281 TEST_CASE("invalid param input combinations",
"[param]")
284 LaunchConfig().
parseString(R
"EOF(<launch><param name="test" value="abc" command="echo -ne test" /></launch>)EOF"), 289 LaunchConfig().parseString(R"EOF(<launch><param name="test" textfile="$(find rosmon_core)/test/textfile.txt" command="echo -ne test" /></launch>)EOF"), 299 TEST_CASE("invalid param names",
"[param]")
301 using Catch::Matchers::Contains;
319 <param name="string" type="string" value=" 0.5 "/> 320 <param name="double" type="double" value=" 0.5 "/> 321 <param name="auto_string" value=" Hallo " /> 322 <param name="auto_double" value=" 0.6 " /> 323 <param name="auto_int" value="6" /> 324 <param name="auto_bool" value=" true " /> 326 <param name="command_param_string" type="string" command="echo ' Hallo '" /> 327 <param name="command_param_double" type="double" command="echo -n ' 1.23 '" /> 328 <param name="command_param_yaml" type="yaml" command="echo -n 1.23" /> 330 <param name="textfile_param_string" type="string" textfile="$(find rosmon_core)/test/textfile_double.txt" /> 331 <param name="textfile_param_double" type="double" textfile="$(find rosmon_core)/test/textfile_double.txt" /> 332 <param name="textfile_param_yaml" type="yaml" textfile="$(find rosmon_core)/test/analyzers.yaml" /> 334 <param name="multiple_lines1" value="first_line 336 <param name="multiple_lines2" command="echo -n first_line 347 CHECK(getTypedParam<std::string>(
params,
"/string", V::TypeString) ==
"0.5");
348 CHECK(getTypedParam<double>(
params,
"/double", V::TypeDouble) == Approx(0.5));
349 CHECK(getTypedParam<std::string>(
params,
"/auto_string", V::TypeString) ==
"Hallo");
350 CHECK(getTypedParam<double>(
params,
"/auto_double", V::TypeDouble) == Approx(0.6));
351 CHECK(getTypedParam<int>(
params,
"/auto_int", V::TypeInt) == 6);
352 CHECK(getTypedParam<bool>(
params,
"/auto_bool", V::TypeBoolean) ==
true);
354 CHECK(getTypedParam<std::string>(
params,
"/command_param_string", V::TypeString) ==
" Hallo \n");
355 CHECK(getTypedParam<double>(
params,
"/command_param_double", V::TypeDouble) == Approx(1.23));
357 CHECK(getTypedParam<std::string>(
params,
"/multiple_lines1", V::TypeString) ==
"first_line second_line");
358 CHECK(getTypedParam<std::string>(
params,
"/multiple_lines2", V::TypeString) ==
"first_line second_line");
const std::map< std::string, XmlRpc::XmlRpcValue > & parameters() const
void setWarningOutput(std::ostream *warningStream)
void evaluateParameters()
void parseString(const std::string &input, bool onlyArguments=false)
TEST_CASE("global_param","[param]")
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