Skip to content

Commit

Permalink
Support nested mapped parameters (#166)
Browse files Browse the repository at this point in the history
  • Loading branch information
pac48 authored Mar 8, 2024
1 parent 4b50b98 commit 032a74d
Show file tree
Hide file tree
Showing 10 changed files with 124 additions and 45 deletions.
41 changes: 27 additions & 14 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ Additionally, dynamic parameters and custom validation are made easy.
* Declarative YAML syntax for ROS 2 Parameters converted into C++ or Python struct
* Declaring, Getting, Validating, and Updating handled by generated code
* Dynamic ROS 2 Parameters made easy
* Custom user specified validator functions
* Custom user-specified validator functions
* Automatically create documentation of parameters

## Basic Usage
Expand Down Expand Up @@ -81,7 +81,7 @@ generate_parameter_module(
)
```

### Use generated struct into project source code
### Use generated struct in project source code

**src/turtlesim.cpp**
```c++
Expand Down Expand Up @@ -181,7 +181,7 @@ cpp_namespace:
type: int,
default_value: 3,
read_only: true,
description: "A read only integer parameter with a default value of 3",
description: "A read-only integer parameter with a default value of 3",
validation:
# validation functions ...
}
Expand Down Expand Up @@ -212,11 +212,11 @@ The types of parameters in ros2 map to C++ types.
| string_fixed_XX | `FixedSizeString<XX>` |
| none | NO CODE GENERATED |

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

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

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

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

```yaml
Expand All @@ -328,7 +328,7 @@ cpp_name_space:
}
```

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

### Mapped parameters
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:
Expand All @@ -340,14 +340,27 @@ cpp_name_space:
default_value: ["joint1", "joint2", "joint3"],
description: "specifies which joints will be used by the controller",
}
interfaces: {
type: string_array,
default_value: ["position", "velocity", "acceleration"],
description: "interfaces to be used by the controller",
}
# nested mapped example
gain:
__map_joints: # create a map with joints as keys
__map_interfaces: # create a map with interfaces as keys
value: {
type: double
}
# simple mapped example
pid:
__map_joints: # create a map with joints as keys
param_name: {
type: string_array
__map_joints: # create a map with joints as keys
values: {
type: double_array
}
```

The generated parameter value can then be access with `params.pid.joints_map.at("joint1").param_name`.
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`.

### Use generated struct in Cpp
The generated header file is named based on the target library name you passed as the first argument to the cmake function.
Expand All @@ -373,7 +386,7 @@ if (param_listener->is_old(params_)) {
### Parameter documentation
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.
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.
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.
Expand Down Expand Up @@ -421,7 +434,7 @@ force_torque_broadcaster_controller:
See [cpp example](example/) or [python example](example_python/) for complete examples of how to use the generate_parameter_library.
### Generated code output
The generated code is primarily consists of two major components:
The generated code primarily consists of two major components:
1) `struct Params` that contains values of all parameters and
2) `class ParamListener` that handles parameter declaration, updating, and validation.
The general structure is shown below.
Expand Down Expand Up @@ -458,7 +471,7 @@ class ParamListener {
// loop over all parameters: perform validation then update
rcl_interfaces::msg::SetParametersResult update(const std::vector<rclcpp::Parameter> &parameters);
// declare all parameters and throw exception if non-optional value is missing or validation fails
// declare all parameters and throw an exception if a non-optional value is missing or validation fails
void declare_params(const std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>& parameters_interface);
private:
Expand Down
22 changes: 22 additions & 0 deletions example/src/parameters.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,28 @@ admittance_controller:
description: "specifies which joints will be used by the controller",
}

nested_dynamic:
__map_joints:
__map_dof_names:
nested: {
type: double,
default_value: 1.0,
description: "test nested map params",
validation: {
gt_eq<>: [ 0.0001 ],
}
}
__map_joints:
__map_dof_names:
nested_deep: {
type: double,
default_value: 1.0,
description: "test deep nested map params",
validation: {
gt_eq<>: [ 0.0001 ],
}
}

pid:
rate: {
type: double,
Expand Down
21 changes: 21 additions & 0 deletions example_python/generate_parameter_module_example/parameters.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,27 @@ admittance_controller:
description: "specifies which joints will be used by the controller",
}

nested_dynamic:
__map_joints:
__map_dof_names:
nested: {
type: double,
default_value: 1.0,
description: "test nested map params",
validation: {
gt_eq<>: [ 0.0001 ],
}
}
__map_joints:
__map_dof_names:
nested_deep: {
type: double,
default_value: 1.0,
description: "test deep nested map params",
validation: {
gt_eq<>: [ 0.0001 ],
}
}
pid:
rate: {
type: double,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,6 @@ def main():
output_file = args.output_python_module_file
yaml_file = args.input_yaml_file
validate_file = args.validate_file

run(output_file, yaml_file, validate_file)


Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,10 @@
for (const auto & value : {{param_struct_instance}}.{{mapped_param}}){
{%- filter indent(width=4) %}
auto& entry = {{param_struct_instance}}.{{parameter_map}}[value];
{% for mapped_param in mapped_params -%}
for (const auto & value_{{loop.index}} : updated_params.{{mapped_param}}) {
{% endfor -%}
{%- filter indent(width=4) -%}
auto& entry = {{param_struct_instance}}.{{struct_name}}{% for map in parameter_map%}.{{map}}[value_{{loop.index}}]{% endfor %};
std::string value = fmt::format("{%- for mapped_param in mapped_params -%}{% if loop.index == 1 %}{}{% else %}.{}{% endif -%} {%- endfor -%}",
{%- for mapped_param in mapped_params -%}{% if loop.index == 1 %} value_{{loop.index}}{% else %}, value_{{loop.index}}{% endif -%} {%- endfor %});
auto param_name = fmt::format("{}{}.{}.{}", prefix_, "{{struct_name}}", value, "{{parameter_field}}");
if (!parameters_interface_->has_parameter(param_name)) {
{%- filter indent(width=4) %}
Expand Down Expand Up @@ -49,4 +53,6 @@ parameters_interface_->declare_parameter(param_name, parameter, descriptor);
}
{{set_runtime_parameter-}}
{% endfilter -%}
{%- for mapped_param in mapped_params -%}
}
{% endfor -%}
Original file line number Diff line number Diff line change
@@ -1,14 +1,20 @@
for (const auto & value : updated_params.{{mapped_param}}){
{%- filter indent(width=4) %}
{% for mapped_param in mapped_params -%}
for (const auto & value_{{loop.index}} : updated_params.{{mapped_param}}) {
{% endfor -%}
{%- filter indent(width=4) -%}
std::string value = fmt::format("{%- for mapped_param in mapped_params -%}{% if loop.index == 1 %}{}{% else %}.{}{% endif -%} {%- endfor -%}",
{%- for mapped_param in mapped_params -%}{% if loop.index == 1 %} value_{{loop.index}}{% else %}, value_{{loop.index}}{% endif -%} {%- endfor %});
auto param_name = fmt::format("{}{}.{}.{}", prefix_, "{{struct_name}}", value, "{{parameter_field}}");
if (param.get_name() == param_name) {
{%- filter indent(width=4) %}
{% if parameter_validations|length -%}
{{parameter_validations-}}
{% endif -%}
updated_params.{{parameter_map}}[value].{{parameter_field}} = param.{{parameter_as_function}};
updated_params.{{struct_name}}{% for map in parameter_map%}.{{map}}[value_{{loop.index}}]{% endfor %}.{{parameter_field}} = param.{{parameter_as_function}};
RCLCPP_DEBUG_STREAM(logger_, param.get_name() << ": " << param.get_type_name() << " = " << param.value_to_string());
{% endfilter -%}
}
{% endfilter -%}
{%- for mapped_param in mapped_params -%}
}
{% endfor -%}
Original file line number Diff line number Diff line change
@@ -1,8 +1,12 @@
for value in {{param_struct_instance}}.{{mapped_param}}:
{%- filter indent(width=4) %}
{{param_struct_instance}}.{{struct_name}}.add_entry(value)
entry = {{param_struct_instance}}.{{struct_name}}.get_entry(value)
param_name = f"{self.prefix_}{{struct_name}}.{value}.{{parameter_field}}"
{% for mapped_param in mapped_params -%}
{%- filter indent(width=4*loop.index0) %}
for value_{{loop.index}} in updated_params.{{mapped_param}}:
{%- endfilter -%}
{% endfor -%}
{%- filter indent(width=4*(mapped_params|length)) %}
{{param_struct_instance}}.{{struct_name}}{% for map in parameter_map%}.add_entry(value_{{loop.index}}){% endfor %}
entry = {{param_struct_instance}}.{{struct_name}}{% for map in parameter_map%}.get_entry(value_{{loop.index}}){% endfor %}
param_name = f"{self.prefix_}{{struct_name}}{% for map in parameter_map%}.{value_{{loop.index}}}{% endfor %}.{{parameter_field}}"
if not self.node_.has_parameter(self.prefix_ + param_name):
{%- filter indent(width=4) %}
descriptor = ParameterDescriptor(description="{{parameter_description|valid_string_python}}", read_only = {{parameter_read_only}})
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ __map_type = __{{struct_name}}
def add_entry(self, name):
if not hasattr(self, name):
setattr(self, name, self.__map_type())
return getattr(self, name)
def get_entry(self, name):
return getattr(self, name)
{% endif -%}
Original file line number Diff line number Diff line change
@@ -1,12 +1,16 @@
for value in updated_params.{{mapped_param}}:
{%- filter indent(width=4) %}
param_name = f"{self.prefix_}{{struct_name}}.{value}.{{parameter_field}}"
{% for mapped_param in mapped_params -%}
{%- filter indent(width=4*loop.index) %}
for value_{{loop.index}} in updated_params.{{mapped_param}}:
{%- endfilter -%}
{% endfor -%}
{%- filter indent(width=4*(1+mapped_params|length)) %}
param_name = f"{self.prefix_}{{struct_name}}{% for map in parameter_map%}.{value_{{loop.index}}}{% endfor %}.{{parameter_field}}"
if param.name == param_name:
{%- filter indent(width=4) %}
{% if parameter_validations|length -%}
{{parameter_validations-}}
{% endif -%}
updated_params.{{parameter_map}}[value].{{parameter_field}} = param.{{parameter_as_function}}
updated_params.{{struct_name}}{% for map in parameter_map%}.get_entry(value_{{loop.index}}){% endfor %}.{{parameter_field}} = param.{{parameter_as_function}}
self.logger_.debug(param.name + ": " + param.type_.name + " = " + str(param.value))
{% endfilter -%}
{% endfilter -%}
Original file line number Diff line number Diff line change
Expand Up @@ -99,14 +99,16 @@ def get_dynamic_parameter_field(yaml_parameter_name: str):

def get_dynamic_mapped_parameter(yaml_parameter_name: str):
tmp = yaml_parameter_name.split('.')
tmp2 = tmp[-2]
mapped_param = tmp2.replace('__map_', '')
return mapped_param
mapped_params = [
val.replace('__map_', '') for val in tmp[:-1] if is_mapped_parameter(val)
]
return mapped_params


def get_dynamic_struct_name(yaml_parameter_name: str):
tmp = yaml_parameter_name.split('.')
struct_name = tmp[:-2]
num_nested = sum([is_mapped_parameter(val) for val in tmp])
struct_name = tmp[: -(num_nested + 1)]
return '.'.join(struct_name)


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


def get_dynamic_parameter_map(yaml_parameter_name: str):
tmp = yaml_parameter_name.split('.')
parameter_map = tmp[:-2]
mapped_param = get_dynamic_mapped_parameter(yaml_parameter_name)
parameter_map.append(mapped_param + '_map')
mapped_params = get_dynamic_mapped_parameter(yaml_parameter_name)
parameter_map = [val + '_map' for val in mapped_params]
parameter_map = '.'.join(parameter_map)
return parameter_map

Expand Down Expand Up @@ -405,13 +405,14 @@ def __str__(self):
class UpdateRuntimeParameter(UpdateParameterBase):
def __str__(self):
parameter_validations_str = ''.join(str(x) for x in self.parameter_validations)
mapped_param = get_dynamic_mapped_parameter(self.parameter_name)
mapped_params = get_dynamic_mapped_parameter(self.parameter_name)
parameter_map = get_dynamic_parameter_map(self.parameter_name)
parameter_map = parameter_map.split('.')
struct_name = get_dynamic_struct_name(self.parameter_name)
parameter_field = get_dynamic_parameter_field(self.parameter_name)

data = {
'mapped_param': mapped_param,
'mapped_params': mapped_params,
'parameter_map': parameter_map,
'struct_name': struct_name,
'parameter_field': parameter_field,
Expand Down Expand Up @@ -556,18 +557,19 @@ def __str__(self):

bool_to_str = self.code_gen_variable.conversation.bool_to_str
parameter_field = get_dynamic_parameter_field(self.parameter_name)
mapped_param = get_dynamic_mapped_parameter(self.parameter_name)
mapped_params = get_dynamic_mapped_parameter(self.parameter_name)
parameter_map = get_dynamic_parameter_map(self.parameter_name)
struct_name = get_dynamic_struct_name(self.parameter_name)
parameter_map = parameter_map.split('.')

data = {
'struct_name': struct_name,
'parameter_type': self.code_gen_variable.get_parameter_type(),
'parameter_description': self.parameter_description,
'parameter_read_only': bool_to_str(self.parameter_read_only),
'parameter_as_function': self.code_gen_variable.parameter_as_function_str(),
'mapped_param': mapped_param,
'mapped_param_underscore': mapped_param.replace('.', '_'),
'mapped_params': mapped_params,
'mapped_param_underscore': [val.replace('.', '_') for val in mapped_params],
'set_runtime_parameter': self.set_runtime_parameter,
'parameter_map': parameter_map,
'param_struct_instance': self.param_struct_instance,
Expand Down Expand Up @@ -596,19 +598,20 @@ def __str__(self):
parameter_map = get_dynamic_parameter_map(
self.dynamic_declare_parameter.parameter_name
)
parameter_map = parameter_map.split('.')
struct_name = get_dynamic_struct_name(
self.dynamic_declare_parameter.parameter_name
)
parameter_field = get_dynamic_parameter_field(
self.dynamic_declare_parameter.parameter_name
)
mapped_param = get_dynamic_mapped_parameter(
mapped_params = get_dynamic_mapped_parameter(
self.dynamic_declare_parameter.parameter_name
)

data = {
'parameter_map': parameter_map,
'mapped_param': mapped_param,
'mapped_params': mapped_params,
'dynamic_declare_parameter': str(self.dynamic_declare_parameter),
'struct_name': struct_name,
'parameter_field': parameter_field,
Expand Down

0 comments on commit 032a74d

Please sign in to comment.