diff --git a/README.md b/README.md index b54f345..40fcd6b 100644 --- a/README.md +++ b/README.md @@ -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 | | ------------ | ------------------- | ---------------------------------------------- | @@ -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` 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. diff --git a/example/src/parameters.yaml b/example/src/parameters.yaml index 5f46ad8..4eb222e 100644 --- a/example/src/parameters.yaml +++ b/example/src/parameters.yaml @@ -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: @@ -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 @@ -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 diff --git a/example_python/generate_parameter_module_example/parameters.yaml b/example_python/generate_parameter_module_example/parameters.yaml index acd6463..df33939 100644 --- a/example_python/generate_parameter_module_example/parameters.yaml +++ b/example_python/generate_parameter_module_example/parameters.yaml @@ -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: @@ -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 @@ -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 diff --git a/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/cpp/declare_parameter b/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/cpp/declare_parameter index 51e4fb4..c0896e2 100644 --- a/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/cpp/declare_parameter +++ b/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/cpp/declare_parameter @@ -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::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::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::lowest()"}}; +descriptor.floating_point_range.at(0).to_value = {{range.upper if range.upper is not none else "std::numeric_limits::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::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::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::lowest()"}}; +descriptor.integer_range.at(0).to_value = {{range.upper if range.upper is not none else "std::numeric_limits::max()"}}; +{%- endif %} +{%- endif %} {%- if not parameter_value|length %} auto parameter = rclcpp::ParameterType::PARAMETER_{{parameter_type}}; {% endif -%} diff --git a/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/cpp/declare_runtime_parameter b/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/cpp/declare_runtime_parameter index 625a842..935bb17 100644 --- a/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/cpp/declare_runtime_parameter +++ b/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/cpp/declare_runtime_parameter @@ -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::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::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::lowest()"}}; +descriptor.floating_point_range.at(0).to_value = {{range.upper if range.upper is not none else "std::numeric_limits::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::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::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::lowest()"}}; +descriptor.integer_range.at(0).to_value = {{range.upper if range.upper is not none else "std::numeric_limits::max()"}}; +{%- endif %} +{%- endif %} {%- if not default_value|length %} auto parameter = rclcpp::ParameterType::PARAMETER_{{parameter_type}}; {% endif -%} diff --git a/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/python/declare_parameter b/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/python/declare_parameter index 312a001..bc71a37 100644 --- a/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/python/declare_parameter +++ b/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/python/declare_parameter @@ -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 -%} diff --git a/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/python/declare_runtime_parameter b/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/python/declare_runtime_parameter index 4d98938..a74ca2c 100644 --- a/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/python/declare_runtime_parameter +++ b/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/python/declare_runtime_parameter @@ -19,37 +19,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 default_value|length %} parameter = rclpy.Parameter.Type.{{parameter_type}} {% endif -%} diff --git a/generate_parameter_library_py/generate_parameter_library_py/parse_yaml.py b/generate_parameter_library_py/generate_parameter_library_py/parse_yaml.py index ed00d29..060980f 100644 --- a/generate_parameter_library_py/generate_parameter_library_py/parse_yaml.py +++ b/generate_parameter_library_py/generate_parameter_library_py/parse_yaml.py @@ -98,6 +98,36 @@ def int_to_integer_str(value: str): return value.replace('int', 'integer') +@typechecked +def validation_base_name(function_name: str): + return function_name.replace('<>', '') + + +@typechecked +def validate_validator_combinations(param_name: str, validations_dict: dict): + validation_names = {validation_base_name(name) for name in validations_dict} + + if 'element_bounds' in validation_names and { + 'lower_element_bounds', + 'upper_element_bounds', + }.intersection(validation_names): + raise compile_error( + "Parameter {} cannot combine 'element_bounds' with 'lower_element_bounds/upper_element_bounds'.".format( + param_name + ) + ) + + scalar_bound_validators = {'gt', 'gt_eq', 'lt', 'lt_eq'} + if 'bounds' in validation_names and validation_names.intersection( + scalar_bound_validators + ): + raise compile_error( + "Parameter {} cannot combine 'bounds' with scalar bound validators " + "(gt/gt_eq/lt/lt_eq). Use only 'bounds<>' for inclusive ranges, " + 'or only scalar bound validators.'.format(param_name) + ) + + def get_dynamic_parameter_field(yaml_parameter_name: str): tmp = yaml_parameter_name.split('.') num_nested = [i for i, val in enumerate(tmp) if is_mapped_parameter(val)] @@ -745,6 +775,8 @@ def preprocess_inputs(language, name, value, nested_name_list): if is_fixed_type(defined_type): validations_dict['size_lt<>'] = fixed_type_size(defined_type) + 1 + validate_validator_combinations(param_name, validations_dict) + for func_name in validations_dict: args = validations_dict[func_name] if args is not None and not isinstance(args, list): diff --git a/generate_parameter_library_py/generate_parameter_library_py/test/YAML_parse_error_test.py b/generate_parameter_library_py/generate_parameter_library_py/test/YAML_parse_error_test.py index eb524b7..2800766 100644 --- a/generate_parameter_library_py/generate_parameter_library_py/test/YAML_parse_error_test.py +++ b/generate_parameter_library_py/generate_parameter_library_py/test/YAML_parse_error_test.py @@ -74,6 +74,8 @@ def set_up(yaml_test_file): 'missing_type.yaml', 'invalid_syntax.yaml', 'invalid_parameter_type.yaml', + 'conflicting_element_bounds.yaml', + 'conflicting_scalar_bounds_with_bounds.yaml', ] ], ) diff --git a/generate_parameter_library_py/generate_parameter_library_py/test/conflicting_element_bounds.yaml b/generate_parameter_library_py/generate_parameter_library_py/test/conflicting_element_bounds.yaml new file mode 100644 index 0000000..2f56e5e --- /dev/null +++ b/generate_parameter_library_py/generate_parameter_library_py/test/conflicting_element_bounds.yaml @@ -0,0 +1,8 @@ +admittance_controller: + acceleration_limits: + type: double_array + description: "specifies maximum acceleration limits for x, y and z axis" + validation: + fixed_size<>: 3 + element_bounds<>: [-10.0, 20.0] + upper_element_bounds<>: 10.0 diff --git a/generate_parameter_library_py/generate_parameter_library_py/test/conflicting_scalar_bounds_with_bounds.yaml b/generate_parameter_library_py/generate_parameter_library_py/test/conflicting_scalar_bounds_with_bounds.yaml new file mode 100644 index 0000000..52c3e3b --- /dev/null +++ b/generate_parameter_library_py/generate_parameter_library_py/test/conflicting_scalar_bounds_with_bounds.yaml @@ -0,0 +1,8 @@ +admittance_controller: + conflicting_bounds: + type: int + default_value: 16 + description: "should be a number between 10 and 20" + validation: + bounds<>: [ 10, 20 ] + lt_eq<>: [ 20 ] diff --git a/generate_parameter_library_py/generate_parameter_library_py/test/valid_parameters.yaml b/generate_parameter_library_py/generate_parameter_library_py/test/valid_parameters.yaml index 6142a45..571c09d 100644 --- a/generate_parameter_library_py/generate_parameter_library_py/test/valid_parameters.yaml +++ b/generate_parameter_library_py/generate_parameter_library_py/test/valid_parameters.yaml @@ -34,6 +34,37 @@ admittance_controller: type: double default_value: 1.0 description: "derivative gain term" + + 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 + + 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 ] + acceleration_limits: + type: double_array + description: "specifies maximum acceleration limits for x, y and z axis" + validation: + fixed_size<>: 3 + lower_element_bounds<>: -10.0 + upper_element_bounds<>: 10.0 fixed_string: type: string_fixed_25 default_value: "string_value" diff --git a/generate_parameter_library_py/setup.py b/generate_parameter_library_py/setup.py index 1a9b4b8..92ec109 100644 --- a/generate_parameter_library_py/setup.py +++ b/generate_parameter_library_py/setup.py @@ -55,6 +55,16 @@ 'share/' + package_name + '/test', ['generate_parameter_library_py/test/invalid_parameter_type.yaml'], ), + ( + 'share/' + package_name + '/test', + ['generate_parameter_library_py/test/conflicting_element_bounds.yaml'], + ), + ( + 'share/' + package_name + '/test', + [ + 'generate_parameter_library_py/test/conflicting_scalar_bounds_with_bounds.yaml' + ], + ), ( 'share/' + package_name + '/test', ['generate_parameter_library_py/test/valid_parameters.yaml'],