diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml index 9900e17..051cdd8 100644 --- a/.github/workflows/ci.yaml +++ b/.github/workflows/ci.yaml @@ -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 diff --git a/README.md b/README.md index 466120f..7e583e2 100644 --- a/README.md +++ b/README.md @@ -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` 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 +#include + +#include +#include -namespace parameter_traits { +namespace my_project { -Result integer_equal_value(rclcpp::Parameter const& parameter, int expected_value) { +tl::expected 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] } ``` diff --git a/example/include/generate_parameter_library_example/example_validators.hpp b/example/include/generate_parameter_library_example/example_validators.hpp index 2fbb8e9..02074d3 100644 --- a/example/include/generate_parameter_library_example/example_validators.hpp +++ b/example/include/generate_parameter_library_example/example_validators.hpp @@ -28,34 +28,42 @@ #pragma once -#include +#include -namespace parameter_traits { +#include + +#include +#include + +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 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 no_args_validator( + const rclcpp::Parameter& parameter) { + return {}; +} -} // namespace parameter_traits +} // namespace custom_validators diff --git a/example/src/parameters.yaml b/example/src/parameters.yaml index ceeb6a7..cb8a995 100644 --- a/example/src/parameters.yaml +++ b/example/src/parameters.yaml @@ -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: { @@ -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 ] } } diff --git a/generate_parameter_library/cmake/generate_parameter_library.cmake b/generate_parameter_library/cmake/generate_parameter_library.cmake index 4a03748..721da18 100644 --- a/generate_parameter_library/cmake/generate_parameter_library.cmake +++ b/generate_parameter_library/cmake/generate_parameter_library.cmake @@ -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() diff --git a/generate_parameter_library/generate_parameter_library-extras.cmake b/generate_parameter_library/generate_parameter_library-extras.cmake index a75f0a3..452030d 100644 --- a/generate_parameter_library/generate_parameter_library-extras.cmake +++ b/generate_parameter_library/generate_parameter_library-extras.cmake @@ -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") diff --git a/generate_parameter_library/package.xml b/generate_parameter_library/package.xml index 6e8fbc7..9f77e97 100644 --- a/generate_parameter_library/package.xml +++ b/generate_parameter_library/package.xml @@ -16,7 +16,9 @@ parameter_traits rclcpp rclcpp_lifecycle + rsl tcb_span + tl_expected ament_lint_auto ament_lint_common diff --git a/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/declare_parameter b/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/declare_parameter index 0ef3f7e..8dbe2c3 100644 --- a/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/declare_parameter +++ b/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/declare_parameter @@ -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 -%} diff --git a/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/declare_runtime_parameter b/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/declare_runtime_parameter index a16d636..40ca32b 100644 --- a/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/declare_runtime_parameter +++ b/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/declare_runtime_parameter @@ -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) %} diff --git a/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/parameter_library_header b/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/parameter_library_header index 1a0a25b..35bb734 100644 --- a/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/parameter_library_header +++ b/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/parameter_library_header @@ -20,12 +20,54 @@ #include +#include +#include +#include + {% 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 +[[nodiscard]] auto to_parameter_value(T value) { + return rclcpp::ParameterValue(value); +} + +template +[[nodiscard]] auto to_parameter_value(rsl::StaticString const& value) { + return rclcpp::ParameterValue(rsl::to_string(value)); +} + +template +[[nodiscard]] auto to_parameter_value(rsl::StaticVector const& value) { + return rclcpp::ParameterValue(rsl::to_vector(value)); +} + {%- filter indent(width=4) %} struct Params { {%- filter indent(width=4) %} @@ -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(){ diff --git a/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/parameter_validation b/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/parameter_validation index ed0eb5e..979a31b 100644 --- a/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/parameter_validation +++ b/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/parameter_validation @@ -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 -%} diff --git a/generate_parameter_library_py/generate_parameter_library_py/main.py b/generate_parameter_library_py/generate_parameter_library_py/main.py index ec1c4db..0e53187 100755 --- a/generate_parameter_library_py/generate_parameter_library_py/main.py +++ b/generate_parameter_library_py/generate_parameter_library_py/main.py @@ -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()));" ) @@ -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 @@ -272,10 +272,10 @@ class CodeGenVariableBase: "double_array": lambda defined_type, templates: "std::vector", "int_array": lambda defined_type, templates: "std::vector", "string_array": lambda defined_type, templates: "std::vector", - "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()", diff --git a/parameter_traits/CMakeLists.txt b/parameter_traits/CMakeLists.txt index 73889d7..46ac4f8 100644 --- a/parameter_traits/CMakeLists.txt +++ b/parameter_traits/CMakeLists.txt @@ -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 @@ -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) @@ -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( @@ -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() diff --git a/parameter_traits/include/parameter_traits/comparison.hpp b/parameter_traits/include/parameter_traits/comparison.hpp deleted file mode 100644 index 0c6a1e5..0000000 --- a/parameter_traits/include/parameter_traits/comparison.hpp +++ /dev/null @@ -1,48 +0,0 @@ -// Copyright (c) 2022, PickNik Inc. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// -// * Redistributions in binary form must reproduce the above copyright -// notice, this list of conditions and the following disclaimer in the -// documentation and/or other materials provided with the distribution. -// -// * Neither the name of the copyright holder nor the names of its -// contributors may be used to endorse or promote products derived from -// this software without specific prior written permission. -// -// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -// POSSIBILITY OF SUCH DAMAGE. - -#pragma once - -#include -#include - -namespace parameter_traits { - -template -bool contains(std::vector const& vec, T const& val) { - return std::find(vec.cbegin(), vec.cend(), val) != vec.cend(); -} - -template -bool is_unique(std::vector const& x) { - auto vec = x; - std::sort(vec.begin(), vec.end()); - return std::adjacent_find(vec.cbegin(), vec.cend()) == vec.cend(); -} - -} // namespace parameter_traits diff --git a/parameter_traits/include/parameter_traits/fixed_size_types.hpp b/parameter_traits/include/parameter_traits/fixed_size_types.hpp deleted file mode 100644 index 1f6d744..0000000 --- a/parameter_traits/include/parameter_traits/fixed_size_types.hpp +++ /dev/null @@ -1,81 +0,0 @@ -// Copyright (c) 2022, PickNik Inc. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// -// * Redistributions in binary form must reproduce the above copyright -// notice, this list of conditions and the following disclaimer in the -// documentation and/or other materials provided with the distribution. -// -// * Neither the name of the copyright holder nor the names of its -// contributors may be used to endorse or promote products derived from -// this software without specific prior written permission. -// -// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -// POSSIBILITY OF SUCH DAMAGE. - -#pragma once - -#include - -#include - -namespace parameter_traits { - -template -class FixedSizeArray { - public: - FixedSizeArray() = default; - FixedSizeArray(const std::vector& values) { - len_ = std::min(values.size(), S); - std::copy(values.cbegin(), values.cbegin() + len_, data_.begin()); - } - - operator tcb::span() { return tcb::span(data_.data(), len_); } - - operator rclcpp::ParameterValue() const { - return rclcpp::ParameterValue( - std::vector(data_.cbegin(), data_.cbegin() + len_)); - } - - private: - std::array data_; - size_t len_; -}; - -template -class FixedSizeString { - public: - FixedSizeString() = default; - FixedSizeString(const std::string& str) { - len_ = std::min(str.size(), S); - std::copy(str.cbegin(), str.cbegin() + len_, data_.begin()); - } - - operator std::string_view() const { - return std::string_view(data_.data(), len_); - } - - operator rclcpp::ParameterValue() const { - return rclcpp::ParameterValue( - std::string(data_.cbegin(), data_.cbegin() + len_)); - } - - private: - std::array data_; - size_t len_; -}; - -} // namespace parameter_traits diff --git a/parameter_traits/include/parameter_traits/parameter_traits.hpp b/parameter_traits/include/parameter_traits/parameter_traits.hpp index eabf6bc..f1e731a 100644 --- a/parameter_traits/include/parameter_traits/parameter_traits.hpp +++ b/parameter_traits/include/parameter_traits/parameter_traits.hpp @@ -28,7 +28,42 @@ #pragma once -#include -#include -#include -#include +#include +#include +#include + +namespace parameter_traits { + +using Result + [[deprecated("Use tl::expected for return instead. " + "`#include `.")]] = + tl::expected; + +template +[[deprecated( + "When returning tl::expected you can call fmt::format " + "directly.")]] auto +ERROR(const std::string& format, Args... args) + -> tl::expected { + return tl::make_unexpected(fmt::format(format, args...)); +} + +auto static OK + [[deprecated("When returning tl::expected default " + "construct for OK with `{}`.")]] = + tl::expected{}; + +template +[[deprecated("Use rsl::contains instead. `#include `")]] bool +contains(std::vector const& vec, T const& val) { + return rsl::contains(vec, val); +} + +template +[[deprecated( + "Use rsl::is_unique instead. `#include `")]] bool +is_unique(std::vector const& x) { + return rsl::is_unique(x); +} + +} // namespace parameter_traits diff --git a/parameter_traits/include/parameter_traits/result.hpp b/parameter_traits/include/parameter_traits/result.hpp deleted file mode 100644 index 0cf6678..0000000 --- a/parameter_traits/include/parameter_traits/result.hpp +++ /dev/null @@ -1,68 +0,0 @@ -// Copyright (c) 2022, PickNik Inc. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// -// * Redistributions in binary form must reproduce the above copyright -// notice, this list of conditions and the following disclaimer in the -// documentation and/or other materials provided with the distribution. -// -// * Neither the name of the copyright holder nor the names of its -// contributors may be used to endorse or promote products derived from -// this software without specific prior written permission. -// -// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -// POSSIBILITY OF SUCH DAMAGE. - -#pragma once - -#include - -#include - -#include - -namespace parameter_traits { - -class Result { - public: - template - Result(const std::string& format, Args... args) { - msg_ = fmt::format(format, args...); - success_ = false; - } - - Result() = default; - - operator rcl_interfaces::msg::SetParametersResult() const { - rcl_interfaces::msg::SetParametersResult result; - result.successful = success_; - result.reason = msg_; - return result; - } - - bool success() { return success_; } - - std::string error_msg() { return msg_; } - - private: - std::string msg_; - bool success_ = true; -}; - -auto static OK = Result(); -using ERROR = Result; - -} // namespace parameter_traits diff --git a/parameter_traits/include/parameter_traits/validators.hpp b/parameter_traits/include/parameter_traits/validators.hpp deleted file mode 100644 index 86f2156..0000000 --- a/parameter_traits/include/parameter_traits/validators.hpp +++ /dev/null @@ -1,227 +0,0 @@ -// Copyright (c) 2022, PickNik Inc. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// -// * Redistributions in binary form must reproduce the above copyright -// notice, this list of conditions and the following disclaimer in the -// documentation and/or other materials provided with the distribution. -// -// * Neither the name of the copyright holder nor the names of its -// contributors may be used to endorse or promote products derived from -// this software without specific prior written permission. -// -// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -// POSSIBILITY OF SUCH DAMAGE. - -#pragma once - -#include -#include -#include -#include - -#include - -#include -#include -#include -#include - -namespace parameter_traits { - -template -Result unique(rclcpp::Parameter const& parameter) { - if (!is_unique(parameter.get_value>())) { - return ERROR("Parameter '{}' must only contain unique values", - parameter.get_name()); - } - return OK; -} - -template -Result subset_of(rclcpp::Parameter const& parameter, - std::vector valid_values) { - auto const& input_values = parameter.get_value>(); - - for (auto const& value : input_values) { - if (!contains(valid_values, value)) { - return ERROR(fmt::format( - "Invalid entry '{}' for parameter '{}'. Not in set: {}", value, - parameter.get_name(), fmt::join(valid_values, ", "))); - } - } - - return OK; -} - -template -Result size_cmp(rclcpp::Parameter const& parameter, size_t size, - std::string const& cmp_str, F cmp) { - if (parameter.get_type() == rclcpp::ParameterType::PARAMETER_STRING) { - if (auto value = parameter.get_value(); - !cmp(value.size(), size)) { - return ERROR("Invalid length '{}' for parameter '{}'. Required {}: {}", - value.size(), parameter.get_name(), cmp_str, size); - } - } else { - if (auto value = parameter.get_value>(); - !cmp(value.size(), size)) { - return ERROR("Invalid length '{}' for parameter '{}'. Required {}: {}", - value.size(), parameter.get_name(), cmp_str, size); - } - } - - return OK; -} - -template -Result fixed_size(rclcpp::Parameter const& parameter, size_t size) { - return size_cmp(parameter, size, "equal to", std::equal_to{}); -} - -template -Result size_gt(rclcpp::Parameter const& parameter, size_t size) { - return size_cmp(parameter, size, "greater than", std::greater{}); -} - -template -Result size_lt(rclcpp::Parameter const& parameter, size_t size) { - return size_cmp(parameter, size, "less than", std::less{}); -} - -template -Result not_empty(rclcpp::Parameter const& parameter) { - if (parameter.get_type() == rclcpp::ParameterType::PARAMETER_STRING) { - if (auto param_value = parameter.get_value(); - param_value.empty()) { - return ERROR("The parameter '{}' cannot be empty.", parameter.get_name()); - } - } else { - if (auto param_value = parameter.get_value>(); - param_value.empty()) { - return ERROR("The parameter '{}' cannot be empty.", parameter.get_name()); - } - } - return OK; -} - -template -Result element_bounds(const rclcpp::Parameter& parameter, T lower, T upper) { - auto param_value = parameter.get_value>(); - for (auto val : param_value) { - if (val < lower || val > upper) { - return ERROR( - "Invalid value '{}' for parameter '{}'. Required bounds: [{}, {}]", - val, parameter.get_name(), lower, upper); - } - } - return OK; -} - -template -Result lower_element_bounds(const rclcpp::Parameter& parameter, T lower) { - auto param_value = parameter.get_value>(); - for (auto val : param_value) { - if (val < lower) { - return ERROR( - "Invalid value '{}' for parameter '{}'. Required lower bounds: {}", - val, parameter.get_name(), lower); - } - } - return OK; -} - -template -Result upper_element_bounds(const rclcpp::Parameter& parameter, T upper) { - auto param_value = parameter.get_value>(); - for (auto val : param_value) { - if (val > upper) { - return ERROR( - "Invalid value '{}' for parameter '{}'. Required upper bounds: {}", - val, parameter.get_name(), upper); - } - } - return OK; -} - -template -Result bounds(const rclcpp::Parameter& parameter, T lower, T upper) { - auto param_value = parameter.get_value(); - if (param_value < lower || param_value > upper) { - return ERROR( - "Invalid value '{}' for parameter '{}'. Required bounds: [{}, {}]", - param_value, parameter.get_name(), lower, upper); - } - return OK; -} - -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 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 -Result one_of(rclcpp::Parameter const& parameter, std::vector collection) { - auto param_value = parameter.get_value(); - - if (std::find(collection.cbegin(), collection.cend(), param_value) == - collection.end()) { - return ERROR("The parameter '{}' with the value '{}' not in the set: {}", - parameter.get_name(), param_value, - fmt::format("{}", fmt::join(collection, ", "))); - } - return OK; -} - -} // namespace parameter_traits diff --git a/parameter_traits/package.xml b/parameter_traits/package.xml index 970a893..605d51d 100644 --- a/parameter_traits/package.xml +++ b/parameter_traits/package.xml @@ -12,7 +12,9 @@ fmt rclcpp + rsl tcb_span + tl_expected ament_cmake_gtest ament_lint_auto diff --git a/parameter_traits/test/CMakeLists.txt b/parameter_traits/test/CMakeLists.txt deleted file mode 100644 index c932590..0000000 --- a/parameter_traits/test/CMakeLists.txt +++ /dev/null @@ -1,7 +0,0 @@ -find_package(ament_cmake_gtest REQUIRED) - -ament_add_gtest(comparison_tests comparison_tests.cpp) -target_link_libraries(comparison_tests parameter_traits) - -ament_add_gtest(validators_tests validators_tests.cpp) -target_link_libraries(validators_tests parameter_traits) diff --git a/parameter_traits/test/comparison_tests.cpp b/parameter_traits/test/comparison_tests.cpp deleted file mode 100644 index 9b68c68..0000000 --- a/parameter_traits/test/comparison_tests.cpp +++ /dev/null @@ -1,85 +0,0 @@ -// Copyright 2022 PickNik Inc -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// -// * Redistributions in binary form must reproduce the above copyright -// notice, this list of conditions and the following disclaimer in the -// documentation and/or other materials provided with the distribution. -// -// * Neither the name of the PickNik Inc nor the names of its -// contributors may be used to endorse or promote products derived from -// this software without specific prior written permission. -// -// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -// POSSIBILITY OF SUCH DAMAGE. - -#include "gtest/gtest.h" - -#include -#include - -#include - -namespace pv = parameter_traits; - -TEST(ComparisonTests, NotContainsEmptyStrVec) { - EXPECT_FALSE(pv::contains(std::vector(), std::string{})); -} - -TEST(ComparisonTests, ContainsEmptyStr) { - EXPECT_TRUE(pv::contains(std::vector({""}), std::string{})); -} - -TEST(ComparisonTests, ContainsAStr) { - EXPECT_TRUE(pv::contains(std::vector({"a", "b", "c"}), - std::string{"a"})); -} - -TEST(ComparisonTests, NotContainsAStr) { - EXPECT_FALSE(pv::contains(std::vector({"aa", "bb", "cc"}), - std::string{"a"})); -} - -TEST(ComparisonTests, NotContainsEmptyIntVec) { - EXPECT_FALSE(pv::contains({}, int{})); -} - -TEST(ComparisonTests, ContainsAInt) { - EXPECT_TRUE(pv::contains({1, 2, 3}, int{1})); -} - -TEST(ComparisonTests, NotContainsAInt) { - EXPECT_FALSE(pv::contains({11, 22, 33}, int{1})); -} - -TEST(ComparisonTests, EmptyIntIsUnique) { EXPECT_TRUE(pv::is_unique({})); } - -TEST(ComparisonTests, EmptyStrIsUnique) { - EXPECT_TRUE(pv::is_unique({})); -} - -TEST(ComparisonTests, RepeatedIntNotIsUnique) { - EXPECT_FALSE(pv::is_unique({1, 1})); -} - -TEST(ComparisonTests, NotRepeatedIntIsUnique) { - EXPECT_TRUE(pv::is_unique({1, 2, 3, 4, 5})); -} - -int main(int argc, char** argv) { - ::testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/parameter_traits/test/validators_tests.cpp b/parameter_traits/test/validators_tests.cpp deleted file mode 100644 index 2f5083c..0000000 --- a/parameter_traits/test/validators_tests.cpp +++ /dev/null @@ -1,516 +0,0 @@ -// Copyright (c) 2022, PickNik Inc. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// -// * Redistributions in binary form must reproduce the above copyright -// notice, this list of conditions and the following disclaimer in the -// documentation and/or other materials provided with the distribution. -// -// * Neither the name of the copyright holder nor the names of its -// contributors may be used to endorse or promote products derived from -// this software without specific prior written permission. -// -// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -// POSSIBILITY OF SUCH DAMAGE. - -#include "gtest/gtest.h" - -#include -#include - -#include - -#include -#include - -namespace parameter_traits { -using rclcpp::Parameter; - -TEST(ValidatorsTests, Bounds) { - EXPECT_TRUE(bounds(Parameter{"", 1.0}, 1.0, 5.0).success()); - EXPECT_TRUE(bounds(Parameter{"", 4.3}, 1.0, 5.0).success()); - EXPECT_TRUE(bounds(Parameter{"", 5.0}, 1.0, 5.0).success()); - EXPECT_FALSE(bounds(Parameter{"", -4.3}, 1.0, 5.0).success()); - EXPECT_FALSE(bounds(Parameter{"", 10.2}, 1.0, 5.0).success()); - - EXPECT_TRUE(bounds(Parameter{"", 1}, 1, 5).success()); - EXPECT_TRUE(bounds(Parameter{"", 4}, 1, 5).success()); - EXPECT_TRUE(bounds(Parameter{"", 5}, 1, 5).success()); - EXPECT_FALSE(bounds(Parameter{"", -4}, 1, 5).success()); - EXPECT_FALSE(bounds(Parameter{"", 10}, 1, 5).success()); - - EXPECT_TRUE(bounds(Parameter{"", true}, false, true).success()); - EXPECT_FALSE(bounds(Parameter{"", false}, true, true).success()); - EXPECT_FALSE(bounds(Parameter{"", true}, false, false).success()); - - EXPECT_ANY_THROW(bounds(Parameter{"", ""}, 1, 5)); - EXPECT_ANY_THROW(bounds(Parameter{"", 4}, "", "foo")); -} - -TEST(ValidatorsTests, LowerBounds) { - EXPECT_TRUE(lower_bounds(Parameter{"", 2.0}, 2.0).success()); - EXPECT_TRUE(lower_bounds(Parameter{"", 4.3}, 1.0).success()); - EXPECT_FALSE(lower_bounds(Parameter{"", -4.3}, 1.0).success()); - - EXPECT_TRUE(lower_bounds(Parameter{"", 1}, 1).success()); - EXPECT_TRUE(lower_bounds(Parameter{"", 4}, 1).success()); - EXPECT_FALSE(lower_bounds(Parameter{"", -4}, 1).success()); - - EXPECT_TRUE(lower_bounds(Parameter{"", true}, false).success()); - EXPECT_FALSE(lower_bounds(Parameter{"", false}, true).success()); - EXPECT_TRUE(lower_bounds(Parameter{"", true}, true).success()); -} - -TEST(ValidatorsTests, UpperBounds) { - EXPECT_TRUE(upper_bounds(Parameter{"", 2.0}, 2.0).success()); - EXPECT_FALSE(upper_bounds(Parameter{"", 4.3}, 1.0).success()); - EXPECT_TRUE(upper_bounds(Parameter{"", -4.3}, 1.0).success()); - - EXPECT_TRUE(upper_bounds(Parameter{"", 1}, 1).success()); - EXPECT_FALSE(upper_bounds(Parameter{"", 4}, 1).success()); - EXPECT_TRUE(upper_bounds(Parameter{"", -4}, 1).success()); - - EXPECT_FALSE(upper_bounds(Parameter{"", true}, false).success()); - EXPECT_TRUE(upper_bounds(Parameter{"", false}, true).success()); - 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()); - EXPECT_TRUE( - one_of(Parameter{"", 2.0}, std::vector{1.0, 2.0, 3.5}) - .success()); - EXPECT_FALSE( - one_of(Parameter{"", 0.0}, std::vector{1.0, 2.0, 3.5}) - .success()); - EXPECT_FALSE( - one_of(Parameter{"", 0.0}, std::vector{}).success()); - - EXPECT_TRUE( - one_of(Parameter{"", 1}, std::vector{1}).success()); - EXPECT_TRUE( - one_of(Parameter{"", 1}, std::vector{1, 2, 3, 4}) - .success()); - EXPECT_FALSE( - one_of(Parameter{"", 0}, std::vector{1, 2, 3, 4}) - .success()); - EXPECT_FALSE( - one_of(Parameter{"", 0}, std::vector{}).success()); - - EXPECT_FALSE( - one_of(Parameter{"", true}, std::vector{false}).success()); - EXPECT_TRUE(one_of(Parameter{"", true}, std::vector{false, true}) - .success()); - EXPECT_TRUE( - one_of(Parameter{"", true}, std::vector{true}).success()); - EXPECT_FALSE( - one_of(Parameter{"", true}, std::vector{}).success()); -} - -TEST(ValidatorsTests, FixedSizeString) { - EXPECT_TRUE(fixed_size(Parameter{"", "foo"}, 3).success()); - EXPECT_TRUE(fixed_size(Parameter{"", ""}, 0).success()); - EXPECT_FALSE(fixed_size(Parameter{"", "foo"}, 0).success()); - EXPECT_FALSE(fixed_size(Parameter{"", "foo"}, 5).success()); -} - -TEST(ValidatorsTests, SizeGtString) { - EXPECT_TRUE(size_gt(Parameter{"", "foo"}, 2).success()); - EXPECT_FALSE(size_gt(Parameter{"", ""}, 0).success()); - EXPECT_FALSE(size_gt(Parameter{"", "foo"}, 5).success()); -} - -TEST(ValidatorsTests, SizeLtString) { - EXPECT_TRUE(size_lt(Parameter{"", "foo"}, 5).success()); - EXPECT_FALSE(size_lt(Parameter{"", ""}, 0).success()); - EXPECT_FALSE(size_lt(Parameter{"", "foo"}, 3).success()); -} - -TEST(ValidatorsTests, NotEmptyString) { - EXPECT_TRUE(not_empty(Parameter{"", "foo"}).success()); - EXPECT_FALSE(not_empty(Parameter{"", ""}).success()); -} - -TEST(ValidatorsTests, OneOfString) { - EXPECT_TRUE(one_of(Parameter{"", "foo"}, - std::vector{"foo", "baz"}) - .success()); - EXPECT_FALSE(one_of(Parameter{"", ""}, - std::vector{"foo", "baz"}) - .success()); -} - -TEST(ValidatorsTests, UniqueArray) { - EXPECT_TRUE( - unique(Parameter{"", std::vector{"", "1", "2"}}) - .success()); - EXPECT_TRUE( - unique(Parameter{"", std::vector{}}).success()); - EXPECT_FALSE( - unique(Parameter{"", std::vector{"foo", "foo"}}) - .success()); - - EXPECT_TRUE(unique(Parameter{"", std::vector{1.0, 2.2, 1.1}}) - .success()); - EXPECT_TRUE(unique(Parameter{"", std::vector{}}).success()); - EXPECT_FALSE( - unique(Parameter{"", std::vector{1.1, 1.1}}).success()); - - EXPECT_TRUE( - unique(Parameter{"", std::vector{1, 2, 3}}).success()); - EXPECT_TRUE(unique(Parameter{"", std::vector{}}).success()); - EXPECT_FALSE( - unique(Parameter{"", std::vector{-1, -1}}).success()); - - EXPECT_TRUE( - unique(Parameter{"", std::vector{true, false}}).success()); - EXPECT_TRUE(unique(Parameter{"", std::vector{}}).success()); - EXPECT_FALSE( - unique(Parameter{"", std::vector{false, false}}).success()); -} - -TEST(ValidatorsTests, SubsetOfArray) { - EXPECT_TRUE(subset_of( - Parameter{"", std::vector{"", "1", "2"}}, - std::vector{"", "1", "2", "three"}) - .success()); - EXPECT_TRUE( - subset_of(Parameter{"", std::vector{}}, - std::vector{"", "1", "2", "three"}) - .success()); - EXPECT_FALSE(subset_of( - Parameter{"", std::vector{"foo", "foo"}}, - std::vector{"", "1", "2", "three"}) - .success()); - - EXPECT_TRUE( - subset_of(Parameter{"", std::vector{1.0, 2.2, 1.1}}, - std::vector{1.0, 2.2, 1.1}) - .success()); - EXPECT_TRUE(subset_of(Parameter{"", std::vector{}}, - std::vector{10, 22}) - .success()); - EXPECT_FALSE(subset_of(Parameter{"", std::vector{1.1, 1.1}}, - std::vector{1.0, 2.2}) - .success()); - - EXPECT_TRUE(subset_of(Parameter{"", std::vector{1, 2, 3}}, - std::vector{1, 2, 3}) - .success()); - EXPECT_TRUE(subset_of(Parameter{"", std::vector{}}, - std::vector{1, 2, 3}) - .success()); - EXPECT_FALSE(subset_of(Parameter{"", std::vector{-1, -1}}, - std::vector{1, 2, 3}) - .success()); - - EXPECT_TRUE(subset_of(Parameter{"", std::vector{true, false}}, - std::vector{true, false}) - .success()); - EXPECT_TRUE(subset_of(Parameter{"", std::vector{}}, - std::vector{true, false}) - .success()); - EXPECT_FALSE(subset_of(Parameter{"", std::vector{false, false}}, - std::vector{true}) - .success()); -} - -TEST(ValidatorsTests, FixedSizeArray) { - EXPECT_TRUE(fixed_size( - Parameter{"", std::vector{"", "1", "2"}}, 3) - .success()); - EXPECT_TRUE( - fixed_size(Parameter{"", std::vector{}}, 0) - .success()); - EXPECT_FALSE(fixed_size( - Parameter{"", std::vector{"foo", "foo"}}, 3) - .success()); - - EXPECT_TRUE( - fixed_size(Parameter{"", std::vector{1.0, 2.2, 1.1}}, 3) - .success()); - EXPECT_TRUE( - fixed_size(Parameter{"", std::vector{}}, 0).success()); - EXPECT_FALSE( - fixed_size(Parameter{"", std::vector{1.1, 1.1}}, 3) - .success()); - - EXPECT_TRUE( - fixed_size(Parameter{"", std::vector{1, 2, 3}}, 3) - .success()); - EXPECT_TRUE( - fixed_size(Parameter{"", std::vector{}}, 0).success()); - EXPECT_FALSE( - fixed_size(Parameter{"", std::vector{-1, -1}}, 0) - .success()); - - EXPECT_TRUE(fixed_size(Parameter{"", std::vector{true, false}}, 2) - .success()); - EXPECT_TRUE( - fixed_size(Parameter{"", std::vector{}}, 0).success()); - EXPECT_FALSE( - fixed_size(Parameter{"", std::vector{false, false}}, 0) - .success()); -} - -TEST(ValidatorsTests, SizeGtArray) { - EXPECT_TRUE(size_gt( - Parameter{"", std::vector{"", "1", "2"}}, 1) - .success()); - EXPECT_FALSE( - size_gt(Parameter{"", std::vector{}}, 0) - .success()); - EXPECT_FALSE(size_gt( - Parameter{"", std::vector{"foo", "foo"}}, 3) - .success()); - - EXPECT_TRUE( - size_gt(Parameter{"", std::vector{1.0, 2.2, 1.1}}, 2) - .success()); - EXPECT_FALSE( - size_gt(Parameter{"", std::vector{}}, 0).success()); - EXPECT_FALSE(size_gt(Parameter{"", std::vector{1.1, 1.1}}, 3) - .success()); - - EXPECT_TRUE(size_gt(Parameter{"", std::vector{1, 2, 3}}, 2) - .success()); - EXPECT_FALSE( - size_gt(Parameter{"", std::vector{}}, 0).success()); - EXPECT_TRUE(size_gt(Parameter{"", std::vector{-1, -1}}, 0) - .success()); - - EXPECT_TRUE(size_gt(Parameter{"", std::vector{true, false}}, 0) - .success()); - EXPECT_FALSE(size_gt(Parameter{"", std::vector{}}, 0).success()); - EXPECT_TRUE(size_gt(Parameter{"", std::vector{false, false}}, 0) - .success()); -} - -TEST(ValidatorsTests, SizeLtArray) { - EXPECT_FALSE(size_lt( - Parameter{"", std::vector{"", "1", "2"}}, 1) - .success()); - EXPECT_FALSE( - size_lt(Parameter{"", std::vector{}}, 0) - .success()); - EXPECT_TRUE(size_lt( - Parameter{"", std::vector{"foo", "foo"}}, 3) - .success()); - - EXPECT_FALSE( - size_lt(Parameter{"", std::vector{1.0, 2.2, 1.1}}, 2) - .success()); - EXPECT_FALSE( - size_lt(Parameter{"", std::vector{}}, 0).success()); - EXPECT_TRUE(size_lt(Parameter{"", std::vector{1.1, 1.1}}, 3) - .success()); - - EXPECT_FALSE(size_lt(Parameter{"", std::vector{1, 2, 3}}, 2) - .success()); - EXPECT_FALSE( - size_lt(Parameter{"", std::vector{}}, 0).success()); - EXPECT_FALSE(size_lt(Parameter{"", std::vector{-1, -1}}, 0) - .success()); - - EXPECT_TRUE(size_lt(Parameter{"", std::vector{true, false}}, 3) - .success()); - EXPECT_FALSE(size_lt(Parameter{"", std::vector{}}, 0).success()); - EXPECT_FALSE(size_lt(Parameter{"", std::vector{false, false}}, 0) - .success()); -} - -TEST(ValidatorsTests, NotEmptyArray) { - EXPECT_TRUE(not_empty( - Parameter{"", std::vector{"", "1", "2"}}) - .success()); - EXPECT_FALSE(not_empty(Parameter{"", std::vector{}}) - .success()); - - EXPECT_TRUE( - not_empty(Parameter{"", std::vector{1.0, 2.2, 1.1}}) - .success()); - EXPECT_FALSE( - not_empty(Parameter{"", std::vector{}}).success()); - - EXPECT_TRUE(not_empty(Parameter{"", std::vector{1, 2, 3}}) - .success()); - EXPECT_FALSE( - not_empty(Parameter{"", std::vector{}}).success()); - - EXPECT_TRUE( - not_empty(Parameter{"", std::vector{true, false}}).success()); - EXPECT_FALSE(not_empty(Parameter{"", std::vector{}}).success()); -} - -TEST(ValidatorsTests, ElementBoundsArray) { - EXPECT_TRUE(element_bounds( - Parameter{"", std::vector{1.0, 2.2, 1.1}}, 0.0, 3.0) - .success()); - EXPECT_TRUE( - element_bounds(Parameter{"", std::vector{}}, 0.0, 1.0) - .success()); - - EXPECT_TRUE(element_bounds( - Parameter{"", std::vector{1, 2, 3}}, 0, 5) - .success()); - EXPECT_FALSE(element_bounds( - Parameter{"", std::vector{1, 2, 3}}, -5, 0) - .success()); - EXPECT_TRUE( - element_bounds(Parameter{"", std::vector{}}, 0, 1) - .success()); - - EXPECT_TRUE(element_bounds( - Parameter{"", std::vector{true, false}}, false, true) - .success()); - EXPECT_FALSE(element_bounds( - Parameter{"", std::vector{true, false}}, true, false) - .success()); - EXPECT_FALSE(element_bounds( - Parameter{"", std::vector{true, false}}, false, false) - .success()); - EXPECT_TRUE( - element_bounds(Parameter{"", std::vector{}}, true, false) - .success()); -} - -TEST(ValidatorsTests, LowerElementBoundsArray) { - EXPECT_TRUE(lower_element_bounds( - Parameter{"", std::vector{1.0, 2.2, 1.1}}, 0.0) - .success()); - EXPECT_TRUE( - lower_element_bounds(Parameter{"", std::vector{}}, 0.0) - .success()); - - EXPECT_TRUE(lower_element_bounds( - Parameter{"", std::vector{1, 2, 3}}, 0) - .success()); - EXPECT_FALSE(lower_element_bounds( - Parameter{"", std::vector{1, 2, 3}}, 3) - .success()); - EXPECT_TRUE( - lower_element_bounds(Parameter{"", std::vector{}}, 0) - .success()); - - EXPECT_TRUE(lower_element_bounds( - Parameter{"", std::vector{true, false}}, false) - .success()); - EXPECT_FALSE(lower_element_bounds( - Parameter{"", std::vector{true, false}}, true) - .success()); - EXPECT_TRUE(lower_element_bounds( - Parameter{"", std::vector{true, false}}, false) - .success()); - EXPECT_TRUE( - lower_element_bounds(Parameter{"", std::vector{}}, true) - .success()); -} - -TEST(ValidatorsTests, UpperElementBoundsArray) { - EXPECT_FALSE(upper_element_bounds( - Parameter{"", std::vector{1.0, 2.2, 1.1}}, 0.0) - .success()); - EXPECT_TRUE( - upper_element_bounds(Parameter{"", std::vector{}}, 0.0) - .success()); - - EXPECT_FALSE(upper_element_bounds( - Parameter{"", std::vector{1, 2, 3}}, 0) - .success()); - EXPECT_TRUE(upper_element_bounds( - Parameter{"", std::vector{1, 2, 3}}, 3) - .success()); - EXPECT_TRUE( - upper_element_bounds(Parameter{"", std::vector{}}, 0) - .success()); - - EXPECT_FALSE(upper_element_bounds( - Parameter{"", std::vector{true, false}}, false) - .success()); - EXPECT_TRUE(upper_element_bounds( - Parameter{"", std::vector{true, false}}, true) - .success()); - EXPECT_FALSE(upper_element_bounds( - Parameter{"", std::vector{true, false}}, false) - .success()); - EXPECT_TRUE( - upper_element_bounds(Parameter{"", std::vector{}}, true) - .success()); -} - -} // namespace parameter_traits - -int main(int argc, char** argv) { - ::testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/upstream.repos b/upstream.repos new file mode 100644 index 0000000..56ea542 --- /dev/null +++ b/upstream.repos @@ -0,0 +1,5 @@ +repositories: + rsl: + type: git + url: https://github.com/picknikrobotics/RSL + version: main