Skip to content

Commit 032a74d

Browse files
authored
Support nested mapped parameters (#166)
1 parent 4b50b98 commit 032a74d

File tree

10 files changed

+124
-45
lines changed

10 files changed

+124
-45
lines changed

README.md

Lines changed: 27 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@ Additionally, dynamic parameters and custom validation are made easy.
77
* Declarative YAML syntax for ROS 2 Parameters converted into C++ or Python struct
88
* Declaring, Getting, Validating, and Updating handled by generated code
99
* Dynamic ROS 2 Parameters made easy
10-
* Custom user specified validator functions
10+
* Custom user-specified validator functions
1111
* Automatically create documentation of parameters
1212

1313
## Basic Usage
@@ -81,7 +81,7 @@ generate_parameter_module(
8181
)
8282
```
8383

84-
### Use generated struct into project source code
84+
### Use generated struct in project source code
8585

8686
**src/turtlesim.cpp**
8787
```c++
@@ -181,7 +181,7 @@ cpp_namespace:
181181
type: int,
182182
default_value: 3,
183183
read_only: true,
184-
description: "A read only integer parameter with a default value of 3",
184+
description: "A read-only integer parameter with a default value of 3",
185185
validation:
186186
# validation functions ...
187187
}
@@ -212,11 +212,11 @@ The types of parameters in ros2 map to C++ types.
212212
| string_fixed_XX | `FixedSizeString<XX>` |
213213
| none | NO CODE GENERATED |
214214

215-
Fixed size types are denoted with a suffix `_fixed_XX`, where `XX` is the desired size.
215+
Fixed-size types are denoted with a suffix `_fixed_XX`, where `XX` is the desired size.
216216
The corresponding C++ type is a data wrapper class for conveniently accessing the data.
217217
Note that any fixed size type will automatically use a `size_lt` validator. Validators are explained in the next section.
218218

219-
The purpose of `none` type is purely documentation, and won't generate any C++ code. See [Parameter documentation](#parameter-documentation) for details.
219+
The purpose of the `none` type is purely documentation, and won't generate any C++ code. See [Parameter documentation](#parameter-documentation) for details.
220220

221221
### Built-In Validators
222222
Validators are C++ functions that take arguments represented by a key-value pair in yaml.
@@ -316,7 +316,7 @@ validation: {
316316
```
317317

318318
### Nested structures
319-
After the top level key, every subsequent non-leaf key will generate a nested c++ struct. The struct instance will have
319+
After the top-level key, every subsequent non-leaf key will generate a nested C++ struct. The struct instance will have
320320
the same name as the key.
321321

322322
```yaml
@@ -328,7 +328,7 @@ cpp_name_space:
328328
}
329329
```
330330

331-
The generated parameter value can then be access with `params.nest1.nest2.param_name`
331+
The generated parameter value can then be accessed with `params.nest1.nest2.param_name`
332332

333333
### Mapped parameters
334334
You can use parameter maps, where a map with keys from another `string_array` parameter is created. Add the `__map_` prefix followed by the key parameter name as follows:
@@ -340,14 +340,27 @@ cpp_name_space:
340340
default_value: ["joint1", "joint2", "joint3"],
341341
description: "specifies which joints will be used by the controller",
342342
}
343+
interfaces: {
344+
type: string_array,
345+
default_value: ["position", "velocity", "acceleration"],
346+
description: "interfaces to be used by the controller",
347+
}
348+
# nested mapped example
349+
gain:
350+
__map_joints: # create a map with joints as keys
351+
__map_interfaces: # create a map with interfaces as keys
352+
value: {
353+
type: double
354+
}
355+
# simple mapped example
343356
pid:
344-
__map_joints: # create a map with joints as keys
345-
param_name: {
346-
type: string_array
357+
__map_joints: # create a map with joints as keys
358+
values: {
359+
type: double_array
347360
}
348361
```
349362

350-
The generated parameter value can then be access with `params.pid.joints_map.at("joint1").param_name`.
363+
The generated parameter value for the nested map example can then be accessed with `params.gain.joints_map.at("joint1").interfaces_map.at("position").value`.
351364

352365
### Use generated struct in Cpp
353366
The generated header file is named based on the target library name you passed as the first argument to the cmake function.
@@ -373,7 +386,7 @@ if (param_listener->is_old(params_)) {
373386
374387
### Parameter documentation
375388
376-
In some case, parameters might be unknown only at compile-time, and cannot be part of the generated C++ code. However, for documentation purpose of such parameters, the type `none` was introduced.
389+
In some cases, parameters might be unknown only at compile-time, and cannot be part of the generated C++ code. However, for documentation purpose of such parameters, the type `none` was introduced.
377390
378391
Parameters with `none` type won't generate any C++ code, but can exist to describe the expected name or namespace, that might be declared by an external piece of code and used in an override.
379392
@@ -421,7 +434,7 @@ force_torque_broadcaster_controller:
421434
See [cpp example](example/) or [python example](example_python/) for complete examples of how to use the generate_parameter_library.
422435
423436
### Generated code output
424-
The generated code is primarily consists of two major components:
437+
The generated code primarily consists of two major components:
425438
1) `struct Params` that contains values of all parameters and
426439
2) `class ParamListener` that handles parameter declaration, updating, and validation.
427440
The general structure is shown below.
@@ -458,7 +471,7 @@ class ParamListener {
458471
// loop over all parameters: perform validation then update
459472
rcl_interfaces::msg::SetParametersResult update(const std::vector<rclcpp::Parameter> &parameters);
460473
461-
// declare all parameters and throw exception if non-optional value is missing or validation fails
474+
// declare all parameters and throw an exception if a non-optional value is missing or validation fails
462475
void declare_params(const std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>& parameters_interface);
463476
464477
private:

example/src/parameters.yaml

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

27+
nested_dynamic:
28+
__map_joints:
29+
__map_dof_names:
30+
nested: {
31+
type: double,
32+
default_value: 1.0,
33+
description: "test nested map params",
34+
validation: {
35+
gt_eq<>: [ 0.0001 ],
36+
}
37+
}
38+
__map_joints:
39+
__map_dof_names:
40+
nested_deep: {
41+
type: double,
42+
default_value: 1.0,
43+
description: "test deep nested map params",
44+
validation: {
45+
gt_eq<>: [ 0.0001 ],
46+
}
47+
}
48+
2749
pid:
2850
rate: {
2951
type: double,

example_python/generate_parameter_module_example/parameters.yaml

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

35+
nested_dynamic:
36+
__map_joints:
37+
__map_dof_names:
38+
nested: {
39+
type: double,
40+
default_value: 1.0,
41+
description: "test nested map params",
42+
validation: {
43+
gt_eq<>: [ 0.0001 ],
44+
}
45+
}
46+
__map_joints:
47+
__map_dof_names:
48+
nested_deep: {
49+
type: double,
50+
default_value: 1.0,
51+
description: "test deep nested map params",
52+
validation: {
53+
gt_eq<>: [ 0.0001 ],
54+
}
55+
}
3556
pid:
3657
rate: {
3758
type: double,

generate_parameter_library_py/generate_parameter_library_py/generate_python_module.py

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -63,7 +63,6 @@ def main():
6363
output_file = args.output_python_module_file
6464
yaml_file = args.input_yaml_file
6565
validate_file = args.validate_file
66-
6766
run(output_file, yaml_file, validate_file)
6867

6968

generate_parameter_library_py/generate_parameter_library_py/jinja_templates/cpp/declare_runtime_parameter

Lines changed: 9 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,10 @@
1-
for (const auto & value : {{param_struct_instance}}.{{mapped_param}}){
2-
{%- filter indent(width=4) %}
3-
auto& entry = {{param_struct_instance}}.{{parameter_map}}[value];
1+
{% for mapped_param in mapped_params -%}
2+
for (const auto & value_{{loop.index}} : updated_params.{{mapped_param}}) {
3+
{% endfor -%}
4+
{%- filter indent(width=4) -%}
5+
auto& entry = {{param_struct_instance}}.{{struct_name}}{% for map in parameter_map%}.{{map}}[value_{{loop.index}}]{% endfor %};
6+
std::string value = fmt::format("{%- for mapped_param in mapped_params -%}{% if loop.index == 1 %}{}{% else %}.{}{% endif -%} {%- endfor -%}",
7+
{%- for mapped_param in mapped_params -%}{% if loop.index == 1 %} value_{{loop.index}}{% else %}, value_{{loop.index}}{% endif -%} {%- endfor %});
48
auto param_name = fmt::format("{}{}.{}.{}", prefix_, "{{struct_name}}", value, "{{parameter_field}}");
59
if (!parameters_interface_->has_parameter(param_name)) {
610
{%- filter indent(width=4) %}
@@ -49,4 +53,6 @@ parameters_interface_->declare_parameter(param_name, parameter, descriptor);
4953
}
5054
{{set_runtime_parameter-}}
5155
{% endfilter -%}
56+
{%- for mapped_param in mapped_params -%}
5257
}
58+
{% endfor -%}
Lines changed: 9 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,20 @@
1-
for (const auto & value : updated_params.{{mapped_param}}){
2-
{%- filter indent(width=4) %}
1+
{% for mapped_param in mapped_params -%}
2+
for (const auto & value_{{loop.index}} : updated_params.{{mapped_param}}) {
3+
{% endfor -%}
4+
{%- filter indent(width=4) -%}
5+
std::string value = fmt::format("{%- for mapped_param in mapped_params -%}{% if loop.index == 1 %}{}{% else %}.{}{% endif -%} {%- endfor -%}",
6+
{%- for mapped_param in mapped_params -%}{% if loop.index == 1 %} value_{{loop.index}}{% else %}, value_{{loop.index}}{% endif -%} {%- endfor %});
37
auto param_name = fmt::format("{}{}.{}.{}", prefix_, "{{struct_name}}", value, "{{parameter_field}}");
48
if (param.get_name() == param_name) {
59
{%- filter indent(width=4) %}
610
{% if parameter_validations|length -%}
711
{{parameter_validations-}}
812
{% endif -%}
9-
updated_params.{{parameter_map}}[value].{{parameter_field}} = param.{{parameter_as_function}};
13+
updated_params.{{struct_name}}{% for map in parameter_map%}.{{map}}[value_{{loop.index}}]{% endfor %}.{{parameter_field}} = param.{{parameter_as_function}};
1014
RCLCPP_DEBUG_STREAM(logger_, param.get_name() << ": " << param.get_type_name() << " = " << param.value_to_string());
1115
{% endfilter -%}
1216
}
1317
{% endfilter -%}
18+
{%- for mapped_param in mapped_params -%}
1419
}
20+
{% endfor -%}

generate_parameter_library_py/generate_parameter_library_py/jinja_templates/python/declare_runtime_parameter

Lines changed: 9 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,12 @@
1-
for value in {{param_struct_instance}}.{{mapped_param}}:
2-
{%- filter indent(width=4) %}
3-
{{param_struct_instance}}.{{struct_name}}.add_entry(value)
4-
entry = {{param_struct_instance}}.{{struct_name}}.get_entry(value)
5-
param_name = f"{self.prefix_}{{struct_name}}.{value}.{{parameter_field}}"
1+
{% for mapped_param in mapped_params -%}
2+
{%- filter indent(width=4*loop.index0) %}
3+
for value_{{loop.index}} in updated_params.{{mapped_param}}:
4+
{%- endfilter -%}
5+
{% endfor -%}
6+
{%- filter indent(width=4*(mapped_params|length)) %}
7+
{{param_struct_instance}}.{{struct_name}}{% for map in parameter_map%}.add_entry(value_{{loop.index}}){% endfor %}
8+
entry = {{param_struct_instance}}.{{struct_name}}{% for map in parameter_map%}.get_entry(value_{{loop.index}}){% endfor %}
9+
param_name = f"{self.prefix_}{{struct_name}}{% for map in parameter_map%}.{value_{{loop.index}}}{% endfor %}.{{parameter_field}}"
610
if not self.node_.has_parameter(self.prefix_ + param_name):
711
{%- filter indent(width=4) %}
812
descriptor = ParameterDescriptor(description="{{parameter_description|valid_string_python}}", read_only = {{parameter_read_only}})

generate_parameter_library_py/generate_parameter_library_py/jinja_templates/python/declare_struct

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@ __map_type = __{{struct_name}}
1515
def add_entry(self, name):
1616
if not hasattr(self, name):
1717
setattr(self, name, self.__map_type())
18+
return getattr(self, name)
1819
def get_entry(self, name):
1920
return getattr(self, name)
2021
{% endif -%}
Lines changed: 8 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,16 @@
1-
for value in updated_params.{{mapped_param}}:
2-
{%- filter indent(width=4) %}
3-
param_name = f"{self.prefix_}{{struct_name}}.{value}.{{parameter_field}}"
1+
{% for mapped_param in mapped_params -%}
2+
{%- filter indent(width=4*loop.index) %}
3+
for value_{{loop.index}} in updated_params.{{mapped_param}}:
4+
{%- endfilter -%}
5+
{% endfor -%}
6+
{%- filter indent(width=4*(1+mapped_params|length)) %}
7+
param_name = f"{self.prefix_}{{struct_name}}{% for map in parameter_map%}.{value_{{loop.index}}}{% endfor %}.{{parameter_field}}"
48
if param.name == param_name:
59
{%- filter indent(width=4) %}
610
{% if parameter_validations|length -%}
711
{{parameter_validations-}}
812
{% endif -%}
9-
updated_params.{{parameter_map}}[value].{{parameter_field}} = param.{{parameter_as_function}}
13+
updated_params.{{struct_name}}{% for map in parameter_map%}.get_entry(value_{{loop.index}}){% endfor %}.{{parameter_field}} = param.{{parameter_as_function}}
1014
self.logger_.debug(param.name + ": " + param.type_.name + " = " + str(param.value))
1115
{% endfilter -%}
1216
{% endfilter -%}

generate_parameter_library_py/generate_parameter_library_py/parse_yaml.py

Lines changed: 18 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -99,14 +99,16 @@ def get_dynamic_parameter_field(yaml_parameter_name: str):
9999

100100
def get_dynamic_mapped_parameter(yaml_parameter_name: str):
101101
tmp = yaml_parameter_name.split('.')
102-
tmp2 = tmp[-2]
103-
mapped_param = tmp2.replace('__map_', '')
104-
return mapped_param
102+
mapped_params = [
103+
val.replace('__map_', '') for val in tmp[:-1] if is_mapped_parameter(val)
104+
]
105+
return mapped_params
105106

106107

107108
def get_dynamic_struct_name(yaml_parameter_name: str):
108109
tmp = yaml_parameter_name.split('.')
109-
struct_name = tmp[:-2]
110+
num_nested = sum([is_mapped_parameter(val) for val in tmp])
111+
struct_name = tmp[: -(num_nested + 1)]
110112
return '.'.join(struct_name)
111113

112114

@@ -119,10 +121,8 @@ def get_dynamic_parameter_name(yaml_parameter_name: str):
119121

120122

121123
def get_dynamic_parameter_map(yaml_parameter_name: str):
122-
tmp = yaml_parameter_name.split('.')
123-
parameter_map = tmp[:-2]
124-
mapped_param = get_dynamic_mapped_parameter(yaml_parameter_name)
125-
parameter_map.append(mapped_param + '_map')
124+
mapped_params = get_dynamic_mapped_parameter(yaml_parameter_name)
125+
parameter_map = [val + '_map' for val in mapped_params]
126126
parameter_map = '.'.join(parameter_map)
127127
return parameter_map
128128

@@ -405,13 +405,14 @@ def __str__(self):
405405
class UpdateRuntimeParameter(UpdateParameterBase):
406406
def __str__(self):
407407
parameter_validations_str = ''.join(str(x) for x in self.parameter_validations)
408-
mapped_param = get_dynamic_mapped_parameter(self.parameter_name)
408+
mapped_params = get_dynamic_mapped_parameter(self.parameter_name)
409409
parameter_map = get_dynamic_parameter_map(self.parameter_name)
410+
parameter_map = parameter_map.split('.')
410411
struct_name = get_dynamic_struct_name(self.parameter_name)
411412
parameter_field = get_dynamic_parameter_field(self.parameter_name)
412413

413414
data = {
414-
'mapped_param': mapped_param,
415+
'mapped_params': mapped_params,
415416
'parameter_map': parameter_map,
416417
'struct_name': struct_name,
417418
'parameter_field': parameter_field,
@@ -556,18 +557,19 @@ def __str__(self):
556557

557558
bool_to_str = self.code_gen_variable.conversation.bool_to_str
558559
parameter_field = get_dynamic_parameter_field(self.parameter_name)
559-
mapped_param = get_dynamic_mapped_parameter(self.parameter_name)
560+
mapped_params = get_dynamic_mapped_parameter(self.parameter_name)
560561
parameter_map = get_dynamic_parameter_map(self.parameter_name)
561562
struct_name = get_dynamic_struct_name(self.parameter_name)
563+
parameter_map = parameter_map.split('.')
562564

563565
data = {
564566
'struct_name': struct_name,
565567
'parameter_type': self.code_gen_variable.get_parameter_type(),
566568
'parameter_description': self.parameter_description,
567569
'parameter_read_only': bool_to_str(self.parameter_read_only),
568570
'parameter_as_function': self.code_gen_variable.parameter_as_function_str(),
569-
'mapped_param': mapped_param,
570-
'mapped_param_underscore': mapped_param.replace('.', '_'),
571+
'mapped_params': mapped_params,
572+
'mapped_param_underscore': [val.replace('.', '_') for val in mapped_params],
571573
'set_runtime_parameter': self.set_runtime_parameter,
572574
'parameter_map': parameter_map,
573575
'param_struct_instance': self.param_struct_instance,
@@ -596,19 +598,20 @@ def __str__(self):
596598
parameter_map = get_dynamic_parameter_map(
597599
self.dynamic_declare_parameter.parameter_name
598600
)
601+
parameter_map = parameter_map.split('.')
599602
struct_name = get_dynamic_struct_name(
600603
self.dynamic_declare_parameter.parameter_name
601604
)
602605
parameter_field = get_dynamic_parameter_field(
603606
self.dynamic_declare_parameter.parameter_name
604607
)
605-
mapped_param = get_dynamic_mapped_parameter(
608+
mapped_params = get_dynamic_mapped_parameter(
606609
self.dynamic_declare_parameter.parameter_name
607610
)
608611

609612
data = {
610613
'parameter_map': parameter_map,
611-
'mapped_param': mapped_param,
614+
'mapped_params': mapped_params,
612615
'dynamic_declare_parameter': str(self.dynamic_declare_parameter),
613616
'struct_name': struct_name,
614617
'parameter_field': parameter_field,

0 commit comments

Comments
 (0)