Skip to content

Commit

Permalink
next_call_time will always be greater than now after calling rcl_time…
Browse files Browse the repository at this point in the history
…r_call. (#1089)

If next_call_time equals now, consecutive callback calls with the same timestamp can occur when using sim time.

Signed-off-by: Thiemo Kohrt <[email protected]>
  • Loading branch information
kohrt authored Oct 12, 2023
1 parent e37d7f8 commit 45fc952
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions rcl/src/rcl/timer.c
Original file line number Diff line number Diff line change
Expand Up @@ -294,15 +294,15 @@ rcl_timer_call(rcl_timer_t * timer)
// between the timer being ready and the callback being triggered
next_call_time += period;
// in case the timer has missed at least once cycle
if (next_call_time < now) {
if (next_call_time <= now) {
if (0 == period) {
// a timer with a period of zero is considered always ready
next_call_time = now;
} else {
// move the next call time forward by as many periods as necessary
int64_t now_ahead = now - next_call_time;
// rounding up without overflow
int64_t periods_ahead = 1 + (now_ahead - 1) / period;
int64_t periods_ahead = 1 + now_ahead / period;
next_call_time += periods_ahead * period;
}
}
Expand Down

0 comments on commit 45fc952

Please sign in to comment.