Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -264,6 +264,8 @@ The built-in validator functions provided by this package are:
| gt_eq<> | [value] | parameter >= value |
| one_of<> | [[val1, val2, ...]] | Value is one of the specified values |

Note: `lt<>`, `gt<>`, `lt_eq<>`, or `gt_eq<>` cannot be used together with `bounds<>`.

**String validators**
| Function | Arguments | Description |
| ------------ | ------------------- | ---------------------------------------------- |
Expand All @@ -286,6 +288,8 @@ The built-in validator functions provided by this package are:
| lower_element_bounds<> | [lower] | Lower bound for each element (inclusive) |
| upper_element_bounds<> | [upper] | Upper bound for each element (inclusive) |

Note: `element_bounds<>` cannot be mixed with `lower_element_bounds<>` or `upper_element_bounds<>`.

### Custom validator functions
Validators are functions that return a `tl::expected<void, std::string>` type and accept a `rclcpp::Parameter const&` as their first argument and any number of arguments after that can be specified in YAML.
Validators are C++ functions defined in a header file similar to the example shown below.
Expand Down
32 changes: 32 additions & 0 deletions example/src/parameters.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,15 @@ admittance_controller:
validation:
gt<>: [0.0]

limit:
type: double_array
description: "specifies limit for x, y and z axis"
default_value: [0.0, 0.0, 0.0]
validation:
fixed_size<>: 3
lower_element_bounds<>: -10.0
upper_element_bounds<>: 10.0

nested_dynamic:
__map_joints:
__map_dof_names:
Expand Down Expand Up @@ -223,6 +232,15 @@ admittance_controller:
validation:
element_bounds: [ 0.0001, 100000.0 ]

acceleration_limits:
type: double_array
description: "specifies maximum acceleration limits for x, y and z axis"
default_value: [0.0, 0.0, 0.0]
validation:
fixed_size<>: 3
lower_element_bounds<>: -10.0
upper_element_bounds<>: 10.0

# general settings
enable_parameter_update_without_reactivation:
type: bool
Expand All @@ -244,6 +262,20 @@ admittance_controller:
description: "should be a number greater than 15"
validation:
gt<>: [ 15 ]
gt_fifteen_lt_eq_twenty:
type: int
default_value: 20
description: "should be a number greater than 15 and less than or equal to 20"
validation:
gt<>: [ 15 ]
lt_eq<>: [ 20 ]
gt_fifteen_lt_twenty:
type: int
default_value: 16
description: "should be a number greater than 15 and less than 20"
validation:
gt<>: [ 15 ]
lt<>: [ 20 ]
one_number:
type: int
default_value: 14540
Expand Down
32 changes: 32 additions & 0 deletions example_python/generate_parameter_module_example/parameters.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,15 @@ admittance_controller:
validation:
gt<>: [0.0]

limit:
type: double_array
description: "specifies limit for x, y and z axis"
default_value: [0.0, 0.0, 0.0]
validation:
fixed_size<>: 3
lower_element_bounds<>: -10.0
upper_element_bounds<>: 10.0

nested_dynamic:
__map_joints:
__map_dof_names:
Expand Down Expand Up @@ -226,6 +235,15 @@ admittance_controller:
validation:
element_bounds: [ 0.0001, 100000.0 ]

acceleration_limits:
type: double_array
description: "specifies maximum acceleration limits for x, y and z axis"
default_value: [0.0, 0.0, 0.0]
validation:
fixed_size<>: 3
lower_element_bounds<>: -10.0
upper_element_bounds<>: 10.0

# general settings
enable_parameter_update_without_reactivation:
type: bool
Expand All @@ -247,6 +265,20 @@ admittance_controller:
description: "should be a number greater than 15"
validation:
gt<>: [ 15 ]
gt_fifteen_lt_eq_twenty:
type: int
default_value: 20
description: "should be a number greater than 15 and less than or equal to 20"
validation:
gt<>: [ 15 ]
lt_eq<>: [ 20 ]
gt_fifteen_lt_twenty:
type: int
default_value: 16
description: "should be a number greater than 15 and less than 20"
validation:
gt<>: [ 15 ]
lt<>: [ 20 ]
one_number:
type: int
default_value: 14540
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,37 +6,41 @@ descriptor.read_only = {{parameter_read_only}};
{%- if parameter_additional_constraints|length %}
descriptor.additional_constraints = {{parameter_additional_constraints | valid_string_cpp}};
{% endif -%}
{%- for validation in parameter_validations if ("bounds" in validation.function_name or "lt" in validation.function_name or "gt" in validation.function_name) %}
{%- if "DOUBLE" in parameter_type %}
{%- set range = namespace(lower=None, upper=None) %}
{%- for validation in parameter_validations if ("bounds" in validation.function_name or "lt" in validation.function_name or "gt" in validation.function_name) %}
{%- if validation.arguments|length == 2 %}
descriptor.floating_point_range.resize({{loop.index}});
descriptor.floating_point_range.at({{loop.index0}}).from_value = {{validation.arguments[0]}};
descriptor.floating_point_range.at({{loop.index0}}).to_value = {{validation.arguments[1]}};
{%- set range.lower = validation.arguments[0] %}
{%- set range.upper = validation.arguments[1] %}
{%- elif ("lower" in validation.function_name or "gt" == validation.function_base_name or "gt_eq" == validation.function_base_name) and validation.arguments|length == 1 %}
descriptor.floating_point_range.resize({{loop.index}});
descriptor.floating_point_range.at({{loop.index0}}).from_value = {{validation.arguments[0]}};
descriptor.floating_point_range.at({{loop.index0}}).to_value = std::numeric_limits<double>::max();
{%- set range.lower = validation.arguments[0] %}
{%- elif ("upper" in validation.function_name or "lt" == validation.function_base_name or "lt_eq" == validation.function_base_name) and validation.arguments|length == 1 %}
descriptor.floating_point_range.resize({{loop.index}});
descriptor.floating_point_range.at({{loop.index0}}).from_value = std::numeric_limits<double>::lowest();
descriptor.floating_point_range.at({{loop.index0}}).to_value = {{validation.arguments[0]}};
{%- set range.upper = validation.arguments[0] %}
{%- endif %}
{%- endfor %}
{%- if range.lower is not none or range.upper is not none %}
descriptor.floating_point_range.resize(1);
descriptor.floating_point_range.at(0).from_value = {{range.lower if range.lower is not none else "std::numeric_limits<double>::lowest()"}};
descriptor.floating_point_range.at(0).to_value = {{range.upper if range.upper is not none else "std::numeric_limits<double>::max()"}};
{%- endif %}
{%- elif "INTEGER" in parameter_type %}
{%- set range = namespace(lower=None, upper=None) %}
{%- for validation in parameter_validations if ("bounds" in validation.function_name or "lt" in validation.function_name or "gt" in validation.function_name) %}
{%- if validation.arguments|length == 2 %}
descriptor.integer_range.resize({{loop.index}});
descriptor.integer_range.at({{loop.index0}}).from_value = {{validation.arguments[0]}};
descriptor.integer_range.at({{loop.index0}}).to_value = {{validation.arguments[1]}};
{%- set range.lower = validation.arguments[0] %}
{%- set range.upper = validation.arguments[1] %}
{%- elif ("lower" in validation.function_name or "gt" == validation.function_base_name or "gt_eq" == validation.function_base_name) and validation.arguments|length == 1 %}
descriptor.integer_range.resize({{loop.index}});
descriptor.integer_range.at({{loop.index0}}).from_value = {{validation.arguments[0]}};
descriptor.integer_range.at({{loop.index0}}).to_value = std::numeric_limits<int64_t>::max();
{%- set range.lower = validation.arguments[0] %}
{%- elif ("upper" in validation.function_name or "lt" == validation.function_base_name or "lt_eq" == validation.function_base_name) and validation.arguments|length == 1 %}
descriptor.integer_range.resize({{loop.index}});
descriptor.integer_range.at({{loop.index0}}).from_value = std::numeric_limits<int64_t>::lowest();
descriptor.integer_range.at({{loop.index0}}).to_value = {{validation.arguments[0]}};
{%- endif %}
{%- set range.upper = validation.arguments[0] %}
{%- endif %}
{%- endfor %}
{%- if range.lower is not none or range.upper is not none %}
descriptor.integer_range.resize(1);
descriptor.integer_range.at(0).from_value = {{range.lower if range.lower is not none else "std::numeric_limits<int64_t>::lowest()"}};
descriptor.integer_range.at(0).to_value = {{range.upper if range.upper is not none else "std::numeric_limits<int64_t>::max()"}};
{%- endif %}
{%- endif %}
{%- if not parameter_value|length %}
auto parameter = rclcpp::ParameterType::PARAMETER_{{parameter_type}};
{% endif -%}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,37 +22,41 @@ descriptor.read_only = {{parameter_read_only}};
{%- if parameter_additional_constraints|length %}
descriptor.additional_constraints = {{parameter_additional_constraints | valid_string_cpp}};
{% endif -%}
{%- for validation in parameter_validations if ("bounds" in validation.function_name or "lt" in validation.function_name or "gt" in validation.function_name) %}
{%- if "DOUBLE" in parameter_type %}
{%- set range = namespace(lower=None, upper=None) %}
{%- for validation in parameter_validations if ("bounds" in validation.function_name or "lt" in validation.function_name or "gt" in validation.function_name) %}
{%- if validation.arguments|length == 2 %}
descriptor.floating_point_range.resize({{loop.index}});
descriptor.floating_point_range.at({{loop.index0}}).from_value = {{validation.arguments[0]}};
descriptor.floating_point_range.at({{loop.index0}}).to_value = {{validation.arguments[1]}};
{%- set range.lower = validation.arguments[0] %}
{%- set range.upper = validation.arguments[1] %}
{%- elif ("lower" in validation.function_name or "gt" == validation.function_base_name or "gt_eq" == validation.function_base_name) and validation.arguments|length == 1 %}
descriptor.floating_point_range.resize({{loop.index}});
descriptor.floating_point_range.at({{loop.index0}}).from_value = {{validation.arguments[0]}};
descriptor.floating_point_range.at({{loop.index0}}).to_value = std::numeric_limits<double>::max();
{%- set range.lower = validation.arguments[0] %}
{%- elif ("upper" in validation.function_name or "lt" == validation.function_base_name or "lt_eq" == validation.function_base_name) and validation.arguments|length == 1 %}
descriptor.floating_point_range.resize({{loop.index}});
descriptor.floating_point_range.at({{loop.index0}}).from_value = std::numeric_limits<double>::lowest();
descriptor.floating_point_range.at({{loop.index0}}).to_value = {{validation.arguments[0]}};
{%- set range.upper = validation.arguments[0] %}
{%- endif %}
{%- endfor %}
{%- if range.lower is not none or range.upper is not none %}
descriptor.floating_point_range.resize(1);
descriptor.floating_point_range.at(0).from_value = {{range.lower if range.lower is not none else "std::numeric_limits<double>::lowest()"}};
descriptor.floating_point_range.at(0).to_value = {{range.upper if range.upper is not none else "std::numeric_limits<double>::max()"}};
{%- endif %}
{%- elif "INTEGER" in parameter_type %}
{%- set range = namespace(lower=None, upper=None) %}
{%- for validation in parameter_validations if ("bounds" in validation.function_name or "lt" in validation.function_name or "gt" in validation.function_name) %}
{%- if validation.arguments|length == 2 %}
descriptor.integer_range.resize({{loop.index}});
descriptor.integer_range.at({{loop.index0}}).from_value = {{validation.arguments[0]}};
descriptor.integer_range.at({{loop.index0}}).to_value = {{validation.arguments[1]}};
{%- set range.lower = validation.arguments[0] %}
{%- set range.upper = validation.arguments[1] %}
{%- elif ("lower" in validation.function_name or "gt" == validation.function_base_name or "gt_eq" == validation.function_base_name) and validation.arguments|length == 1 %}
descriptor.integer_range.resize({{loop.index}});
descriptor.integer_range.at({{loop.index0}}).from_value = {{validation.arguments[0]}};
descriptor.integer_range.at({{loop.index0}}).to_value = std::numeric_limits<int64_t>::max();
{%- set range.lower = validation.arguments[0] %}
{%- elif ("upper" in validation.function_name or "lt" == validation.function_base_name or "lt_eq" == validation.function_base_name) and validation.arguments|length == 1 %}
descriptor.integer_range.resize({{loop.index}});
descriptor.integer_range.at({{loop.index0}}).from_value = std::numeric_limits<int64_t>::lowest();
descriptor.integer_range.at({{loop.index0}}).to_value = {{validation.arguments[0]}};
{%- endif %}
{%- set range.upper = validation.arguments[0] %}
{%- endif %}
{%- endfor %}
{%- if range.lower is not none or range.upper is not none %}
descriptor.integer_range.resize(1);
descriptor.integer_range.at(0).from_value = {{range.lower if range.lower is not none else "std::numeric_limits<int64_t>::lowest()"}};
descriptor.integer_range.at(0).to_value = {{range.upper if range.upper is not none else "std::numeric_limits<int64_t>::max()"}};
{%- endif %}
{%- endif %}
{%- if not default_value|length %}
auto parameter = rclcpp::ParameterType::PARAMETER_{{parameter_type}};
{% endif -%}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,37 +4,41 @@ descriptor = ParameterDescriptor(description=r"{{parameter_description|valid_str
{%- if parameter_additional_constraints|length %}
descriptor.additional_constraints = "{{parameter_additional_constraints|valid_string_python}}"
{% endif -%}
{%- for validation in parameter_validations if ("bounds" in validation.function_name or "lt" in validation.function_name or "gt" in validation.function_name) %}
{%- if "DOUBLE" in parameter_type %}
{%- set range = namespace(lower=None, upper=None) %}
{%- for validation in parameter_validations if ("bounds" in validation.function_name or "lt" in validation.function_name or "gt" in validation.function_name) %}
{%- if validation.arguments|length == 2 %}
descriptor.floating_point_range.append(FloatingPointRange())
descriptor.floating_point_range[-1].from_value = {{validation.arguments[0]}}
descriptor.floating_point_range[-1].to_value = {{validation.arguments[1]}}
{%- set range.lower = validation.arguments[0] %}
{%- set range.upper = validation.arguments[1] %}
{%- elif ("lower" in validation.function_name or "gt" == validation.function_base_name or "gt_eq" == validation.function_base_name) and validation.arguments|length == 1 %}
descriptor.floating_point_range.append(FloatingPointRange())
descriptor.floating_point_range[-1].from_value = {{validation.arguments[0]}}
descriptor.floating_point_range[-1].to_value = float('inf')
{%- set range.lower = validation.arguments[0] %}
{%- elif ("upper" in validation.function_name or "lt" == validation.function_base_name or "lt_eq" == validation.function_base_name) and validation.arguments|length == 1 %}
{%- set range.upper = validation.arguments[0] %}
{%- endif %}
{%- endfor %}
{%- if range.lower is not none or range.upper is not none %}
descriptor.floating_point_range.append(FloatingPointRange())
descriptor.floating_point_range[-1].from_value = -float('inf')
descriptor.floating_point_range[-1].to_value = {{validation.arguments[0]}}
descriptor.floating_point_range[-1].from_value = {{range.lower if range.lower is not none else "-float('inf')"}}
descriptor.floating_point_range[-1].to_value = {{range.upper if range.upper is not none else "float('inf')"}}
{%- endif %}
{%- elif "INTEGER" in parameter_type %}
{%- set range = namespace(lower=None, upper=None) %}
{%- for validation in parameter_validations if ("bounds" in validation.function_name or "lt" in validation.function_name or "gt" in validation.function_name) %}
{%- if validation.arguments|length == 2 %}
descriptor.integer_range.append(IntegerRange())
descriptor.integer_range[-1].from_value = {{validation.arguments[0]}}
descriptor.integer_range[-1].to_value = {{validation.arguments[1]}}
{%- set range.lower = validation.arguments[0] %}
{%- set range.upper = validation.arguments[1] %}
{%- elif ("lower" in validation.function_name or "gt" == validation.function_base_name or "gt_eq" == validation.function_base_name) and validation.arguments|length == 1 %}
descriptor.integer_range.append(IntegerRange())
descriptor.integer_range[-1].from_value = {{validation.arguments[0]}}
descriptor.integer_range[-1].to_value = 2**31-1
{%- set range.lower = validation.arguments[0] %}
{%- elif ("upper" in validation.function_name or "lt" == validation.function_base_name or "lt_eq" == validation.function_base_name) and validation.arguments|length == 1 %}
{%- set range.upper = validation.arguments[0] %}
{%- endif %}
{%- endfor %}
{%- if range.lower is not none or range.upper is not none %}
descriptor.integer_range.append(IntegerRange())
descriptor.integer_range[-1].from_value = -2**31-1
descriptor.integer_range[-1].to_value = {{validation.arguments[0]}}
descriptor.integer_range[-1].from_value = {{range.lower if range.lower is not none else "-2**31-1"}}
descriptor.integer_range[-1].to_value = {{range.upper if range.upper is not none else "2**31-1"}}
{%- endif %}
{%- endif %}
{%- endfor %}
{%- if not parameter_value|length %}
parameter = rclpy.Parameter.Type.{{parameter_type}}
{% endif -%}
Expand Down
Loading
Loading