From 5ee71d9c4c63ee288125078ef5f426137eaa6262 Mon Sep 17 00:00:00 2001 From: Sathya Subramanian Date: Thu, 2 Jan 2025 00:03:15 -0600 Subject: [PATCH] fix coalesce_interval_ms not working correctly --- joy/src/joy.cpp | 12 ++---------- 1 file changed, 2 insertions(+), 10 deletions(-) diff --git a/joy/src/joy.cpp b/joy/src/joy.cpp index c3e8c9df..6717a047 100644 --- a/joy/src/joy.cpp +++ b/joy/src/joy.cpp @@ -450,16 +450,8 @@ void Joy::eventThread() } else { RCLCPP_INFO(get_logger(), "Unknown event type %d", e.type); } - } - - if (!should_publish) { - // So far, nothing has indicated that we should publish. However we need to - // do additional checking since there are several possible reasons: - // 1. SDL_WaitEventTimeout failed - // 2. SDL_WaitEventTimeout timed out - // 3. SDL_WaitEventTimeout succeeded, but the event that happened didn't cause - // a publish to happen. - // + } else { + // We didn't succeed, either because of a failure or because of a timeout. // If we are autorepeating and enough time has passed, set should_publish. rclcpp::Time now = this->now(); rclcpp::Duration diff_since_last_publish = now - last_publish;