test_arg.cpp
Go to the documentation of this file.
1 // Unit tests for arg 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 "core_utils.h"
9 #include "param_utils.h"
10 
11 using namespace rosmon::launch;
12 
13 TEST_CASE("arg basic", "[arg]")
14 {
15  LaunchConfig config;
16  config.parseString(R"EOF(
17  <launch>
18  <arg name="arg1" value="hello world" />
19  <arg name="arg2" default="hello world" />
20  <arg name="arg3" default="True" />
21 
22  <param name="arg1" value="$(arg arg1)" />
23  <param name="arg2" value="$(arg arg2)" />
24  <param name="arg3" type="bool" value="$(arg arg3)" />
25  </launch>
26  )EOF");
27 
28  config.evaluateParameters();
29 
30  auto params = config.parameters();
31 
32  CHECK(getTypedParam<std::string>(params, "/arg1") == "hello world");
33  CHECK(getTypedParam<std::string>(params, "/arg2") == "hello world");
34  CHECK(getTypedParam<bool>(params, "/arg3") == true);
35 }
36 
37 TEST_CASE("arg from external", "[arg]")
38 {
39  LaunchConfig config;
40 
41  config.setArgument("arg1", "test");
42  config.setArgument("arg2", "test");
43 
44  config.parseString(R"EOF(
45  <launch>
46  <arg name="arg1" />
47  <arg name="arg2" default="hello world" />
48 
49  <param name="arg1" value="$(arg arg1)" />
50  <param name="arg2" value="$(arg arg2)" />
51  </launch>
52  )EOF");
53 
54  config.evaluateParameters();
55 
56  auto params = config.parameters();
57 
58  CHECK(getTypedParam<std::string>(params, "/arg1") == "test");
59  CHECK(getTypedParam<std::string>(params, "/arg2") == "test");
60 }
61 
62 TEST_CASE("arg unset", "[arg]")
63 {
65  <launch>
66  <param name="test" value="$(arg arg1)" />
67  </launch>
68  )EOF");
69 
71  <launch>
72  <arg name="arg1" />
73  <param name="test" value="$(arg arg1)" />
74  </launch>
75  )EOF");
76 }
77 
78 TEST_CASE("arg whitespace", "[arg]")
79 {
80  LaunchConfig config;
81  config.parseString(R"EOF(
82  <launch>
83  <arg name="arg1" value="hello world" />
84  <arg name="arg2" default="hello world" />
85  <arg name="arg3" default="True" />
86 
87  <param name="arg1" value="$(arg arg1 )" />
88  <param name="arg2" value="$(arg arg2)" />
89  <param name="arg3" type="bool" value="$(arg arg3 )" />
90  </launch>
91  )EOF");
92 
93  config.evaluateParameters();
94 
95  auto params = config.parameters();
96 
97  CHECK(getTypedParam<std::string>(params, "/arg1") == "hello world");
98  CHECK(getTypedParam<std::string>(params, "/arg2") == "hello world");
99  CHECK(getTypedParam<bool>(params, "/arg3") == true);
100 }
TEST_CASE("arg basic","[arg]")
Definition: test_arg.cpp:13
auto & params
Definition: test_param.cpp:220
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)
void setArgument(const std::string &name, const std::string &value)


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