Skip to content

Commit 4c5f526

Browse files
committed
Restore functionality for mapped params with no struct name
1 parent 9f1fc8f commit 4c5f526

File tree

10 files changed

+57
-0
lines changed

10 files changed

+57
-0
lines changed

.gitignore

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1 @@
1+
**/__pycache__

example/config/implementation.yaml

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,9 @@ admittance_controller:
1111
fixed_string_no_default:
1212
"happy"
1313

14+
elbow_joint:
15+
weight: 2.0
16+
1417
pid:
1518
shoulder_pan_joint:
1619
i: 0.7

example/src/parameters.yaml

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,16 @@ admittance_controller:
2424
description: "specifies which joints will be used by the controller",
2525
}
2626

27+
__map_joints:
28+
weight: {
29+
type: double,
30+
default_value: 1.0,
31+
description: "map parameter without struct name",
32+
validation: {
33+
gt<>: [0.0],
34+
}
35+
}
36+
2737
nested_dynamic:
2838
__map_joints:
2939
__map_dof_names:

example_python/config/implementation.yaml

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,9 @@ admittance_controller:
1111
fixed_string_no_default:
1212
"happy"
1313

14+
elbow_joint:
15+
weight: 2.0
16+
1417
pid:
1518
shoulder_pan_joint:
1619
i: 0.7

example_python/generate_parameter_module_example/parameters.yaml

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,16 @@ admittance_controller:
3232
description: "specifies which joints will be used by the controller",
3333
}
3434

35+
__map_joints:
36+
weight: {
37+
type: double,
38+
default_value: 1.0,
39+
description: "map parameter without struct name",
40+
validation: {
41+
gt<>: [0.0],
42+
}
43+
}
44+
3545
nested_dynamic:
3646
__map_joints:
3747
__map_dof_names:

generate_parameter_library_py/generate_parameter_library_py/jinja_templates/cpp/declare_runtime_parameter

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,10 +2,18 @@
22
for (const auto & value_{{loop.index}} : updated_params.{{mapped_param}}) {
33
{% endfor -%}
44
{%- filter indent(width=4) -%}
5+
{% if struct_name != "" %}
56
auto& entry = {{param_struct_instance}}.{{struct_name}}{% for map in parameter_map%}.{{map}}[value_{{loop.index}}]{% endfor %};
7+
{% else %}
8+
auto& entry = {{param_struct_instance}}.{% for map in parameter_map%}{{map}}[value_{{loop.index}}]{% endfor %};
9+
{% endif -%}
610
std::string value = fmt::format("{%- for mapped_param in mapped_params -%}{% if loop.index == 1 %}{}{% else %}.{}{% endif -%} {%- endfor -%}",
711
{%- for mapped_param in mapped_params -%}{% if loop.index == 1 %} value_{{loop.index}}{% else %}, value_{{loop.index}}{% endif -%} {%- endfor %});
12+
{% if struct_name != "" %}
813
auto param_name = fmt::format("{}{}.{}.{}", prefix_, "{{struct_name}}", value, "{{parameter_field}}");
14+
{% else %}
15+
auto param_name = fmt::format("{}{}.{}", prefix_, value, "{{parameter_field}}");
16+
{% endif -%}
917
if (!parameters_interface_->has_parameter(param_name)) {
1018
{%- filter indent(width=4) %}
1119
rcl_interfaces::msg::ParameterDescriptor descriptor;

generate_parameter_library_py/generate_parameter_library_py/jinja_templates/cpp/remove_runtime_parameter

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,11 @@
22
std::set<std::string> {{mapped_param}}_set(updated_params.{{mapped_param}}.begin(), updated_params.{{mapped_param}}.end());
33
for (const auto &it: updated_params.{{parameter_map}}) {
44
if ({{mapped_param}}_set.find(it.first) == {{mapped_param}}_set.end()) {
5+
{% if struct_name != "" %}
56
auto param_name = fmt::format("{}{}.{}.{}", prefix_, "{{struct_name}}", it.first, "{{parameter_field}}");
7+
{% else %}
8+
auto param_name = fmt::format("{}{}.{}", prefix_, it.first, "{{parameter_field}}");
9+
{% endif -%}
610
parameters_interface_->undeclare_parameter(param_name);
711
}
812
}

generate_parameter_library_py/generate_parameter_library_py/jinja_templates/cpp/update_runtime_parameter

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,13 +4,21 @@ for (const auto & value_{{loop.index}} : updated_params.{{mapped_param}}) {
44
{%- filter indent(width=4) -%}
55
std::string value = fmt::format("{%- for mapped_param in mapped_params -%}{% if loop.index == 1 %}{}{% else %}.{}{% endif -%} {%- endfor -%}",
66
{%- for mapped_param in mapped_params -%}{% if loop.index == 1 %} value_{{loop.index}}{% else %}, value_{{loop.index}}{% endif -%} {%- endfor %});
7+
{% if struct_name != "" %}
78
auto param_name = fmt::format("{}{}.{}.{}", prefix_, "{{struct_name}}", value, "{{parameter_field}}");
9+
{% else %}
10+
auto param_name = fmt::format("{}{}.{}", prefix_, value, "{{parameter_field}}");
11+
{% endif -%}
812
if (param.get_name() == param_name) {
913
{%- filter indent(width=4) %}
1014
{% if parameter_validations|length -%}
1115
{{parameter_validations-}}
1216
{% endif -%}
17+
{% if struct_name != "" %}
1318
updated_params.{{struct_name}}{% for map in parameter_map%}.{{map}}[value_{{loop.index}}]{% endfor %}.{{parameter_field}} = param.{{parameter_as_function}};
19+
{% else %}
20+
updated_params.{% for map in parameter_map%}{{map}}[value_{{loop.index}}]{% endfor %}.{{parameter_field}} = param.{{parameter_as_function}};
21+
{% endif -%}
1422
RCLCPP_DEBUG_STREAM(logger_, param.get_name() << ": " << param.get_type_name() << " = " << param.value_to_string());
1523
{% endfilter -%}
1624
}

generate_parameter_library_py/generate_parameter_library_py/jinja_templates/python/declare_runtime_parameter

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,9 +4,15 @@ for value_{{loop.index}} in updated_params.{{mapped_param}}:
44
{%- endfilter -%}
55
{% endfor -%}
66
{%- filter indent(width=4*(mapped_params|length)) %}
7+
{% if struct_name != "" %}
78
{{param_struct_instance}}.{{struct_name}}{% for map in parameter_map%}.add_entry(value_{{loop.index}}){% endfor %}
89
entry = {{param_struct_instance}}.{{struct_name}}{% for map in parameter_map%}.get_entry(value_{{loop.index}}){% endfor %}
910
param_name = f"{self.prefix_}{{struct_name}}{% for map in parameter_map%}.{value_{{loop.index}}}{% endfor %}.{{parameter_field}}"
11+
{% else %}
12+
{{param_struct_instance}}{% for map in parameter_map%}.add_entry(value_{{loop.index}}){% endfor %}
13+
entry = {{param_struct_instance}}{% for map in parameter_map%}.get_entry(value_{{loop.index}}){% endfor %}
14+
param_name = f"{self.prefix_}{% for map in parameter_map%}{value_{{loop.index}}}{% endfor %}.{{parameter_field}}"
15+
{% endif -%}
1016
if not self.node_.has_parameter(self.prefix_ + param_name):
1117
{%- filter indent(width=4) %}
1218
descriptor = ParameterDescriptor(description="{{parameter_description|valid_string_python}}", read_only = {{parameter_read_only}})

generate_parameter_library_py/generate_parameter_library_py/jinja_templates/python/update_runtime_parameter

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,11 @@ if param.name == param_name:
1010
{% if parameter_validations|length -%}
1111
{{parameter_validations-}}
1212
{% endif -%}
13+
{% if struct_name != "" %}
1314
updated_params.{{struct_name}}{% for map in parameter_map%}.get_entry(value_{{loop.index}}){% endfor %}.{{parameter_field}} = param.{{parameter_as_function}}
15+
{% else %}
16+
updated_params{% for map in parameter_map%}.get_entry(value_{{loop.index}}){% endfor %}.{{parameter_field}} = param.{{parameter_as_function}}
17+
{% endif -%}
1418
self.logger_.debug(param.name + ": " + param.type_.name + " = " + str(param.value))
1519
{% endfilter -%}
1620
{% endfilter -%}

0 commit comments

Comments
 (0)