From 1c0c5cab12d8e33f3a7497f2b52281285a9e41ec Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Denis=20=C5=A0togl?= Date: Tue, 16 May 2023 09:00:18 +0200 Subject: [PATCH] Deprecations in generate_parameter_library. --- .../validate_jtc_parameters.hpp | 48 +++++++++++-------- ...oint_trajectory_controller_parameters.yaml | 6 +-- 2 files changed, 31 insertions(+), 23 deletions(-) diff --git a/joint_trajectory_controller/include/joint_trajectory_controller/validate_jtc_parameters.hpp b/joint_trajectory_controller/include/joint_trajectory_controller/validate_jtc_parameters.hpp index 09363eebb1..91c652013e 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/validate_jtc_parameters.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/validate_jtc_parameters.hpp @@ -16,12 +16,16 @@ #define JOINT_TRAJECTORY_CONTROLLER__VALIDATE_JTC_PARAMETERS_HPP_ #include +#include #include "parameter_traits/parameter_traits.hpp" +#include "rsl/algorithm.hpp" +#include "tl_expected/expected.hpp" namespace parameter_traits { -Result command_interface_type_combinations(rclcpp::Parameter const & parameter) +tl::expected command_interface_type_combinations( + rclcpp::Parameter const & parameter) { auto const & interface_types = parameter.as_string_array(); @@ -31,33 +35,37 @@ Result command_interface_type_combinations(rclcpp::Parameter const & parameter) // 2. position [velocity, [acceleration]] if ( - contains(interface_types, "velocity") && interface_types.size() > 1 && - !contains(interface_types, "position")) + rsl::contains>(interface_types, "velocity") && + interface_types.size() > 1 && + !rsl::contains>(interface_types, "position")) { - return ERROR( + return tl::make_unexpected( "'velocity' command interface can be used either alone or 'position' " "interface has to be present"); } if ( - contains(interface_types, "acceleration") && - (!contains(interface_types, "velocity") && - !contains(interface_types, "position"))) + rsl::contains>(interface_types, "acceleration") && + (!rsl::contains>(interface_types, "velocity") && + !rsl::contains>(interface_types, "position"))) { - return ERROR( + return tl::make_unexpected( "'acceleration' command interface can only be used if 'velocity' and " "'position' interfaces are present"); } - if (contains(interface_types, "effort") && interface_types.size() > 1) + if ( + rsl::contains>(interface_types, "effort") && + interface_types.size() > 1) { - return ERROR("'effort' command interface has to be used alone"); + return tl::make_unexpected("'effort' command interface has to be used alone"); } - return OK; + return {}; } -Result state_interface_type_combinations(rclcpp::Parameter const & parameter) +tl::expected state_interface_type_combinations( + rclcpp::Parameter const & parameter) { auto const & interface_types = parameter.as_string_array(); @@ -65,25 +73,25 @@ Result state_interface_type_combinations(rclcpp::Parameter const & parameter) // 1. position [velocity, [acceleration]] if ( - contains(interface_types, "velocity") && - !contains(interface_types, "position")) + rsl::contains>(interface_types, "velocity") && + !rsl::contains>(interface_types, "position")) { - return ERROR( + return tl::make_unexpected( "'velocity' state interface cannot be used if 'position' interface " "is missing."); } if ( - contains(interface_types, "acceleration") && - (!contains(interface_types, "position") || - !contains(interface_types, "velocity"))) + rsl::contains>(interface_types, "acceleration") && + (!rsl::contains>(interface_types, "position") || + !rsl::contains>(interface_types, "velocity"))) { - return ERROR( + return tl::make_unexpected( "'acceleration' state interface cannot be used if 'position' and 'velocity' " "interfaces are not present."); } - return OK; + return {}; } } // namespace parameter_traits diff --git a/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml b/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml index f767b15b27..e710b33d07 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml +++ b/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml @@ -55,7 +55,7 @@ joint_trajectory_controller: default_value: 50.0, description: "Rate controller state is published", validation: { - lower_bounds: [0.1] + gt_eq: [0.1] } } action_monitor_rate: { @@ -63,7 +63,7 @@ joint_trajectory_controller: default_value: 20.0, description: "Rate status changes will be monitored", validation: { - lower_bounds: [0.1] + gt_eq: [0.1] } } interpolation_method: { @@ -117,7 +117,7 @@ joint_trajectory_controller: default_value: 0.0, description: "Time tolerance for achieving trajectory goal before or after commanded time.", validation: { - lower_bounds: [0.0], + gt_eq: [0.0], } } __map_joints: