Skip to content

Commit f3d66b8

Browse files
jmachowinskiJanosch Machowinski
and
Janosch Machowinski
authored
fix(rclcpp_action): Fix sleep of expire thread in case of canceled timer (#2800)
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 <[email protected]> Co-authored-by: Janosch Machowinski <[email protected]>
1 parent 3ca1e69 commit f3d66b8

File tree

1 file changed

+2
-3
lines changed

1 file changed

+2
-3
lines changed

rclcpp_action/src/server.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -184,9 +184,8 @@ class ServerBaseImpl
184184

185185
auto ret2 = rcl_timer_get_time_until_next_call(expire_timer, &time_until_call);
186186
if (ret2 == RCL_RET_TIMER_CANCELED) {
187-
rclcpp::Time endless(std::chrono::duration_cast<std::chrono::nanoseconds>(
188-
std::chrono::hours(100)).count(), clock_type);
189-
expire_cv->wait_until(l, endless, [this] () -> bool {
187+
rclcpp::Duration endless(std::chrono::hours(100));
188+
expire_cv->wait_until(l, clock_->now() + endless, [this] () -> bool {
190189
return expire_time_changed || terminate_expire_thread;
191190
});
192191
continue;

0 commit comments

Comments
 (0)