Skip to content
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
1 change: 1 addition & 0 deletions .github/workflows/ci.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -106,6 +106,7 @@ jobs:
with:
package-name: rsl
target-ros2-distro: ${{ matrix.ros_distro }}
extra-cmake-args: -DRSL_BUILD_TESTING=ON
colcon-defaults: |
{
"build": {
Expand Down
1 change: 1 addition & 0 deletions .github/workflows/rolling-debian-binary-build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -20,3 +20,4 @@ jobs:
with:
ros_distro: ${{ matrix.ROS_DISTRO }}
ref_for_scheduled_build: main
target_cmake_args: -DRSL_BUILD_TESTING=ON
1 change: 1 addition & 0 deletions .github/workflows/rolling-rhel-binary-build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -20,3 +20,4 @@ jobs:
with:
ros_distro: ${{ matrix.ROS_DISTRO }}
ref_for_scheduled_build: main
target_cmake_args: -DRSL_BUILD_TESTING=ON
4 changes: 2 additions & 2 deletions .github/workflows/rolling-win-binary-build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,6 @@ jobs:
uses: ros-controls/ros2_control_ci/.github/workflows/reusable-ros-tooling-win-build.yml@master
with:
ros_distro: rolling
pixi_dependencies: jinja2 compilers
pixi_dependencies: jinja2 compilers range-v3
ninja_packages: rsl
target_cmake_args: -DBUILD_TESTING=OFF
target_cmake_args: -DRSL_BUILD_TESTING=ON
41 changes: 29 additions & 12 deletions include/rsl/parameter_validators.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
#include <tl_expected/expected.hpp>

#include <fmt/ranges.h>
#include <type_traits>

namespace rsl {

Expand All @@ -19,6 +20,20 @@ namespace rsl {
* @cond DETAIL
*/
namespace detail {
template <typename T>
[[nodiscard]] auto stringify(T const& value) -> std::string {
if constexpr (std::is_floating_point_v<T>) return fmt::format("{:g}", value);
return fmt::format("{}", value);
}

template <typename T>
[[nodiscard]] auto join_stringified(std::vector<T> const& values) -> std::string {
std::vector<std::string> tokens;
tokens.reserve(values.size());
for (auto const& value : values) tokens.push_back(stringify(value));
return fmt::format("{}", fmt::join(tokens, ", "));
}

template <typename T, typename Fn>
[[nodiscard]] auto size_compare(rclcpp::Parameter const& parameter, size_t const size,
std::string const& predicate_description,
Expand All @@ -44,8 +59,8 @@ template <typename T, typename Fn>
Fn const& predicate) -> tl::expected<void, std::string> {
if (auto const param_value = parameter.get_value<T>(); !predicate(param_value, value))
return tl::unexpected(fmt::format("Parameter '{}' with the value '{}' must be {} '{}'",
parameter.get_name(), param_value, predicate_description,
value));
parameter.get_name(), stringify(param_value),
predicate_description, stringify(value)));
return {};
}
} // namespace detail
Expand Down Expand Up @@ -154,8 +169,9 @@ template <typename T>
for (auto val : param_value)
if (val < lower || val > upper)
return tl::unexpected(
fmt::format("Value '{}' in parameter '{}' must be within bounds '[{}, {}]'", val,
parameter.get_name(), lower, upper));
fmt::format("Value '{}' in parameter '{}' must be within bounds '[{}, {}]'",
detail::stringify(val), parameter.get_name(), detail::stringify(lower),
detail::stringify(upper)));
return {};
}

Expand All @@ -171,9 +187,9 @@ template <typename T>
auto const& param_value = parameter.get_value<std::vector<T>>();
for (auto val : param_value)
if (val < lower)
return tl::unexpected(
fmt::format("Value '{}' in parameter '{}' must be above lower bound of '{}'", val,
parameter.get_name(), lower));
return tl::unexpected(fmt::format(
"Value '{}' in parameter '{}' must be above lower bound of '{}'",
detail::stringify(val), parameter.get_name(), detail::stringify(lower)));
return {};
}

Expand All @@ -189,9 +205,9 @@ template <typename T>
auto const& param_value = parameter.get_value<std::vector<T>>();
for (auto val : param_value)
if (val > upper)
return tl::unexpected(
fmt::format("Value '{}' in parameter '{}' must be below upper bound of '{}'", val,
parameter.get_name(), upper));
return tl::unexpected(fmt::format(
"Value '{}' in parameter '{}' must be below upper bound of '{}'",
detail::stringify(val), parameter.get_name(), detail::stringify(upper)));
return {};
}

Expand All @@ -208,7 +224,8 @@ template <typename T>
if (param_value < lower || param_value > upper)
return tl::unexpected(
fmt::format("Parameter '{}' with the value '{}' must be within bounds '[{}, {}]'",
parameter.get_name(), param_value, lower, upper));
parameter.get_name(), detail::stringify(param_value),
detail::stringify(lower), detail::stringify(upper)));
return {};
}

Expand Down Expand Up @@ -293,7 +310,7 @@ template <typename T>
if (contains(collection, param_value)) return {};
return tl::unexpected(fmt::format(
"Parameter '{}' with the value '{}' is not in the set '{{{}}}'", parameter.get_name(),
param_value, fmt::format("{}", fmt::join(collection, ", "))));
detail::stringify(param_value), detail::join_stringified(collection)));
}

/**
Expand Down
5 changes: 4 additions & 1 deletion tests/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,10 @@ target_link_libraries(test-rsl PRIVATE
Catch2::Catch2WithMain
range-v3::range-v3
)
catch_discover_tests(test-rsl)
# Discover tests at CTest runtime (not build time) to avoid Windows CI
# failures (0xc0000135 / missing runtime DLLs) when Catch2 executes test-rsl
# during project build.
catch_discover_tests(test-rsl DISCOVERY_MODE PRE_TEST)

# Test install interface
add_test(NAME "Install RSL" COMMAND
Expand Down
Loading