|
| 1 | +// Copyright 2024 Cellumation GmbH |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +#include <gtest/gtest.h> |
| 16 | + |
| 17 | +#include <chrono> |
| 18 | + |
| 19 | +#include "rcl/error_handling.h" |
| 20 | +#include "rcl/time.h" |
| 21 | +#include "rclcpp/clock.hpp" |
| 22 | +#include "rclcpp/rclcpp.hpp" |
| 23 | +#include "rclcpp/time_source.hpp" |
| 24 | + |
| 25 | +#include "../utils/rclcpp_gtest_macros.hpp" |
| 26 | + |
| 27 | +using namespace std::chrono_literals; |
| 28 | +class TestClockWakeup : public ::testing::Test |
| 29 | +{ |
| 30 | +public: |
| 31 | + void test_wakeup_before_sleep(const rclcpp::Clock::SharedPtr & clock) |
| 32 | + { |
| 33 | + std::atomic_bool thread_finished = false; |
| 34 | + |
| 35 | + std::thread wait_thread = std::thread( |
| 36 | + [&clock, &thread_finished]() |
| 37 | + { |
| 38 | + // make sure the thread starts sleeping late |
| 39 | + std::this_thread::sleep_for(std::chrono::milliseconds(100)); |
| 40 | + clock->sleep_until(clock->now() + std::chrono::seconds(3)); |
| 41 | + thread_finished = true; |
| 42 | + }); |
| 43 | + |
| 44 | + // notify the clock, that the sleep shall be interrupted |
| 45 | + clock->cancel_sleep_or_wait(); |
| 46 | + |
| 47 | + auto start_time = std::chrono::steady_clock::now(); |
| 48 | + auto cur_time = start_time; |
| 49 | + while (!thread_finished && start_time + std::chrono::seconds(1) > cur_time) { |
| 50 | + std::this_thread::sleep_for(std::chrono::milliseconds(10)); |
| 51 | + cur_time = std::chrono::steady_clock::now(); |
| 52 | + } |
| 53 | + |
| 54 | + wait_thread.join(); |
| 55 | + |
| 56 | + EXPECT_TRUE(thread_finished); |
| 57 | + EXPECT_LT(cur_time, start_time + std::chrono::seconds(1)); |
| 58 | + } |
| 59 | + |
| 60 | + void test_wakeup_after_sleep(const rclcpp::Clock::SharedPtr & clock) |
| 61 | + { |
| 62 | + std::atomic_bool thread_finished = false; |
| 63 | + |
| 64 | + std::thread wait_thread = std::thread( |
| 65 | + [&clock, &thread_finished]() |
| 66 | + { |
| 67 | + clock->sleep_until(clock->now() + std::chrono::seconds(3)); |
| 68 | + thread_finished = true; |
| 69 | + }); |
| 70 | + |
| 71 | + // make sure the thread is already sleeping before we send the cancel |
| 72 | + std::this_thread::sleep_for(std::chrono::milliseconds(100)); |
| 73 | + |
| 74 | + // notify the clock, that the sleep shall be interrupted |
| 75 | + clock->cancel_sleep_or_wait(); |
| 76 | + |
| 77 | + auto start_time = std::chrono::steady_clock::now(); |
| 78 | + auto cur_time = start_time; |
| 79 | + while (!thread_finished && start_time + std::chrono::seconds(1) > cur_time) { |
| 80 | + std::this_thread::sleep_for(std::chrono::milliseconds(10)); |
| 81 | + cur_time = std::chrono::steady_clock::now(); |
| 82 | + } |
| 83 | + |
| 84 | + wait_thread.join(); |
| 85 | + |
| 86 | + EXPECT_TRUE(thread_finished); |
| 87 | + EXPECT_LT(cur_time, start_time + std::chrono::seconds(1)); |
| 88 | + } |
| 89 | + |
| 90 | +protected: |
| 91 | + static void SetUpTestCase() |
| 92 | + { |
| 93 | + rclcpp::init(0, nullptr); |
| 94 | + } |
| 95 | + |
| 96 | + static void TearDownTestCase() |
| 97 | + { |
| 98 | + rclcpp::shutdown(); |
| 99 | + } |
| 100 | + |
| 101 | + void SetUp() |
| 102 | + { |
| 103 | + node = std::make_shared<rclcpp::Node>("my_node"); |
| 104 | + } |
| 105 | + |
| 106 | + void TearDown() |
| 107 | + { |
| 108 | + node.reset(); |
| 109 | + } |
| 110 | + |
| 111 | + rclcpp::Node::SharedPtr node; |
| 112 | +}; |
| 113 | + |
| 114 | +TEST_F(TestClockWakeup, wakeup_sleep_steay_time) { |
| 115 | + auto clock = std::make_shared<rclcpp::Clock>(RCL_STEADY_TIME); |
| 116 | + test_wakeup_after_sleep(clock); |
| 117 | + test_wakeup_before_sleep(clock); |
| 118 | +} |
| 119 | + |
| 120 | +TEST_F(TestClockWakeup, wakeup_sleep_system_time) { |
| 121 | + auto clock = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME); |
| 122 | + test_wakeup_after_sleep(clock); |
| 123 | + test_wakeup_before_sleep(clock); |
| 124 | +} |
| 125 | + |
| 126 | +TEST_F(TestClockWakeup, wakeup_sleep_ros_time_not_active) { |
| 127 | + auto clock = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME); |
| 128 | + test_wakeup_after_sleep(clock); |
| 129 | + test_wakeup_before_sleep(clock); |
| 130 | +} |
| 131 | + |
| 132 | +TEST_F(TestClockWakeup, wakeup_sleep_ros_time_active) { |
| 133 | + node->set_parameter({"use_sim_time", true}); |
| 134 | + auto clock = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME); |
| 135 | + rclcpp::TimeSource time_source(node); |
| 136 | + time_source.attachClock(clock); |
| 137 | + |
| 138 | + EXPECT_TRUE(clock->ros_time_is_active()); |
| 139 | + |
| 140 | + test_wakeup_after_sleep(clock); |
| 141 | + test_wakeup_before_sleep(clock); |
| 142 | +} |
| 143 | + |
| 144 | +TEST_F(TestClockWakeup, no_wakeup_on_sim_time) { |
| 145 | + node->set_parameter({"use_sim_time", true}); |
| 146 | + auto clock = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME); |
| 147 | + rclcpp::TimeSource time_source(node); |
| 148 | + time_source.attachClock(clock); |
| 149 | + |
| 150 | + EXPECT_TRUE(clock->ros_time_is_active()); |
| 151 | + |
| 152 | + std::atomic_bool thread_finished = false; |
| 153 | + |
| 154 | + std::thread wait_thread = std::thread( |
| 155 | + [&clock, &thread_finished]() |
| 156 | + { |
| 157 | + // make sure the thread starts sleeping late |
| 158 | + clock->sleep_until(clock->now() + std::chrono::milliseconds(10)); |
| 159 | + thread_finished = true; |
| 160 | + }); |
| 161 | + |
| 162 | + // make sure, that the sim time clock does not wakeup, as no clock is provided |
| 163 | + std::this_thread::sleep_for(std::chrono::milliseconds(500)); |
| 164 | + EXPECT_FALSE(thread_finished); |
| 165 | + |
| 166 | + // notify the clock, that the sleep shall be interrupted |
| 167 | + clock->cancel_sleep_or_wait(); |
| 168 | + |
| 169 | + auto start_time = std::chrono::steady_clock::now(); |
| 170 | + auto cur_time = start_time; |
| 171 | + while (!thread_finished && start_time + std::chrono::seconds(1) > cur_time) { |
| 172 | + std::this_thread::sleep_for(std::chrono::milliseconds(10)); |
| 173 | + cur_time = std::chrono::steady_clock::now(); |
| 174 | + } |
| 175 | + |
| 176 | + wait_thread.join(); |
| 177 | + |
| 178 | + EXPECT_TRUE(thread_finished); |
| 179 | + EXPECT_LT(cur_time, start_time + std::chrono::seconds(1)); |
| 180 | +} |
0 commit comments