diff --git a/demo_nodes_py/demo_nodes_py/parameters/async_param_client.py b/demo_nodes_py/demo_nodes_py/parameters/async_param_client.py index 1c1e9046c..1893d29e1 100644 --- a/demo_nodes_py/demo_nodes_py/parameters/async_param_client.py +++ b/demo_nodes_py/demo_nodes_py/parameters/async_param_client.py @@ -73,8 +73,7 @@ def main(args=None): rclpy.spin_until_future_complete(node, future) load_parameter_results = future.result() if load_parameter_results is not None: - param_file_dict = parameter_dict_from_yaml_file( - param_file_path, False, target_nodes=['parameter_blackboard']) + param_file_dict = parameter_dict_from_yaml_file(param_file_path) for i, v in enumerate(param_file_dict.keys()): node.get_logger().info(f' {v}:') node.get_logger().info(f' successful: ' diff --git a/demo_nodes_py/demo_nodes_py/parameters/params.yaml b/demo_nodes_py/demo_nodes_py/parameters/params.yaml index 962581ebb..768ddfd8e 100644 --- a/demo_nodes_py/demo_nodes_py/parameters/params.yaml +++ b/demo_nodes_py/demo_nodes_py/parameters/params.yaml @@ -1,4 +1,4 @@ -/parameter_blackboard: +/param_test_target: ros__parameters: other_int_parameter: 0 int_parameter: 12