Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

lt/gt/lt_eq/gt_eq validators #80

Merged
merged 1 commit into from
Sep 29, 2022
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
4 changes: 4 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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**
Expand Down
51 changes: 36 additions & 15 deletions parameter_traits/include/parameter_traits/validators.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -168,26 +168,47 @@ Result bounds(const rclcpp::Parameter& parameter, T lower, T upper) {
return OK;
}

template <typename T>
Result lower_bounds(const rclcpp::Parameter& parameter, T lower) {
auto param_value = parameter.get_value<T>();
if (param_value < lower) {
return ERROR(
"Invalid value '{}' for parameter '{}'. Required lower bounds: {}",
param_value, parameter.get_name(), lower);
template <typename T, typename Fn>
Result cmp(rclcpp::Parameter const& parameter, T value,
std::string const& cmp_str, Fn predicate) {
if (auto const param_value = parameter.get_value<T>();
!predicate(param_value, value)) {
return ERROR("Invalid value '{}' for parameter '{}'. Required {}: {}",
param_value, parameter.get_name(), cmp_str, value);
}

return OK;
}

template <typename T>
Result upper_bounds(const rclcpp::Parameter& parameter, T upper) {
auto param_value = parameter.get_value<T>();
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<T>{});
}

template <typename T>
Result upper_bounds(const rclcpp::Parameter& parameter, T value) {
return cmp(parameter, value, "upper bounds", std::less_equal<T>{});
}

template <typename T>
Result lt(const rclcpp::Parameter& parameter, T value) {
return cmp(parameter, value, "less than", std::less<T>{});
}

template <typename T>
Result gt(const rclcpp::Parameter& parameter, T value) {
return cmp(parameter, value, "greater than", std::greater<T>{});
}

template <typename T>
Result lt_eq(const rclcpp::Parameter& parameter, T value) {
return cmp(parameter, value, "less than or equal", std::less_equal<T>{});
}

template <typename T>
Result gt_eq(const rclcpp::Parameter& parameter, T value) {
return cmp(parameter, value, "greater than or equal",
std::greater_equal<T>{});
}

template <typename T>
Expand Down
56 changes: 56 additions & 0 deletions parameter_traits/test/validators_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,62 @@ TEST(ValidatorsTests, UpperBounds) {
EXPECT_TRUE(upper_bounds<bool>(Parameter{"", true}, true).success());
}

TEST(ValidatorsTests, GreaterThan) {
EXPECT_FALSE(gt<double>(Parameter{"", 2.0}, 2.0).success());
EXPECT_TRUE(gt<double>(Parameter{"", 4.3}, 1.0).success());
EXPECT_FALSE(gt<double>(Parameter{"", -4.3}, 1.0).success());

EXPECT_FALSE(gt<int64_t>(Parameter{"", 1}, 1).success());
EXPECT_TRUE(gt<int64_t>(Parameter{"", 4}, 1).success());
EXPECT_FALSE(gt<int64_t>(Parameter{"", -4}, 1).success());

EXPECT_TRUE(gt<bool>(Parameter{"", true}, false).success());
EXPECT_FALSE(gt<bool>(Parameter{"", false}, true).success());
EXPECT_FALSE(gt<bool>(Parameter{"", true}, true).success());
}

TEST(ValidatorsTests, LessThan) {
EXPECT_FALSE(lt<double>(Parameter{"", 2.0}, 2.0).success());
EXPECT_FALSE(lt<double>(Parameter{"", 4.3}, 1.0).success());
EXPECT_TRUE(lt<double>(Parameter{"", -4.3}, 1.0).success());

EXPECT_FALSE(lt<int64_t>(Parameter{"", 1}, 1).success());
EXPECT_FALSE(lt<int64_t>(Parameter{"", 4}, 1).success());
EXPECT_TRUE(lt<int64_t>(Parameter{"", -4}, 1).success());

EXPECT_FALSE(lt<bool>(Parameter{"", true}, false).success());
EXPECT_TRUE(lt<bool>(Parameter{"", false}, true).success());
EXPECT_FALSE(lt<bool>(Parameter{"", true}, true).success());
}

TEST(ValidatorsTests, GreaterThanOrEqual) {
EXPECT_TRUE(gt_eq<double>(Parameter{"", 2.0}, 2.0).success());
EXPECT_TRUE(gt_eq<double>(Parameter{"", 4.3}, 1.0).success());
EXPECT_FALSE(gt_eq<double>(Parameter{"", -4.3}, 1.0).success());

EXPECT_TRUE(gt_eq<int64_t>(Parameter{"", 1}, 1).success());
EXPECT_TRUE(gt_eq<int64_t>(Parameter{"", 4}, 1).success());
EXPECT_FALSE(gt_eq<int64_t>(Parameter{"", -4}, 1).success());

EXPECT_TRUE(gt_eq<bool>(Parameter{"", true}, false).success());
EXPECT_FALSE(gt_eq<bool>(Parameter{"", false}, true).success());
EXPECT_TRUE(gt_eq<bool>(Parameter{"", true}, true).success());
}

TEST(ValidatorsTests, LessThanOrEqual) {
EXPECT_TRUE(lt_eq<double>(Parameter{"", 2.0}, 2.0).success());
EXPECT_FALSE(lt_eq<double>(Parameter{"", 4.3}, 1.0).success());
EXPECT_TRUE(lt_eq<double>(Parameter{"", -4.3}, 1.0).success());

EXPECT_TRUE(lt_eq<int64_t>(Parameter{"", 1}, 1).success());
EXPECT_FALSE(lt_eq<int64_t>(Parameter{"", 4}, 1).success());
EXPECT_TRUE(lt_eq<int64_t>(Parameter{"", -4}, 1).success());

EXPECT_FALSE(lt_eq<bool>(Parameter{"", true}, false).success());
EXPECT_TRUE(lt_eq<bool>(Parameter{"", false}, true).success());
EXPECT_TRUE(lt_eq<bool>(Parameter{"", true}, true).success());
}

TEST(ValidatorsTests, OneOf) {
EXPECT_TRUE(
one_of<double>(Parameter{"", 2.0}, std::vector<double>{2.0}).success());
Expand Down