Enforce a precedence for wildcard matching in parameter overrides. (#1094)
Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>
This commit is contained in:
parent
45f3976453
commit
814298480c
3 changed files with 15 additions and 7 deletions
|
@ -107,11 +107,14 @@ NodeParameters::NodeParameters(
|
||||||
rcl_yaml_node_struct_fini(params);
|
rcl_yaml_node_struct_fini(params);
|
||||||
});
|
});
|
||||||
rclcpp::ParameterMap initial_map = rclcpp::parameter_map_from(params);
|
rclcpp::ParameterMap initial_map = rclcpp::parameter_map_from(params);
|
||||||
for (auto iter = initial_map.begin(); initial_map.end() != iter; iter++) {
|
|
||||||
|
// Enforce wildcard matching precedence
|
||||||
// TODO(cottsay) implement further wildcard matching
|
// TODO(cottsay) implement further wildcard matching
|
||||||
if (iter->first == "/**" || iter->first == combined_name_) {
|
const std::vector<std::string> 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
|
// 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()] =
|
parameter_overrides_[param.get_name()] =
|
||||||
rclcpp::ParameterValue(param.get_value_message());
|
rclcpp::ParameterValue(param.get_value_message());
|
||||||
}
|
}
|
||||||
|
|
|
@ -1,4 +1,8 @@
|
||||||
/**:
|
/**:
|
||||||
ros__parameters:
|
ros__parameters:
|
||||||
parameter_int: 21
|
parameter_bool: true
|
||||||
|
parameter_int: 42
|
||||||
parameter_string_array: [baz, baz, baz]
|
parameter_string_array: [baz, baz, baz]
|
||||||
|
test_declare_parameter_node:
|
||||||
|
ros__parameters:
|
||||||
|
parameter_int: 21
|
||||||
|
|
|
@ -691,7 +691,7 @@ TEST_F(TestNode, declare_parameter_with_cli_overrides) {
|
||||||
no.arguments(
|
no.arguments(
|
||||||
{
|
{
|
||||||
"--ros-args",
|
"--ros-args",
|
||||||
"-p", "parameter_bool:=true",
|
"-p", "parameter_bool:=false",
|
||||||
"-p", "parameter_int:=42",
|
"-p", "parameter_int:=42",
|
||||||
"-p", "parameter_double:=0.42",
|
"-p", "parameter_double:=0.42",
|
||||||
"-p", "parameter_string:=foo",
|
"-p", "parameter_string:=foo",
|
||||||
|
@ -702,7 +702,8 @@ TEST_F(TestNode, declare_parameter_with_cli_overrides) {
|
||||||
"-p", "parameter_string_array:=[foo, bar]"
|
"-p", "parameter_string_array:=[foo, bar]"
|
||||||
});
|
});
|
||||||
|
|
||||||
auto node = std::make_shared<rclcpp::Node>("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<rclcpp::Node>("test_declare_parameter_node", no);
|
||||||
{
|
{
|
||||||
rclcpp::ParameterValue value = node->declare_parameter("parameter_bool");
|
rclcpp::ParameterValue value = node->declare_parameter("parameter_bool");
|
||||||
EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_BOOL);
|
EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_BOOL);
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue