From 00b40201948548691ffcbb4d8ba9f61312f08565 Mon Sep 17 00:00:00 2001 From: brawner Date: Thu, 18 Jun 2020 14:00:31 -0700 Subject: [PATCH] Check period duration in create_wall_timer (#1178) * Check period duration in create_wall_timer Signed-off-by: Stephen Brawner * Adding comments Signed-off-by: Stephen Brawner --- rclcpp/include/rclcpp/create_timer.hpp | 38 +++++++++++++--- rclcpp/test/rclcpp/test_create_timer.cpp | 57 +++++++++++++++++++++++- 2 files changed, 89 insertions(+), 6 deletions(-) diff --git a/rclcpp/include/rclcpp/create_timer.hpp b/rclcpp/include/rclcpp/create_timer.hpp index f7b810dc4d..345f43fcbb 100644 --- a/rclcpp/include/rclcpp/create_timer.hpp +++ b/rclcpp/include/rclcpp/create_timer.hpp @@ -76,14 +76,14 @@ create_timer( * \tparam DurationRepT * \tparam DurationT * \tparam CallbackT - * \param period period to exectute callback + * \param period period to execute callback. This duration must be 0 <= period < nanoseconds::max() * \param callback callback to execute via the timer period * \param group * \param node_base * \param node_timers * \return * \throws std::invalid argument if either node_base or node_timers - * are null + * are null, or period is negative or too large */ template typename rclcpp::WallTimer::SharedPtr @@ -102,10 +102,38 @@ create_wall_timer( throw std::invalid_argument{"input node_timers cannot be null"}; } + if (period < std::chrono::duration::zero()) { + throw std::invalid_argument{"timer period cannot be negative"}; + } + + // Casting to a double representation might lose precision and allow the check below to succeed + // but the actual cast to nanoseconds fail. Using 1 DurationT worth of nanoseconds less than max. + constexpr auto maximum_safe_cast_ns = + std::chrono::nanoseconds::max() - std::chrono::duration(1); + + // If period is greater than nanoseconds::max(), the duration_cast to nanoseconds will overflow + // a signed integer, which is undefined behavior. Checking whether any std::chrono::duration is + // greater than nanoseconds::max() is a difficult general problem. This is a more conservative + // version of Howard Hinnant's (the guy>) response here: + // https://stackoverflow.com/a/44637334/2089061 + // However, this doesn't solve the issue for all possible duration types of period. + // Follow-up issue: https://github.com/ros2/rclcpp/issues/1177 + constexpr auto ns_max_as_double = + std::chrono::duration_cast>( + maximum_safe_cast_ns); + if (period > ns_max_as_double) { + throw std::invalid_argument{ + "timer period must be less than std::chrono::nanoseconds::max()"}; + } + + const auto period_ns = std::chrono::duration_cast(period); + if (period_ns < std::chrono::nanoseconds::zero()) { + throw std::runtime_error{ + "Casting timer period to nanoseconds resulted in integer overflow."}; + } + auto timer = rclcpp::WallTimer::make_shared( - std::chrono::duration_cast(period), - std::move(callback), - node_base->get_context()); + period_ns, std::move(callback), node_base->get_context()); node_timers->add_timer(timer, group); return timer; } diff --git a/rclcpp/test/rclcpp/test_create_timer.cpp b/rclcpp/test/rclcpp/test_create_timer.cpp index cff870a8a4..f6acd79b24 100644 --- a/rclcpp/test/rclcpp/test_create_timer.cpp +++ b/rclcpp/test/rclcpp/test_create_timer.cpp @@ -18,10 +18,10 @@ #include #include +#include "node_interfaces/node_wrapper.hpp" #include "rclcpp/create_timer.hpp" #include "rclcpp/executors.hpp" #include "rclcpp/node.hpp" -#include "node_interfaces/node_wrapper.hpp" using namespace std::chrono_literals; @@ -61,3 +61,58 @@ TEST(TestCreateTimer, call_with_node_wrapper_compiles) []() {}); rclcpp::shutdown(); } + +TEST(TestCreateTimer, call_wall_timer_with_bad_arguments) +{ + rclcpp::init(0, nullptr); + NodeWrapper node("test_create_wall_timers_with_bad_arguments"); + auto callback = []() {}; + rclcpp::CallbackGroup::SharedPtr group = nullptr; + auto node_interface = + rclcpp::node_interfaces::get_node_base_interface(node).get(); + auto timers_interface = + rclcpp::node_interfaces::get_node_timers_interface(node).get(); + + // Negative period + EXPECT_THROW( + rclcpp::create_wall_timer(-1ms, callback, group, node_interface, timers_interface), + std::invalid_argument); + + // Very negative period + constexpr auto nanoseconds_min = std::chrono::nanoseconds::min(); + EXPECT_THROW( + rclcpp::create_wall_timer( + nanoseconds_min, callback, group, node_interface, timers_interface), + std::invalid_argument); + + // Period must be less than nanoseconds::max() + constexpr auto nanoseconds_max = std::chrono::nanoseconds::min(); + EXPECT_THROW( + rclcpp::create_wall_timer( + nanoseconds_max, callback, group, node_interface, timers_interface), + std::invalid_argument); + + EXPECT_NO_THROW( + rclcpp::create_wall_timer( + nanoseconds_max - 1us, callback, group, node_interface, timers_interface)); + + EXPECT_NO_THROW( + rclcpp::create_wall_timer(0ms, callback, group, node_interface, timers_interface)); + + // Period must be less than nanoseconds::max() + constexpr auto hours_max = std::chrono::hours::max(); + EXPECT_THROW( + rclcpp::create_wall_timer(hours_max, callback, group, node_interface, timers_interface), + std::invalid_argument); + + // node_interface is null + EXPECT_THROW( + rclcpp::create_wall_timer(1ms, callback, group, nullptr, timers_interface), + std::invalid_argument); + + // timers_interface is null + EXPECT_THROW( + rclcpp::create_wall_timer(1ms, callback, group, node_interface, nullptr), + std::invalid_argument); + rclcpp::shutdown(); +}