Skip to content

Commit

Permalink
Use PlayerClock::wakeup() in new play_next() impl
Browse files Browse the repository at this point in the history
Signed-off-by: Christophe Bedard <[email protected]>
  • Loading branch information
christophebedard committed Dec 2, 2024
1 parent bd7129f commit 347585d
Showing 1 changed file with 4 additions and 7 deletions.
11 changes: 4 additions & 7 deletions rosbag2_transport/src/rosbag2_transport/player.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -739,10 +739,8 @@ bool PlayerImpl::play_next()

// Wait for play next to be done, and then return the result
std::unique_lock<std::mutex> lk(finished_play_next_mutex_);
// Temporarily resume clock to force wakeup in clock_->sleep_until(time),
// then return in pause mode to preserve original state of the player
clock_->resume();
clock_->pause();
// Wake up the clock in case it's in a sleep_until(time) call
clock_->wakeup();
finished_play_next_ = false;
finished_play_next_cv_.wait(lk, [this] {return finished_play_next_.load();});
play_next_ = false;
Expand Down Expand Up @@ -1044,9 +1042,8 @@ void PlayerImpl::play_messages_from_queue()
while (!stop_playback_ && is_paused() && !play_next_.load() && rclcpp::ok()) {
clock_->sleep_until(clock_->now());
}
// If we ran out of messages and are not in pause state, it means we're done playing,
// unless play_next() is resuming and pausing the clock in order to wake us up
if (!is_paused() && !play_next_.load()) {
// If we ran out of messages and are not in pause state, it means we're done playing
if (!is_paused()) {
break;
}

Expand Down

0 comments on commit 347585d

Please sign in to comment.