Skip to content

Commit c091fe1

Browse files
authored
Implement validity checks for rclcpp::Clock (#2040)
1 parent a20a295 commit c091fe1

File tree

3 files changed

+180
-0
lines changed

3 files changed

+180
-0
lines changed

rclcpp/include/rclcpp/clock.hpp

Lines changed: 45 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -137,6 +137,51 @@ class Clock
137137
Duration rel_time,
138138
Context::SharedPtr context = contexts::get_global_default_context());
139139

140+
/**
141+
* Check if the clock is started.
142+
*
143+
* A started clock is a clock that reflects non-zero time.
144+
* Typically a clock will be unstarted if it is using RCL_ROS_TIME with ROS time and
145+
* nothing has been published on the clock topic yet.
146+
*
147+
* \return true if clock is started
148+
* \throws std::runtime_error if the clock is not rcl_clock_valid
149+
*/
150+
RCLCPP_PUBLIC
151+
bool
152+
started();
153+
154+
/**
155+
* Wait until clock to start.
156+
*
157+
* \rclcpp::Clock::started
158+
* \param context the context to wait in
159+
* \return true if clock was already started or became started
160+
* \throws std::runtime_error if the context is invalid or clock is not rcl_clock_valid
161+
*/
162+
RCLCPP_PUBLIC
163+
bool
164+
wait_until_started(Context::SharedPtr context = contexts::get_global_default_context());
165+
166+
/**
167+
* Wait for clock to start, with timeout.
168+
*
169+
* The timeout is waited in steady time.
170+
*
171+
* \rclcpp::Clock::started
172+
* \param timeout the maximum time to wait for.
173+
* \param context the context to wait in.
174+
* \param wait_tick_ns the time to wait between each iteration of the wait loop (in nanoseconds).
175+
* \return true if clock was or became valid
176+
* \throws std::runtime_error if the context is invalid or clock is not rcl_clock_valid
177+
*/
178+
RCLCPP_PUBLIC
179+
bool
180+
wait_until_started(
181+
const rclcpp::Duration & timeout,
182+
Context::SharedPtr context = contexts::get_global_default_context(),
183+
const rclcpp::Duration & wait_tick_ns = rclcpp::Duration(0, static_cast<uint32_t>(1e7)));
184+
140185
/**
141186
* Returns the clock of the type `RCL_ROS_TIME` is active.
142187
*

rclcpp/src/rclcpp/clock.cpp

Lines changed: 65 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -182,6 +182,71 @@ Clock::sleep_for(Duration rel_time, Context::SharedPtr context)
182182
return sleep_until(now() + rel_time, context);
183183
}
184184

185+
bool
186+
Clock::started()
187+
{
188+
if (!rcl_clock_valid(get_clock_handle())) {
189+
throw std::runtime_error("clock is not rcl_clock_valid");
190+
}
191+
return rcl_clock_time_started(get_clock_handle());
192+
}
193+
194+
bool
195+
Clock::wait_until_started(Context::SharedPtr context)
196+
{
197+
if (!context || !context->is_valid()) {
198+
throw std::runtime_error("context cannot be slept with because it's invalid");
199+
}
200+
if (!rcl_clock_valid(get_clock_handle())) {
201+
throw std::runtime_error("clock cannot be waited on as it is not rcl_clock_valid");
202+
}
203+
204+
if (started()) {
205+
return true;
206+
} else {
207+
// Wait until the first non-zero time
208+
return sleep_until(rclcpp::Time(0, 1, get_clock_type()), context);
209+
}
210+
}
211+
212+
bool
213+
Clock::wait_until_started(
214+
const Duration & timeout,
215+
Context::SharedPtr context,
216+
const Duration & wait_tick_ns)
217+
{
218+
if (!context || !context->is_valid()) {
219+
throw std::runtime_error("context cannot be slept with because it's invalid");
220+
}
221+
if (!rcl_clock_valid(get_clock_handle())) {
222+
throw std::runtime_error("clock cannot be waited on as it is not rcl_clock_valid");
223+
}
224+
225+
Clock timeout_clock = Clock(RCL_STEADY_TIME);
226+
Time start = timeout_clock.now();
227+
228+
// Check if the clock has started every wait_tick_ns nanoseconds
229+
// Context check checks for rclcpp::shutdown()
230+
while (!started() && context->is_valid()) {
231+
if (timeout < wait_tick_ns) {
232+
timeout_clock.sleep_for(timeout);
233+
} else {
234+
Duration time_left = start + timeout - timeout_clock.now();
235+
if (time_left > wait_tick_ns) {
236+
timeout_clock.sleep_for(Duration(wait_tick_ns));
237+
} else {
238+
timeout_clock.sleep_for(time_left);
239+
}
240+
}
241+
242+
if (timeout_clock.now() - start > timeout) {
243+
return started();
244+
}
245+
}
246+
return started();
247+
}
248+
249+
185250
bool
186251
Clock::ros_time_is_active()
187252
{

rclcpp/test/rclcpp/test_time.cpp

Lines changed: 70 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
#include <limits>
2020
#include <memory>
2121
#include <string>
22+
#include <thread>
2223

2324
#include "rcl/error_handling.h"
2425
#include "rcl/time.h"
@@ -848,3 +849,72 @@ TEST_F(TestClockSleep, sleep_for_basic_ros) {
848849
sleep_thread.join();
849850
EXPECT_TRUE(sleep_succeeded);
850851
}
852+
853+
class TestClockStarted : public ::testing::Test
854+
{
855+
protected:
856+
void SetUp()
857+
{
858+
rclcpp::init(0, nullptr);
859+
}
860+
861+
void TearDown()
862+
{
863+
rclcpp::shutdown();
864+
}
865+
};
866+
867+
TEST_F(TestClockStarted, started) {
868+
// rclcpp::Clock ros_clock(RCL_ROS_TIME);
869+
// auto ros_clock_handle = ros_clock.get_clock_handle();
870+
//
871+
// // At this point, the ROS clock is reading system time since the ROS time override isn't on
872+
// // So we expect it to be started (it's extremely unlikely that system time is at epoch start)
873+
// EXPECT_TRUE(ros_clock.started());
874+
// EXPECT_TRUE(ros_clock.wait_until_started());
875+
// EXPECT_TRUE(ros_clock.wait_until_started(rclcpp::Duration(0, static_cast<uint32_t>(1e7))));
876+
// EXPECT_EQ(RCL_RET_OK, rcl_enable_ros_time_override(ros_clock_handle));
877+
// EXPECT_TRUE(ros_clock.ros_time_is_active());
878+
// EXPECT_FALSE(ros_clock.started());
879+
// EXPECT_EQ(RCL_RET_OK, rcl_set_ros_time_override(ros_clock_handle, 1));
880+
// EXPECT_TRUE(ros_clock.started());
881+
//
882+
// rclcpp::Clock system_clock(RCL_SYSTEM_TIME);
883+
// EXPECT_TRUE(system_clock.started());
884+
// EXPECT_TRUE(system_clock.wait_until_started());
885+
// EXPECT_TRUE(system_clock.wait_until_started(rclcpp::Duration(0, static_cast<uint32_t>(1e7))));
886+
//
887+
// rclcpp::Clock steady_clock(RCL_STEADY_TIME);
888+
// EXPECT_TRUE(steady_clock.started());
889+
// EXPECT_TRUE(steady_clock.wait_until_started());
890+
// EXPECT_TRUE(steady_clock.wait_until_started(rclcpp::Duration(0, static_cast<uint32_t>(1e7))));
891+
//
892+
// rclcpp::Clock uninit_clock(RCL_CLOCK_UNINITIALIZED);
893+
// RCLCPP_EXPECT_THROW_EQ(
894+
// uninit_clock.started(), std::runtime_error("clock is not rcl_clock_valid"));
895+
// RCLCPP_EXPECT_THROW_EQ(
896+
// uninit_clock.wait_until_started(rclcpp::Duration(0, static_cast<uint32_t>(1e7))),
897+
// std::runtime_error("clock cannot be waited on as it is not rcl_clock_valid"));
898+
}
899+
900+
TEST_F(TestClockStarted, started_timeout) {
901+
rclcpp::Clock ros_clock(RCL_ROS_TIME);
902+
auto ros_clock_handle = ros_clock.get_clock_handle();
903+
904+
EXPECT_EQ(RCL_RET_OK, rcl_enable_ros_time_override(ros_clock_handle));
905+
EXPECT_TRUE(ros_clock.ros_time_is_active());
906+
907+
EXPECT_EQ(RCL_RET_OK, rcl_set_ros_time_override(ros_clock_handle, 0));
908+
909+
EXPECT_FALSE(ros_clock.started());
910+
EXPECT_FALSE(ros_clock.wait_until_started(rclcpp::Duration(0, static_cast<uint32_t>(1e7))));
911+
912+
std::thread t([]() {
913+
std::this_thread::sleep_for(std::chrono::seconds(1));
914+
rclcpp::shutdown();
915+
});
916+
917+
// Test rclcpp shutdown escape hatch (otherwise this waits indefinitely)
918+
EXPECT_FALSE(ros_clock.wait_until_started());
919+
t.join();
920+
}

0 commit comments

Comments
 (0)