|
37 | 37 |
|
38 | 38 | from ros2cli.node.strategy import NodeStrategy |
39 | 39 |
|
| 40 | +import yaml |
| 41 | + |
40 | 42 | TEST_NODE = 'test_node' |
41 | 43 | TEST_NAMESPACE = '/foo' |
42 | 44 |
|
|
71 | 73 | ' str_param: Bye World\n' |
72 | 74 | ' use_sim_time: false\n' |
73 | 75 | ) |
| 76 | +INPUT_WILDCARD_PARAMETER_FILE = ( |
| 77 | + '/**:\n' |
| 78 | + ' ros__parameters:\n' |
| 79 | + ' str_param: Wildcard\n' |
| 80 | + ' int_param: 12345\n' |
| 81 | +) |
| 82 | +INPUT_NODE_OVERLAY_PARAMETER_FILE = ( |
| 83 | + f'{TEST_NAMESPACE}/{TEST_NODE}:\n' |
| 84 | + ' ros__parameters:\n' |
| 85 | + ' str_param: Override\n' |
| 86 | +) |
74 | 87 |
|
75 | 88 | # Skip cli tests on Windows while they exhibit pathological behavior |
76 | 89 | # https://github.com/ros2/build_farmer/issues/248 |
@@ -191,10 +204,10 @@ def setUp(self): |
191 | 204 | if timed_out: |
192 | 205 | self.fail(f'CLI daemon failed to find test node after {TEST_TIMEOUT} seconds') |
193 | 206 |
|
194 | | - def _write_param_file(self, tmpdir, filename): |
| 207 | + def _write_param_file(self, tmpdir, filename, contents=INPUT_PARAMETER_FILE): |
195 | 208 | yaml_path = os.path.join(tmpdir, filename) |
196 | 209 | with open(yaml_path, 'w') as f: |
197 | | - f.write(INPUT_PARAMETER_FILE) |
| 210 | + f.write(contents) |
198 | 211 | return yaml_path |
199 | 212 |
|
200 | 213 | def _output_file(self): |
@@ -280,3 +293,62 @@ def test_verb_load(self): |
280 | 293 | text=param_dump_command.output, |
281 | 294 | strict=True |
282 | 295 | ) |
| 296 | + |
| 297 | + def test_verb_load_wildcard(self): |
| 298 | + with tempfile.TemporaryDirectory() as tmpdir: |
| 299 | + # Try param file with only wildcard |
| 300 | + filepath = self._write_param_file(tmpdir, 'params.yaml', INPUT_WILDCARD_PARAMETER_FILE) |
| 301 | + with self.launch_param_load_command( |
| 302 | + arguments=[f'{TEST_NAMESPACE}/{TEST_NODE}', filepath, |
| 303 | + '--no-use-wildcard'] |
| 304 | + ) as param_load_command: |
| 305 | + assert param_load_command.wait_for_shutdown(timeout=TEST_TIMEOUT) |
| 306 | + assert param_load_command.exit_code != launch_testing.asserts.EXIT_OK |
| 307 | + assert launch_testing.tools.expect_output( |
| 308 | + expected_lines=['Param file does not contain parameters for ' |
| 309 | + f'{TEST_NAMESPACE}/{TEST_NODE}'], |
| 310 | + text=param_load_command.output, |
| 311 | + strict=False |
| 312 | + ) |
| 313 | + |
| 314 | + with self.launch_param_load_command( |
| 315 | + arguments=[f'{TEST_NAMESPACE}/{TEST_NODE}', filepath] |
| 316 | + ) as param_load_command: |
| 317 | + assert param_load_command.wait_for_shutdown(timeout=TEST_TIMEOUT) |
| 318 | + assert param_load_command.exit_code == launch_testing.asserts.EXIT_OK |
| 319 | + assert launch_testing.tools.expect_output( |
| 320 | + expected_lines=[''], |
| 321 | + text=param_load_command.output, |
| 322 | + strict=True |
| 323 | + ) |
| 324 | + # Dump with ros2 param and check that wildcard parameters are loaded |
| 325 | + with self.launch_param_dump_command( |
| 326 | + arguments=[f'{TEST_NAMESPACE}/{TEST_NODE}', '--print'] |
| 327 | + ) as param_dump_command: |
| 328 | + assert param_dump_command.wait_for_shutdown(timeout=TEST_TIMEOUT) |
| 329 | + assert param_dump_command.exit_code == launch_testing.asserts.EXIT_OK |
| 330 | + loaded_params = yaml.safe_load(param_dump_command.output) |
| 331 | + params = loaded_params[f'{TEST_NAMESPACE}/{TEST_NODE}']['ros__parameters'] |
| 332 | + assert params['str_param'] == 'Wildcard' |
| 333 | + assert params['int_param'] == 12345 |
| 334 | + |
| 335 | + # Concatenate wildcard + some overlays |
| 336 | + filepath = self._write_param_file(tmpdir, 'params.yaml', |
| 337 | + INPUT_WILDCARD_PARAMETER_FILE + '\n' + |
| 338 | + INPUT_NODE_OVERLAY_PARAMETER_FILE) |
| 339 | + with self.launch_param_load_command( |
| 340 | + arguments=[f'{TEST_NAMESPACE}/{TEST_NODE}', filepath] |
| 341 | + ) as param_load_command: |
| 342 | + assert param_load_command.wait_for_shutdown(timeout=TEST_TIMEOUT) |
| 343 | + assert param_load_command.exit_code == launch_testing.asserts.EXIT_OK |
| 344 | + |
| 345 | + # Dump and check that wildcard parameters were overriden if in node namespace |
| 346 | + with self.launch_param_dump_command( |
| 347 | + arguments=[f'{TEST_NAMESPACE}/{TEST_NODE}', '--print'] |
| 348 | + ) as param_dump_command: |
| 349 | + assert param_dump_command.wait_for_shutdown(timeout=TEST_TIMEOUT) |
| 350 | + assert param_dump_command.exit_code == launch_testing.asserts.EXIT_OK |
| 351 | + loaded_params = yaml.safe_load(param_dump_command.output) |
| 352 | + params = loaded_params[f'{TEST_NAMESPACE}/{TEST_NODE}']['ros__parameters'] |
| 353 | + assert params['str_param'] == 'Override' # Overriden |
| 354 | + assert params['int_param'] == 12345 # Wildcard namespace |
0 commit comments