diff --git a/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp b/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp index 40db54b..f5d0aa7 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp @@ -107,11 +107,14 @@ NodeParameters::NodeParameters( rcl_yaml_node_struct_fini(params); }); rclcpp::ParameterMap initial_map = rclcpp::parameter_map_from(params); - for (auto iter = initial_map.begin(); initial_map.end() != iter; iter++) { - // TODO(cottsay) implement further wildcard matching - if (iter->first == "/**" || iter->first == combined_name_) { + + // Enforce wildcard matching precedence + // TODO(cottsay) implement further wildcard matching + const std::vector node_matching_names{"/**", combined_name_}; + for (const auto & node_name : node_matching_names) { + if (initial_map.count(node_name) > 0) { // Combine parameter yaml files, overwriting values in older ones - for (auto & param : iter->second) { + for (const rclcpp::Parameter & param : initial_map.at(node_name)) { parameter_overrides_[param.get_name()] = rclcpp::ParameterValue(param.get_value_message()); } diff --git a/rclcpp/test/resources/test_node/test_parameters.yaml b/rclcpp/test/resources/test_node/test_parameters.yaml index 2c4e307..449caa3 100644 --- a/rclcpp/test/resources/test_node/test_parameters.yaml +++ b/rclcpp/test/resources/test_node/test_parameters.yaml @@ -1,4 +1,8 @@ /**: ros__parameters: - parameter_int: 21 + parameter_bool: true + parameter_int: 42 parameter_string_array: [baz, baz, baz] +test_declare_parameter_node: + ros__parameters: + parameter_int: 21 diff --git a/rclcpp/test/test_node.cpp b/rclcpp/test/test_node.cpp index c85954a..e4851e1 100644 --- a/rclcpp/test/test_node.cpp +++ b/rclcpp/test/test_node.cpp @@ -691,7 +691,7 @@ TEST_F(TestNode, declare_parameter_with_cli_overrides) { no.arguments( { "--ros-args", - "-p", "parameter_bool:=true", + "-p", "parameter_bool:=false", "-p", "parameter_int:=42", "-p", "parameter_double:=0.42", "-p", "parameter_string:=foo", @@ -702,7 +702,8 @@ TEST_F(TestNode, declare_parameter_with_cli_overrides) { "-p", "parameter_string_array:=[foo, bar]" }); - auto node = std::make_shared("test_declare_parameter_node"_unq, no); + // To match parameters YAML file content, use a well-known node name for this test only. + auto node = std::make_shared("test_declare_parameter_node", no); { rclcpp::ParameterValue value = node->declare_parameter("parameter_bool"); EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_BOOL);