From f642b2c1270b26e3c0925bfa69fd3746a980c90c Mon Sep 17 00:00:00 2001 From: Tyler Weaver Date: Thu, 29 Sep 2022 15:40:48 -0600 Subject: [PATCH] lt/gt/lt_eq/gt_eq validators Signed-off-by: Tyler Weaver --- README.md | 4 ++ .../include/parameter_traits/validators.hpp | 51 ++++++++++++----- parameter_traits/test/validators_tests.cpp | 56 +++++++++++++++++++ 3 files changed, 96 insertions(+), 15 deletions(-) diff --git a/README.md b/README.md index a55ecd2..466120f 100644 --- a/README.md +++ b/README.md @@ -221,6 +221,10 @@ The built-in validator functions provided by this package are: | bounds<> | [lower, upper] | Bounds checking (inclusive) | | lower_bounds<> | [lower] | Lower bounds (inclusive) | | upper_bounds<> | [upper] | Upper bounds (inclusive) | +| lt<> | [value] | parameter < value | +| gt<> | [value] | parameter > value | +| lt_eq<> | [value] | parameter <= value (upper_bounds) | +| gt_eq<> | [value] | parameter >= value (lower_bounds) | | one_of<> | [[val1, val2, ...]] | Value is one of the specified values | **String validators** diff --git a/parameter_traits/include/parameter_traits/validators.hpp b/parameter_traits/include/parameter_traits/validators.hpp index c208ca2..86f2156 100644 --- a/parameter_traits/include/parameter_traits/validators.hpp +++ b/parameter_traits/include/parameter_traits/validators.hpp @@ -168,26 +168,47 @@ Result bounds(const rclcpp::Parameter& parameter, T lower, T upper) { return OK; } -template -Result lower_bounds(const rclcpp::Parameter& parameter, T lower) { - auto param_value = parameter.get_value(); - if (param_value < lower) { - return ERROR( - "Invalid value '{}' for parameter '{}'. Required lower bounds: {}", - param_value, parameter.get_name(), lower); +template +Result cmp(rclcpp::Parameter const& parameter, T value, + std::string const& cmp_str, Fn predicate) { + if (auto const param_value = parameter.get_value(); + !predicate(param_value, value)) { + return ERROR("Invalid value '{}' for parameter '{}'. Required {}: {}", + param_value, parameter.get_name(), cmp_str, value); } + return OK; } template -Result upper_bounds(const rclcpp::Parameter& parameter, T upper) { - auto param_value = parameter.get_value(); - if (param_value > upper) { - return ERROR( - "Invalid value '{}' for parameter '{}'. Required upper bounds: {}", - param_value, parameter.get_name(), upper); - } - return OK; +Result lower_bounds(rclcpp::Parameter const& parameter, T value) { + return cmp(parameter, value, "lower bounds", std::greater_equal{}); +} + +template +Result upper_bounds(const rclcpp::Parameter& parameter, T value) { + return cmp(parameter, value, "upper bounds", std::less_equal{}); +} + +template +Result lt(const rclcpp::Parameter& parameter, T value) { + return cmp(parameter, value, "less than", std::less{}); +} + +template +Result gt(const rclcpp::Parameter& parameter, T value) { + return cmp(parameter, value, "greater than", std::greater{}); +} + +template +Result lt_eq(const rclcpp::Parameter& parameter, T value) { + return cmp(parameter, value, "less than or equal", std::less_equal{}); +} + +template +Result gt_eq(const rclcpp::Parameter& parameter, T value) { + return cmp(parameter, value, "greater than or equal", + std::greater_equal{}); } template diff --git a/parameter_traits/test/validators_tests.cpp b/parameter_traits/test/validators_tests.cpp index eb2996e..2f5083c 100644 --- a/parameter_traits/test/validators_tests.cpp +++ b/parameter_traits/test/validators_tests.cpp @@ -88,6 +88,62 @@ TEST(ValidatorsTests, UpperBounds) { EXPECT_TRUE(upper_bounds(Parameter{"", true}, true).success()); } +TEST(ValidatorsTests, GreaterThan) { + EXPECT_FALSE(gt(Parameter{"", 2.0}, 2.0).success()); + EXPECT_TRUE(gt(Parameter{"", 4.3}, 1.0).success()); + EXPECT_FALSE(gt(Parameter{"", -4.3}, 1.0).success()); + + EXPECT_FALSE(gt(Parameter{"", 1}, 1).success()); + EXPECT_TRUE(gt(Parameter{"", 4}, 1).success()); + EXPECT_FALSE(gt(Parameter{"", -4}, 1).success()); + + EXPECT_TRUE(gt(Parameter{"", true}, false).success()); + EXPECT_FALSE(gt(Parameter{"", false}, true).success()); + EXPECT_FALSE(gt(Parameter{"", true}, true).success()); +} + +TEST(ValidatorsTests, LessThan) { + EXPECT_FALSE(lt(Parameter{"", 2.0}, 2.0).success()); + EXPECT_FALSE(lt(Parameter{"", 4.3}, 1.0).success()); + EXPECT_TRUE(lt(Parameter{"", -4.3}, 1.0).success()); + + EXPECT_FALSE(lt(Parameter{"", 1}, 1).success()); + EXPECT_FALSE(lt(Parameter{"", 4}, 1).success()); + EXPECT_TRUE(lt(Parameter{"", -4}, 1).success()); + + EXPECT_FALSE(lt(Parameter{"", true}, false).success()); + EXPECT_TRUE(lt(Parameter{"", false}, true).success()); + EXPECT_FALSE(lt(Parameter{"", true}, true).success()); +} + +TEST(ValidatorsTests, GreaterThanOrEqual) { + EXPECT_TRUE(gt_eq(Parameter{"", 2.0}, 2.0).success()); + EXPECT_TRUE(gt_eq(Parameter{"", 4.3}, 1.0).success()); + EXPECT_FALSE(gt_eq(Parameter{"", -4.3}, 1.0).success()); + + EXPECT_TRUE(gt_eq(Parameter{"", 1}, 1).success()); + EXPECT_TRUE(gt_eq(Parameter{"", 4}, 1).success()); + EXPECT_FALSE(gt_eq(Parameter{"", -4}, 1).success()); + + EXPECT_TRUE(gt_eq(Parameter{"", true}, false).success()); + EXPECT_FALSE(gt_eq(Parameter{"", false}, true).success()); + EXPECT_TRUE(gt_eq(Parameter{"", true}, true).success()); +} + +TEST(ValidatorsTests, LessThanOrEqual) { + EXPECT_TRUE(lt_eq(Parameter{"", 2.0}, 2.0).success()); + EXPECT_FALSE(lt_eq(Parameter{"", 4.3}, 1.0).success()); + EXPECT_TRUE(lt_eq(Parameter{"", -4.3}, 1.0).success()); + + EXPECT_TRUE(lt_eq(Parameter{"", 1}, 1).success()); + EXPECT_FALSE(lt_eq(Parameter{"", 4}, 1).success()); + EXPECT_TRUE(lt_eq(Parameter{"", -4}, 1).success()); + + EXPECT_FALSE(lt_eq(Parameter{"", true}, false).success()); + EXPECT_TRUE(lt_eq(Parameter{"", false}, true).success()); + EXPECT_TRUE(lt_eq(Parameter{"", true}, true).success()); +} + TEST(ValidatorsTests, OneOf) { EXPECT_TRUE( one_of(Parameter{"", 2.0}, std::vector{2.0}).success());