From f0ee6138fe91486588a39dec48d9dbc436a40546 Mon Sep 17 00:00:00 2001 From: Janosch Machowinski Date: Wed, 11 Dec 2024 15:06:06 +0100 Subject: [PATCH] test: Added test case, if timer within waitable works as expected Signed-off-by: Janosch Machowinski --- .../rclcpp/executors/test_events_executor.cpp | 119 ++++++++++++++++++ 1 file changed, 119 insertions(+) diff --git a/rclcpp/test/rclcpp/executors/test_events_executor.cpp b/rclcpp/test/rclcpp/executors/test_events_executor.cpp index 2c6504426e..fa9c5177d5 100644 --- a/rclcpp/test/rclcpp/executors/test_events_executor.cpp +++ b/rclcpp/test/rclcpp/executors/test_events_executor.cpp @@ -497,3 +497,122 @@ TEST_F(TestEventsExecutor, test_default_incompatible_qos_callbacks) rcutils_logging_set_output_handler(original_output_handler); } + +class TestWaitableWithTimer : public rclcpp::Waitable +{ + static constexpr int TimerCallbackType = 0; + +public: + explicit TestWaitableWithTimer(const rclcpp::Context::SharedPtr & context) + { + auto timer_callback = [this] () { + timer_ready = true; + if (ready_callback) { + // inform executor that the waitable is ready to process a timer event + ready_callback(1, TimerCallbackType); + } + }; + timer = + std::make_shared>(std::chrono::milliseconds(10), + std::move(timer_callback), context); + } + + void + add_to_wait_set(rcl_wait_set_t & /*wait_set*/) override {} + + bool + is_ready(const rcl_wait_set_t & /*wait_set*/) override + { + return false; + } + + std::shared_ptr + take_data() override + { + return std::shared_ptr(nullptr); + } + + std::shared_ptr + take_data_by_entity_id(size_t id) override + { + if (id != TimerCallbackType) { + throw std::runtime_error("Internal error, got wrong ID for take data"); + } + return nullptr; + } + + void + execute(const std::shared_ptr &) override + { + if (timer_ready) { + timer_triggered_waitable_and_waitable_was_executed = true; + } + } + + void + set_on_ready_callback(std::function callback) override + { + ready_callback = callback; + } + + void + clear_on_ready_callback() override + { + ready_callback = std::function(); + } + + size_t + get_number_of_ready_guard_conditions() override + { + return 0; + } + + std::vector> get_timers() const override + { + return {timer}; + } + + bool timerTriggeredWaitable() const + { + return timer_triggered_waitable_and_waitable_was_executed; + } + +private: + std::atomic_bool timer_triggered_waitable_and_waitable_was_executed = false; + std::atomic_bool timer_ready = false; + rclcpp::TimerBase::SharedPtr timer; + std::function ready_callback; +}; + +TEST_F(TestEventsExecutor, waitable_with_timer) +{ + auto node = std::make_shared("node"); + + auto waitable = + std::make_shared(rclcpp::contexts::get_global_default_context()); + + EventsExecutor executor; + executor.add_node(node); + + node->get_node_waitables_interface()->add_waitable(waitable, + node->get_node_base_interface()->get_default_callback_group()); + + std::thread spinner([&executor]() {executor.spin();}); + + size_t cnt = 0; + while (!waitable->timerTriggeredWaitable()) { + std::this_thread::sleep_for(10ms); + cnt++; + + // This should terminate after ~20 ms, so a timeout of 500ms should be plenty + EXPECT_LT(cnt, 51); + if (cnt > 50) { + // timeout case + break; + } + } + executor.cancel(); + spinner.join(); + + EXPECT_TRUE(waitable->timerTriggeredWaitable()); +}