-
Notifications
You must be signed in to change notification settings - Fork 421
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
feat(clock): Added function to interrupt sleep
This is useful in case a second thread needs to wake up another thread, that is sleeping using a clock. Signed-off-by: Janosch Machowinski <[email protected]>
- Loading branch information
Janosch Machowinski
authored and
Janosch Machowinski
committed
Apr 10, 2024
1 parent
9ab9b1b
commit c288dbf
Showing
4 changed files
with
233 additions
and
22 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,180 @@ | ||
// Copyright 2024 Cellumation GmbH | ||
// | ||
// Licensed under the Apache License, Version 2.0 (the "License"); | ||
// you may not use this file except in compliance with the License. | ||
// You may obtain a copy of the License at | ||
// | ||
// http://www.apache.org/licenses/LICENSE-2.0 | ||
// | ||
// Unless required by applicable law or agreed to in writing, software | ||
// distributed under the License is distributed on an "AS IS" BASIS, | ||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
// See the License for the specific language governing permissions and | ||
// limitations under the License. | ||
|
||
#include <gtest/gtest.h> | ||
|
||
#include <chrono> | ||
|
||
#include "rcl/error_handling.h" | ||
#include "rcl/time.h" | ||
#include "rclcpp/clock.hpp" | ||
#include "rclcpp/rclcpp.hpp" | ||
#include "rclcpp/time_source.hpp" | ||
|
||
#include "../utils/rclcpp_gtest_macros.hpp" | ||
|
||
using namespace std::chrono_literals; | ||
class TestClockWakeup : public ::testing::Test | ||
{ | ||
public: | ||
void test_wakeup_before_sleep(const rclcpp::Clock::SharedPtr & clock) | ||
{ | ||
std::atomic_bool thread_finished = false; | ||
|
||
std::thread wait_thread = std::thread( | ||
[&clock, &thread_finished]() | ||
{ | ||
// make sure the thread starts sleeping late | ||
std::this_thread::sleep_for(std::chrono::milliseconds(100)); | ||
clock->sleep_until(clock->now() + std::chrono::seconds(3)); | ||
thread_finished = true; | ||
}); | ||
|
||
// notify the clock, that the sleep shall be interrupted | ||
clock->cancel_sleep_or_wait(); | ||
|
||
auto start_time = std::chrono::steady_clock::now(); | ||
auto cur_time = start_time; | ||
while (!thread_finished && start_time + std::chrono::seconds(1) > cur_time) { | ||
std::this_thread::sleep_for(std::chrono::milliseconds(10)); | ||
cur_time = std::chrono::steady_clock::now(); | ||
} | ||
|
||
wait_thread.join(); | ||
|
||
EXPECT_TRUE(thread_finished); | ||
EXPECT_LT(cur_time, start_time + std::chrono::seconds(1)); | ||
} | ||
|
||
void test_wakeup_after_sleep(const rclcpp::Clock::SharedPtr & clock) | ||
{ | ||
std::atomic_bool thread_finished = false; | ||
|
||
std::thread wait_thread = std::thread( | ||
[&clock, &thread_finished]() | ||
{ | ||
clock->sleep_until(clock->now() + std::chrono::seconds(3)); | ||
thread_finished = true; | ||
}); | ||
|
||
// make sure the thread is already sleeping before we send the cancel | ||
std::this_thread::sleep_for(std::chrono::milliseconds(100)); | ||
|
||
// notify the clock, that the sleep shall be interrupted | ||
clock->cancel_sleep_or_wait(); | ||
|
||
auto start_time = std::chrono::steady_clock::now(); | ||
auto cur_time = start_time; | ||
while (!thread_finished && start_time + std::chrono::seconds(1) > cur_time) { | ||
std::this_thread::sleep_for(std::chrono::milliseconds(10)); | ||
cur_time = std::chrono::steady_clock::now(); | ||
} | ||
|
||
wait_thread.join(); | ||
|
||
EXPECT_TRUE(thread_finished); | ||
EXPECT_LT(cur_time, start_time + std::chrono::seconds(1)); | ||
} | ||
|
||
protected: | ||
static void SetUpTestCase() | ||
{ | ||
rclcpp::init(0, nullptr); | ||
} | ||
|
||
static void TearDownTestCase() | ||
{ | ||
rclcpp::shutdown(); | ||
} | ||
|
||
void SetUp() | ||
{ | ||
node = std::make_shared<rclcpp::Node>("my_node"); | ||
} | ||
|
||
void TearDown() | ||
{ | ||
node.reset(); | ||
} | ||
|
||
rclcpp::Node::SharedPtr node; | ||
}; | ||
|
||
TEST_F(TestClockWakeup, wakeup_sleep_steay_time) { | ||
auto clock = std::make_shared<rclcpp::Clock>(RCL_STEADY_TIME); | ||
test_wakeup_after_sleep(clock); | ||
test_wakeup_before_sleep(clock); | ||
} | ||
|
||
TEST_F(TestClockWakeup, wakeup_sleep_system_time) { | ||
auto clock = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME); | ||
test_wakeup_after_sleep(clock); | ||
test_wakeup_before_sleep(clock); | ||
} | ||
|
||
TEST_F(TestClockWakeup, wakeup_sleep_ros_time_not_active) { | ||
auto clock = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME); | ||
test_wakeup_after_sleep(clock); | ||
test_wakeup_before_sleep(clock); | ||
} | ||
|
||
TEST_F(TestClockWakeup, wakeup_sleep_ros_time_active) { | ||
node->set_parameter({"use_sim_time", true}); | ||
auto clock = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME); | ||
rclcpp::TimeSource time_source(node); | ||
time_source.attachClock(clock); | ||
|
||
EXPECT_TRUE(clock->ros_time_is_active()); | ||
|
||
test_wakeup_after_sleep(clock); | ||
test_wakeup_before_sleep(clock); | ||
} | ||
|
||
TEST_F(TestClockWakeup, no_wakeup_on_sim_time) { | ||
node->set_parameter({"use_sim_time", true}); | ||
auto clock = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME); | ||
rclcpp::TimeSource time_source(node); | ||
time_source.attachClock(clock); | ||
|
||
EXPECT_TRUE(clock->ros_time_is_active()); | ||
|
||
std::atomic_bool thread_finished = false; | ||
|
||
std::thread wait_thread = std::thread( | ||
[&clock, &thread_finished]() | ||
{ | ||
// make sure the thread starts sleeping late | ||
clock->sleep_until(clock->now() + std::chrono::milliseconds(10)); | ||
thread_finished = true; | ||
}); | ||
|
||
// make sure, that the sim time clock does not wakeup, as no clock is provided | ||
std::this_thread::sleep_for(std::chrono::milliseconds(500)); | ||
EXPECT_FALSE(thread_finished); | ||
|
||
// notify the clock, that the sleep shall be interrupted | ||
clock->cancel_sleep_or_wait(); | ||
|
||
auto start_time = std::chrono::steady_clock::now(); | ||
auto cur_time = start_time; | ||
while (!thread_finished && start_time + std::chrono::seconds(1) > cur_time) { | ||
std::this_thread::sleep_for(std::chrono::milliseconds(10)); | ||
cur_time = std::chrono::steady_clock::now(); | ||
} | ||
|
||
wait_thread.join(); | ||
|
||
EXPECT_TRUE(thread_finished); | ||
EXPECT_LT(cur_time, start_time + std::chrono::seconds(1)); | ||
} |