Skip to content

Commit 44b5576

Browse files
authored
Migrate from parameter_traits to RSL (take 2) (#91)
1 parent 93b8955 commit 44b5576

File tree

23 files changed

+147
-1076
lines changed

23 files changed

+147
-1076
lines changed

.github/workflows/ci.yaml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,7 @@ jobs:
2727

2828
env:
2929
BASEDIR: ${{ github.workspace }}/.work
30+
UPSTREAM_WORKSPACE: upstream.repos
3031

3132
name: ${{ matrix.env.ROS_DISTRO }}-${{ matrix.env.ROS_REPO }}
3233
runs-on: ubuntu-latest

README.md

Lines changed: 15 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -250,35 +250,37 @@ The built-in validator functions provided by this package are:
250250
| upper_element_bounds<> | [upper] | Upper bound for each element (inclusive) |
251251

252252
### Custom validator functions
253-
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.
253+
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.
254254
Validators are C++ functions defined in a header file similar to the example shown below.
255255

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

261258
```c++
262-
#include <parameter_traits/parameter_traits.hpp>
259+
#include <rclcpp/rclcpp.hpp>
260+
261+
#include <fmt/core.h>
262+
#include <tl_expected/expected.hpp>
263263

264-
namespace parameter_traits {
264+
namespace my_project {
265265

266-
Result integer_equal_value(rclcpp::Parameter const& parameter, int expected_value) {
266+
tl::expected<void, std::string> integer_equal_value(
267+
rclcpp::Parameter const& parameter, int expected_value) {
267268
int param_value = parameter.as_int();
268269
if (param_value != expected_value) {
269-
return ERROR("Invalid value {} for parameter {}. Expected {}",
270-
param_value, parameter.get_name(), expected_value);
270+
return tl::make_unexpected(fmt::format(
271+
"Invalid value {} for parameter {}. Expected {}",
272+
param_value, parameter.get_name(), expected_value);
271273
}
272274

273-
return OK;
275+
return {};
274276
}
275277

276-
} // namespace parameter_traits
278+
} // namespace my_project
277279
```
278280
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.
279281
```yaml
280282
validation: {
281-
integer_equal_value: [3]
283+
"my_project::integer_equal_value": [3]
282284
}
283285
```
284286

example/include/generate_parameter_library_example/example_validators.hpp

Lines changed: 19 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -28,34 +28,42 @@
2828

2929
#pragma once
3030

31-
#include <parameter_traits/parameter_traits.hpp>
31+
#include <string>
3232

33-
namespace parameter_traits {
33+
#include <rclcpp/rclcpp.hpp>
34+
35+
#include <fmt/core.h>
36+
#include <tl_expected/expected.hpp>
37+
38+
namespace custom_validators {
3439

3540
// User defined parameter validation
36-
Result validate_double_array_custom_func(const rclcpp::Parameter& parameter,
37-
double max_sum, double max_element) {
41+
tl::expected<void, std::string> validate_double_array_custom_func(
42+
const rclcpp::Parameter& parameter, double max_sum, double max_element) {
3843
const auto& double_array = parameter.as_double_array();
3944
double sum = 0.0;
4045
for (auto val : double_array) {
4146
sum += val;
4247
if (val > max_element) {
43-
return ERROR(
48+
return tl::make_unexpected(fmt::format(
4449
"The parameter contained an element greater than the max allowed "
4550
"value. (%f) was greater than (%f)",
46-
val, max_element);
51+
val, max_element));
4752
}
4853
}
4954
if (sum > max_sum) {
50-
return ERROR(
55+
return tl::make_unexpected(fmt::format(
5156
"The sum of the parameter vector was greater than the max allowed "
5257
"value. (%f) was greater than (%f)",
53-
sum, max_sum);
58+
sum, max_sum));
5459
}
5560

56-
return OK;
61+
return {};
5762
}
5863

59-
Result no_args_validator(const rclcpp::Parameter& parameter) { return OK; }
64+
tl::expected<void, std::string> no_args_validator(
65+
const rclcpp::Parameter& parameter) {
66+
return {};
67+
}
6068

61-
} // namespace parameter_traits
69+
} // namespace custom_validators

example/src/parameters.yaml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,7 @@ admittance_controller:
1010
description: "specifies which algorithm to use for interpolation.",
1111
validation: {
1212
one_of<>: [ [ "spline", "linear" ] ],
13-
no_args_validator: null
13+
"custom_validators::no_args_validator": null
1414
}
1515
}
1616
joints: {
@@ -218,7 +218,7 @@ admittance_controller:
218218
The values are calculated as damping can be used instead: zeta = D / (2 * sqrt( M * S ))",
219219
validation: {
220220
fixed_size<>: 6,
221-
validate_double_array_custom_func: [ 20.3, 5.0 ],
221+
"custom_validators::validate_double_array_custom_func": [ 20.3, 5.0 ],
222222
element_bounds<>: [ 0.1, 10.0 ]
223223
}
224224
}

generate_parameter_library/cmake/generate_parameter_library.cmake

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -85,7 +85,9 @@ function(generate_parameter_library LIB_NAME YAML_FILE)
8585
parameter_traits::parameter_traits
8686
rclcpp::rclcpp
8787
rclcpp_lifecycle::rclcpp_lifecycle
88+
rsl::rsl
8889
tcb_span::tcb_span
90+
tl_expected::tl_expected
8991
)
9092
install(DIRECTORY ${LIB_INCLUDE_DIR} DESTINATION include/)
9193
endfunction()

generate_parameter_library/generate_parameter_library-extras.cmake

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,9 @@
2929
find_package(fmt REQUIRED)
3030
find_package(parameter_traits REQUIRED)
3131
find_package(rclcpp REQUIRED)
32+
find_package(rsl REQUIRED)
3233
find_package(rclcpp_lifecycle REQUIRED)
3334
find_package(tcb_span REQUIRED)
35+
find_package(tl_expected REQUIRED)
3436

3537
include("${generate_parameter_library_DIR}/generate_parameter_library.cmake")

generate_parameter_library/package.xml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,9 @@
1616
<depend>parameter_traits</depend>
1717
<depend>rclcpp</depend>
1818
<depend>rclcpp_lifecycle</depend>
19+
<depend>rsl</depend>
1920
<depend>tcb_span</depend>
21+
<depend>tl_expected</depend>
2022

2123
<test_depend>ament_lint_auto</test_depend>
2224
<test_depend>ament_lint_common</test_depend>

generate_parameter_library_py/generate_parameter_library_py/jinja_templates/declare_parameter

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@ descriptor.read_only = {{parameter_read_only}};
77
auto parameter = rclcpp::ParameterType::PARAMETER_{{parameter_type}};
88
{% endif -%}
99
{%- if parameter_value|length %}
10-
auto parameter = rclcpp::ParameterValue(updated_params.{{parameter_value}});
10+
auto parameter = to_parameter_value(updated_params.{{parameter_value}});
1111
{% endif -%}
1212
parameters_interface_->declare_parameter(prefix_ + "{{parameter_name}}", parameter, descriptor);
1313
{% endfilter -%}

generate_parameter_library_py/generate_parameter_library_py/jinja_templates/declare_runtime_parameter

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
for (const auto & value : {{param_struct_instance}}.{{mapped_param}}){
22
{%- filter indent(width=4) %}
3-
auto entry = {{param_struct_instance}}.{{parameter_map}}[value];
3+
auto& entry = {{param_struct_instance}}.{{parameter_map}}[value];
44
auto param_name = fmt::format("{}{}.{}.{}", prefix_, "{{struct_name}}", value, "{{parameter_field}}");
55
if (!parameters_interface_->has_parameter(param_name)) {
66
{%- filter indent(width=4) %}

generate_parameter_library_py/generate_parameter_library_py/jinja_templates/parameter_library_header

Lines changed: 43 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -20,12 +20,54 @@
2020

2121
#include <parameter_traits/parameter_traits.hpp>
2222

23+
#include <rsl/static_string.hpp>
24+
#include <rsl/static_vector.hpp>
25+
#include <rsl/parameter_validators.hpp>
26+
2327
{% if user_validation_file|length -%}
2428
#include "{{user_validation_file}}"
2529
{% endif %}
2630

2731
namespace {{namespace}} {
2832

33+
// Use validators from RSL
34+
using rsl::unique;
35+
using rsl::subset_of;
36+
using rsl::fixed_size;
37+
using rsl::size_gt;
38+
using rsl::size_lt;
39+
using rsl::not_empty;
40+
using rsl::element_bounds;
41+
using rsl::lower_element_bounds;
42+
using rsl::upper_element_bounds;
43+
using rsl::bounds;
44+
using rsl::upper_bounds;
45+
using rsl::lower_bounds;
46+
using rsl::lt;
47+
using rsl::gt;
48+
using rsl::lt_eq;
49+
using rsl::gt_eq;
50+
using rsl::one_of;
51+
using rsl::to_parameter_result_msg;
52+
53+
// temporarily needed for backwards compatibility for custom validators
54+
using namespace parameter_traits;
55+
56+
template <typename T>
57+
[[nodiscard]] auto to_parameter_value(T value) {
58+
return rclcpp::ParameterValue(value);
59+
}
60+
61+
template <size_t capacity>
62+
[[nodiscard]] auto to_parameter_value(rsl::StaticString<capacity> const& value) {
63+
return rclcpp::ParameterValue(rsl::to_string(value));
64+
}
65+
66+
template <typename T, size_t capacity>
67+
[[nodiscard]] auto to_parameter_value(rsl::StaticVector<T, capacity> const& value) {
68+
return rclcpp::ParameterValue(rsl::to_vector(value));
69+
}
70+
2971
{%- filter indent(width=4) %}
3072
struct Params {
3173
{%- filter indent(width=4) %}
@@ -118,7 +160,7 @@ struct StackParams {
118160
{%- endif %}
119161
updated_params.__stamp = clock_.now();
120162
update_interal_params(updated_params);
121-
return parameter_traits::OK;
163+
return rsl::to_parameter_result_msg({});
122164
}
123165

124166
void declare_params(){

0 commit comments

Comments
 (0)