diff --git a/ros2param/ros2param/api/__init__.py b/ros2param/ros2param/api/__init__.py index 7f3180492..5cd3fd7cf 100644 --- a/ros2param/ros2param/api/__init__.py +++ b/ros2param/ros2param/api/__init__.py @@ -39,7 +39,8 @@ def load_parameter_file(*, node, node_name, parameter_file, use_wildcard): raise RuntimeError('Wait for service timed out waiting for ' f'parameter services for node {node_name}') future = client.load_parameter_file(parameter_file, use_wildcard) - parameters = list(parameter_dict_from_yaml_file(parameter_file, use_wildcard).values()) + parameters = list(parameter_dict_from_yaml_file( + parameter_file, use_wildcard, target_nodes=[node_name]).values()) rclpy.spin_until_future_complete(node, future) response = future.result() assert len(response.results) == len(parameters), 'Not all parameters set' diff --git a/ros2param/test/test_verb_load.py b/ros2param/test/test_verb_load.py index b2eabd1e2..e3711b5bf 100644 --- a/ros2param/test/test_verb_load.py +++ b/ros2param/test/test_verb_load.py @@ -85,6 +85,12 @@ ' ros__parameters:\n' ' str_param: Override\n' ) +INPUT_NS_NODE_OVERLAY_PARAMETER_FILE = ( + f'{TEST_NAMESPACE}:\n' + f' {TEST_NODE}:\n' + ' ros__parameters:\n' + ' str_param: Override\n' +) # Skip cli tests on Windows while they exhibit pathological behavior # https://github.com/ros2/build_farmer/issues/248 @@ -318,7 +324,7 @@ def test_verb_load_wildcard(self): assert param_load_command.wait_for_shutdown(timeout=TEST_TIMEOUT) assert param_load_command.exit_code != launch_testing.asserts.EXIT_OK assert launch_testing.tools.expect_output( - expected_lines=['Param file does not contain selected parameters'], + expected_lines=['Param file does not contain any valid parameters'], text=param_load_command.output, strict=False ) @@ -344,7 +350,7 @@ def test_verb_load_wildcard(self): assert params['str_param'] == 'Wildcard' assert params['int_param'] == 12345 - # Concatenate wildcard + some overlays + # Concatenate wildcard + some overlays with absolute node name filepath = self._write_param_file(tmpdir, 'params.yaml', INPUT_WILDCARD_PARAMETER_FILE + '\n' + INPUT_NODE_OVERLAY_PARAMETER_FILE) @@ -364,3 +370,24 @@ def test_verb_load_wildcard(self): params = loaded_params[f'{TEST_NAMESPACE}/{TEST_NODE}']['ros__parameters'] assert params['str_param'] == 'Override' # Overriden assert params['int_param'] == 12345 # Wildcard namespace + + # Concatenate wildcard + some overlays with namespace and base node name + filepath = self._write_param_file(tmpdir, 'params.yaml', + INPUT_WILDCARD_PARAMETER_FILE + '\n' + + INPUT_NS_NODE_OVERLAY_PARAMETER_FILE) + with self.launch_param_load_command( + arguments=[f'{TEST_NAMESPACE}/{TEST_NODE}', filepath] + ) as param_load_command: + assert param_load_command.wait_for_shutdown(timeout=TEST_TIMEOUT) + assert param_load_command.exit_code == launch_testing.asserts.EXIT_OK + + # Dump and check that wildcard parameters were overriden if in node namespace + with self.launch_param_dump_command( + arguments=[f'{TEST_NAMESPACE}/{TEST_NODE}'] + ) as param_dump_command: + assert param_dump_command.wait_for_shutdown(timeout=TEST_TIMEOUT) + assert param_dump_command.exit_code == launch_testing.asserts.EXIT_OK + loaded_params = yaml.safe_load(param_dump_command.output) + params = loaded_params[f'{TEST_NAMESPACE}/{TEST_NODE}']['ros__parameters'] + assert params['str_param'] == 'Override' # Overriden + assert params['int_param'] == 12345 # Wildcard namespace