From 740e219b5364f96e0594cf1af521dfe638647266 Mon Sep 17 00:00:00 2001 From: Janosch Machowinski Date: Thu, 10 Apr 2025 17:44:27 +0200 Subject: [PATCH] fix(rclcpp_action): Fix sleep of expire thread in case of canceled timer This fixes a bug, that the expire action thread would not sleep as, the sleep duration was not computed correctly. Signed-off-by: Janosch Machowinski --- rclcpp_action/src/server.cpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/rclcpp_action/src/server.cpp b/rclcpp_action/src/server.cpp index dbc9311d58..27be4b0f96 100644 --- a/rclcpp_action/src/server.cpp +++ b/rclcpp_action/src/server.cpp @@ -184,9 +184,8 @@ class ServerBaseImpl auto ret2 = rcl_timer_get_time_until_next_call(expire_timer, &time_until_call); if (ret2 == RCL_RET_TIMER_CANCELED) { - rclcpp::Time endless(std::chrono::duration_cast( - std::chrono::hours(100)).count(), clock_type); - expire_cv->wait_until(l, endless, [this] () -> bool { + rclcpp::Duration endless(std::chrono::hours(100)); + expire_cv->wait_until(l, clock_->now() + endless, [this] () -> bool { return expire_time_changed || terminate_expire_thread; }); continue;