From b5156d7b0d8e735965a8d88ac2c7bc8e11159cb4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=C3=98ystein=20Sture?= Date: Fri, 10 Jan 2025 09:56:33 +0100 Subject: [PATCH] Rename stop_discovery to discovery_running and change logic accordingly MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Øystein Sture --- .../src/rosbag2_transport/recorder.cpp | 20 +++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/rosbag2_transport/src/rosbag2_transport/recorder.cpp b/rosbag2_transport/src/rosbag2_transport/recorder.cpp index 068506570..94703768f 100644 --- a/rosbag2_transport/src/rosbag2_transport/recorder.cpp +++ b/rosbag2_transport/src/rosbag2_transport/recorder.cpp @@ -143,7 +143,7 @@ class RecorderImpl std::mutex start_stop_transition_mutex_; std::mutex discovery_mutex_; - std::atomic stop_discovery_ = true; + std::atomic discovery_running_ = false; std::atomic_uchar paused_ = 0; std::atomic in_recording_ = false; std::shared_ptr keyboard_handler_; @@ -440,21 +440,18 @@ bool RecorderImpl::is_paused() void RecorderImpl::start_discovery() { std::lock_guard state_lock(discovery_mutex_); - if (stop_discovery_.exchange(false)) { + if (discovery_running_.exchange(true)) { + RCLCPP_DEBUG(node->get_logger(), "Recorder topic discovery is already running."); + } else { discovery_future_ = std::async(std::launch::async, std::bind(&RecorderImpl::topics_discovery, this)); - } else { - RCLCPP_DEBUG(node->get_logger(), "Recorder topic discovery is already running."); } } void RecorderImpl::stop_discovery() { std::lock_guard state_lock(discovery_mutex_); - if (stop_discovery_.exchange(true)) { - RCLCPP_DEBUG( - node->get_logger(), "Recorder topic discovery has already been stopped or not running."); - } else { + if (discovery_running_.exchange(false)) { if (discovery_future_.valid()) { auto status = discovery_future_.wait_for(2 * record_options_.topic_polling_interval); if (status != std::future_status::ready) { @@ -465,6 +462,9 @@ void RecorderImpl::stop_discovery() (status == std::future_status::timeout ? "timeout" : "deferred")); } } + } else { + RCLCPP_DEBUG( + node->get_logger(), "Recorder topic discovery has already been stopped or not running."); } } @@ -475,7 +475,7 @@ void RecorderImpl::topics_discovery() RCLCPP_INFO( node->get_logger(), "use_sim_time set, waiting for /clock before starting recording..."); - while (rclcpp::ok() && stop_discovery_ == false) { + while (rclcpp::ok() && discovery_running_) { if (node->get_clock()->wait_until_started(record_options_.topic_polling_interval)) { break; } @@ -484,7 +484,7 @@ void RecorderImpl::topics_discovery() RCLCPP_INFO(node->get_logger(), "Sim time /clock found, starting recording."); } } - while (rclcpp::ok() && stop_discovery_ == false) { + while (rclcpp::ok() && discovery_running_) { try { auto topics_to_subscribe = get_requested_or_available_topics(); for (const auto & topic_and_type : topics_to_subscribe) {