|
| 1 | +// Copyright 2024 iRobot Corporation. All Rights Reserved. |
| 2 | + |
| 3 | +#include <gtest/gtest.h> |
| 4 | + |
| 5 | +#include <rclcpp/rclcpp.hpp> |
| 6 | + |
| 7 | +#include "rclcpp/experimental/executors/events_executor/events_executor.hpp" |
| 8 | +#include "rclcpp/experimental/executors/events_executor/simple_events_queue.hpp" |
| 9 | + |
| 10 | +using rclcpp::experimental::executors::EventsExecutor; |
| 11 | + |
| 12 | +class TimersTest |
| 13 | +: public testing::Test |
| 14 | +{ |
| 15 | +public: |
| 16 | + void SetUp() override |
| 17 | + { |
| 18 | + rclcpp::init(0, nullptr); |
| 19 | + } |
| 20 | + |
| 21 | + void TearDown() override |
| 22 | + { |
| 23 | + rclcpp::shutdown(); |
| 24 | + } |
| 25 | +}; |
| 26 | + |
| 27 | +TEST_F(TimersTest, TimersWithSamePeriod) |
| 28 | +{ |
| 29 | + auto timers_period = std::chrono::milliseconds(50); |
| 30 | + auto node = std::make_shared<rclcpp::Node>("test_node"); |
| 31 | + auto events_queue = std::make_unique<rclcpp::experimental::executors::SimpleEventsQueue>(); |
| 32 | + auto executor = std::make_unique<EventsExecutor>(std::move(events_queue), true, rclcpp::ExecutorOptions()); |
| 33 | + |
| 34 | + executor->add_node(node); |
| 35 | + |
| 36 | + size_t count_1 = 0; |
| 37 | + auto timer_1 = rclcpp::create_timer( |
| 38 | + node, |
| 39 | + node->get_clock(), |
| 40 | + rclcpp::Duration(timers_period), |
| 41 | + [&count_1]() { |
| 42 | + count_1++; |
| 43 | + }); |
| 44 | + |
| 45 | + size_t count_2 = 0; |
| 46 | + auto timer_2 = rclcpp::create_timer( |
| 47 | + node, |
| 48 | + node->get_clock(), |
| 49 | + rclcpp::Duration(timers_period), |
| 50 | + [&count_2]() { |
| 51 | + count_2++; |
| 52 | + }); |
| 53 | + |
| 54 | + { |
| 55 | + std::thread executor_thread([&executor](){ |
| 56 | + executor->spin(); |
| 57 | + }); |
| 58 | + |
| 59 | + while (count_2 < 10u) { |
| 60 | + std::this_thread::sleep_for(std::chrono::milliseconds(10)); |
| 61 | + } |
| 62 | + executor->cancel(); |
| 63 | + executor_thread.join(); |
| 64 | + |
| 65 | + EXPECT_GE(count_2, 10u); |
| 66 | + EXPECT_LE(count_2 - count_1, 1u); |
| 67 | + } |
| 68 | + |
| 69 | + count_1 = 0; |
| 70 | + timer_1 = rclcpp::create_timer( |
| 71 | + node, |
| 72 | + node->get_clock(), |
| 73 | + rclcpp::Duration(timers_period), |
| 74 | + [&count_1]() { |
| 75 | + count_1++; |
| 76 | + }); |
| 77 | + |
| 78 | + count_2 = 0; |
| 79 | + timer_2 = rclcpp::create_timer( |
| 80 | + node, |
| 81 | + node->get_clock(), |
| 82 | + rclcpp::Duration(timers_period), |
| 83 | + [&count_2]() { |
| 84 | + count_2++; |
| 85 | + }); |
| 86 | + |
| 87 | + { |
| 88 | + std::thread executor_thread([&executor](){ |
| 89 | + executor->spin(); |
| 90 | + }); |
| 91 | + |
| 92 | + while (count_2 < 10u) { |
| 93 | + std::this_thread::sleep_for(std::chrono::milliseconds(10)); |
| 94 | + } |
| 95 | + executor->cancel(); |
| 96 | + executor_thread.join(); |
| 97 | + |
| 98 | + EXPECT_GE(count_2, 10u); |
| 99 | + EXPECT_LE(count_2 - count_1, 1u); |
| 100 | + } |
| 101 | +} |
| 102 | + |
| 103 | +int main(int argc, char **argv) |
| 104 | +{ |
| 105 | + ::testing::InitGoogleTest(&argc, argv); |
| 106 | + return RUN_ALL_TESTS(); |
| 107 | +} |
0 commit comments