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
1 change: 1 addition & 0 deletions .github/workflows/ci.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@ jobs:

env:
BASEDIR: ${{ github.workspace }}/.work
UPSTREAM_WORKSPACE: upstream.repos

name: ${{ matrix.env.ROS_DISTRO }}-${{ matrix.env.ROS_REPO }}
runs-on: ubuntu-latest
Expand Down
28 changes: 15 additions & 13 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -250,35 +250,37 @@ The built-in validator functions provided by this package are:
| upper_element_bounds<> | [upper] | Upper bound for each element (inclusive) |

### Custom validator functions
Validators are functions that return a `Result` 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 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.

The `Result` type has a alias `OK` that is shorthand for returning a successful validation.
It also had a function `ERROR` that uses the expressive [fmt format](https://github.com/fmtlib/fmt) for constructing a human readable error.
These come from the `parameter_traits` library.
Note that you need to place your custom validators in the `parameter_traits` namespace.
Here is an example custom allocator.

```c++
#include <parameter_traits/parameter_traits.hpp>
#include <rclcpp/rclcpp.hpp>

#include <fmt/core.h>
#include <tl_expected/expected.hpp>

namespace parameter_traits {
namespace my_project {

Result integer_equal_value(rclcpp::Parameter const& parameter, int expected_value) {
tl::expected<void, std::string> integer_equal_value(
rclcpp::Parameter const& parameter, int expected_value) {
int param_value = parameter.as_int();
if (param_value != expected_value) {
return ERROR("Invalid value {} for parameter {}. Expected {}",
param_value, parameter.get_name(), expected_value);
return tl::make_unexpected(fmt::format(
"Invalid value {} for parameter {}. Expected {}",
param_value, parameter.get_name(), expected_value);
}

return OK;
return {};
}

} // namespace parameter_traits
} // namespace my_project
```
To configure a parameter to be validated with the custom validator function `integer_equal_value` with an `expected_value` of `3` you could would this to the YAML.
```yaml
validation: {
integer_equal_value: [3]
"my_project::integer_equal_value": [3]
}
```

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,34 +28,42 @@

#pragma once

#include <parameter_traits/parameter_traits.hpp>
#include <string>

namespace parameter_traits {
#include <rclcpp/rclcpp.hpp>

#include <fmt/core.h>
#include <tl_expected/expected.hpp>

namespace custom_validators {

// User defined parameter validation
Result validate_double_array_custom_func(const rclcpp::Parameter& parameter,
double max_sum, double max_element) {
tl::expected<void, std::string> validate_double_array_custom_func(
const rclcpp::Parameter& parameter, double max_sum, double max_element) {
const auto& double_array = parameter.as_double_array();
double sum = 0.0;
for (auto val : double_array) {
sum += val;
if (val > max_element) {
return ERROR(
return tl::make_unexpected(fmt::format(
"The parameter contained an element greater than the max allowed "
"value. (%f) was greater than (%f)",
val, max_element);
val, max_element));
}
}
if (sum > max_sum) {
return ERROR(
return tl::make_unexpected(fmt::format(
"The sum of the parameter vector was greater than the max allowed "
"value. (%f) was greater than (%f)",
sum, max_sum);
sum, max_sum));
}

return OK;
return {};
}

Result no_args_validator(const rclcpp::Parameter& parameter) { return OK; }
tl::expected<void, std::string> no_args_validator(
const rclcpp::Parameter& parameter) {
return {};
}

} // namespace parameter_traits
} // namespace custom_validators
4 changes: 2 additions & 2 deletions example/src/parameters.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ admittance_controller:
description: "specifies which algorithm to use for interpolation.",
validation: {
one_of<>: [ [ "spline", "linear" ] ],
no_args_validator: null
"custom_validators::no_args_validator": null
}
}
joints: {
Expand Down Expand Up @@ -218,7 +218,7 @@ admittance_controller:
The values are calculated as damping can be used instead: zeta = D / (2 * sqrt( M * S ))",
validation: {
fixed_size<>: 6,
validate_double_array_custom_func: [ 20.3, 5.0 ],
"custom_validators::validate_double_array_custom_func": [ 20.3, 5.0 ],
element_bounds<>: [ 0.1, 10.0 ]
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,9 @@ function(generate_parameter_library LIB_NAME YAML_FILE)
parameter_traits::parameter_traits
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
rsl::rsl
tcb_span::tcb_span
tl_expected::tl_expected
)
install(DIRECTORY ${LIB_INCLUDE_DIR} DESTINATION include/)
endfunction()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,9 @@
find_package(fmt REQUIRED)
find_package(parameter_traits REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rsl REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(tcb_span REQUIRED)
find_package(tl_expected REQUIRED)

include("${generate_parameter_library_DIR}/generate_parameter_library.cmake")
2 changes: 2 additions & 0 deletions generate_parameter_library/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,9 @@
<depend>parameter_traits</depend>
<depend>rclcpp</depend>
<depend>rclcpp_lifecycle</depend>
<depend>rsl</depend>
<depend>tcb_span</depend>
<depend>tl_expected</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ descriptor.read_only = {{parameter_read_only}};
auto parameter = rclcpp::ParameterType::PARAMETER_{{parameter_type}};
{% endif -%}
{%- if parameter_value|length %}
auto parameter = rclcpp::ParameterValue(updated_params.{{parameter_value}});
auto parameter = to_parameter_value(updated_params.{{parameter_value}});
{% endif -%}
parameters_interface_->declare_parameter(prefix_ + "{{parameter_name}}", parameter, descriptor);
{% endfilter -%}
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
for (const auto & value : {{param_struct_instance}}.{{mapped_param}}){
{%- filter indent(width=4) %}
auto entry = {{param_struct_instance}}.{{parameter_map}}[value];
auto& entry = {{param_struct_instance}}.{{parameter_map}}[value];
auto param_name = fmt::format("{}{}.{}.{}", prefix_, "{{struct_name}}", value, "{{parameter_field}}");
if (!parameters_interface_->has_parameter(param_name)) {
{%- filter indent(width=4) %}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,54 @@

#include <parameter_traits/parameter_traits.hpp>

#include <rsl/static_string.hpp>
#include <rsl/static_vector.hpp>
#include <rsl/parameter_validators.hpp>

{% if user_validation_file|length -%}
#include "{{user_validation_file}}"
{% endif %}

namespace {{namespace}} {

// Use validators from RSL
using rsl::unique;
using rsl::subset_of;
using rsl::fixed_size;
using rsl::size_gt;
using rsl::size_lt;
using rsl::not_empty;
using rsl::element_bounds;
using rsl::lower_element_bounds;
using rsl::upper_element_bounds;
using rsl::bounds;
using rsl::upper_bounds;
using rsl::lower_bounds;
using rsl::lt;
using rsl::gt;
using rsl::lt_eq;
using rsl::gt_eq;
using rsl::one_of;
using rsl::to_parameter_result_msg;

// temporarily needed for backwards compatibility for custom validators
using namespace parameter_traits;

template <typename T>
[[nodiscard]] auto to_parameter_value(T value) {
return rclcpp::ParameterValue(value);
}

template <size_t capacity>
[[nodiscard]] auto to_parameter_value(rsl::StaticString<capacity> const& value) {
return rclcpp::ParameterValue(rsl::to_string(value));
}

template <typename T, size_t capacity>
[[nodiscard]] auto to_parameter_value(rsl::StaticVector<T, capacity> const& value) {
return rclcpp::ParameterValue(rsl::to_vector(value));
}

{%- filter indent(width=4) %}
struct Params {
{%- filter indent(width=4) %}
Expand Down Expand Up @@ -118,7 +160,7 @@ struct StackParams {
{%- endif %}
updated_params.__stamp = clock_.now();
update_interal_params(updated_params);
return parameter_traits::OK;
return rsl::to_parameter_result_msg({});
}

void declare_params(){
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
if(auto validation_result = parameter_traits::{{validation_function}};
!validation_result.success()) {
if(auto validation_result = {{validation_function}};
!validation_result) {
{%- filter indent(width=4) %}
{{invalid_effect}}
{% endfilter -%}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ def initialization_fail_validation(param_name: str) -> str:
return (
f"throw rclcpp::exceptions::InvalidParameterValueException"
f'(fmt::format("Invalid value set during initialization for '
f"parameter '{param_name}': \" + validation_result.error_msg()));"
f"parameter '{param_name}': \" + validation_result.error()));"
)


Expand All @@ -96,7 +96,7 @@ def initialization_pass_validation(param_name: str, parameter_conversion: str) -

@typechecked
def update_parameter_fail_validation() -> str:
return "return validation_result;"
return "return rsl::to_parameter_result_msg(validation_result);"


@typechecked
Expand Down Expand Up @@ -272,10 +272,10 @@ class CodeGenVariableBase:
"double_array": lambda defined_type, templates: "std::vector<double>",
"int_array": lambda defined_type, templates: "std::vector<int64_t>",
"string_array": lambda defined_type, templates: "std::vector<std::string>",
"double_array_fixed": lambda defined_type, templates: f"parameter_traits::FixedSizeArray<{templates[0]}, {templates[1]}>",
"int_array_fixed": lambda defined_type, templates: f"parameter_traits::FixedSizeArray<{templates[0]}, {templates[1]}>",
"string_array_fixed": lambda defined_type, templates: f"parameter_traits::FixedSizeArray<{templates[0]}, {templates[1]}>",
"string_fixed": lambda defined_type, templates: f"parameter_traits::FixedSizeString<{templates[1]}>",
"double_array_fixed": lambda defined_type, templates: f"rsl::StaticVector<{templates[0]}, {templates[1]}>",
"int_array_fixed": lambda defined_type, templates: f"rsl::StaticVector<{templates[0]}, {templates[1]}>",
"string_array_fixed": lambda defined_type, templates: f"rsl::StaticVector<{templates[0]}, {templates[1]}>",
"string_fixed": lambda defined_type, templates: f"rsl::StaticString<{templates[1]}>",
}
yaml_type_to_as_function = {
"string_array": "as_string_array()",
Expand Down
8 changes: 5 additions & 3 deletions parameter_traits/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,9 @@ project(parameter_traits)
find_package(ament_cmake REQUIRED)
find_package(fmt REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rsl REQUIRED)
find_package(tcb_span REQUIRED)
find_package(tl_expected REQUIRED)

add_library(parameter_traits INTERFACE)
target_include_directories(parameter_traits INTERFACE
Expand All @@ -16,7 +18,9 @@ target_link_libraries(parameter_traits
INTERFACE
fmt::fmt
rclcpp::rclcpp
rsl::rsl
tcb_span::tcb_span
tl_expected::tl_expected
)

if(BUILD_TESTING)
Expand All @@ -25,8 +29,6 @@ if(BUILD_TESTING)
set(ament_cmake_cpplint_FOUND TRUE) # Conflicts with clang-foramt
set(ament_cmake_uncrustify_FOUND TRUE) # Conflicts with clang-format
ament_lint_auto_find_test_dependencies()

add_subdirectory(test)
endif()

install(
Expand All @@ -44,5 +46,5 @@ install(
)

ament_export_targets(export_parameter_traits HAS_LIBRARY_TARGET)
ament_export_dependencies(fmt rclcpp tcb_span)
ament_export_dependencies(fmt rclcpp rsl tcb_span tl_expected)
ament_package()
48 changes: 0 additions & 48 deletions parameter_traits/include/parameter_traits/comparison.hpp

This file was deleted.

Loading