From 9b7eb217dc72dc18479f9cf760fc7b98b166d25d Mon Sep 17 00:00:00 2001 From: Michael Orlov Date: Wed, 10 Apr 2024 18:57:52 -0700 Subject: [PATCH 1/2] Gracefully handle SIGINT and SIGTERM signals for play and burst CLI (#1557) * Gracefully handle SIGINT and SIGTERM signals for play and burst CLI - Intercept signals to call Player::stop() instead of relying on the rclcpp::shutdown() in default signal handlers. - Also added static Player::Cancel() method. Signed-off-by: Michael Orlov * Add test_play_cancel to the test_transport.py Signed-off-by: Michael Orlov * Add missing imports in test_transport.py Signed-off-by: Michael Orlov * Regenerate Python stub files (.pyi) after altering API Signed-off-by: Michael Orlov * Add call for original deferred signal handler for Player and Recorder Signed-off-by: Michael Orlov --------- Signed-off-by: Michael Orlov (cherry picked from commit 32bd5c3a9b5e4ff690682f04621d42f3151ba467) # Conflicts: # rosbag2_py/rosbag2_py/_transport.pyi # rosbag2_py/src/rosbag2_py/_transport.cpp # rosbag2_transport/src/rosbag2_transport/player.cpp --- rosbag2_py/rosbag2_py/_transport.pyi | 67 ++++++ rosbag2_py/src/rosbag2_py/_transport.cpp | 219 ++++++++++++++++-- rosbag2_py/test/test_transport.py | 41 ++++ .../src/rosbag2_transport/player.cpp | 6 + 4 files changed, 309 insertions(+), 24 deletions(-) create mode 100644 rosbag2_py/rosbag2_py/_transport.pyi diff --git a/rosbag2_py/rosbag2_py/_transport.pyi b/rosbag2_py/rosbag2_py/_transport.pyi new file mode 100644 index 0000000000..2d3f771100 --- /dev/null +++ b/rosbag2_py/rosbag2_py/_transport.pyi @@ -0,0 +1,67 @@ +from typing import Any, List + +import datetime +import rosbag2_py._storage + +class PlayOptions: + clock_publish_frequency: float + clock_publish_on_topic_publish: bool + clock_topics: List[str] + delay: float + disable_keyboard_controls: bool + disable_loan_message: bool + loop: bool + node_prefix: str + playback_duration: float + playback_until_timestamp: int + rate: float + read_ahead_queue_size: int + start_offset: float + start_paused: bool + topic_qos_profile_overrides: dict + topic_remapping_options: List[str] + topics_regex_to_exclude: str + topics_regex_to_filter: str + topics_to_filter: List[str] + wait_acked_timeout: int + def __init__(self) -> None: ... + +class Player: + def __init__(self) -> None: ... + def burst(self, storage_options: rosbag2_py._storage.StorageOptions, play_options: PlayOptions, num_messages: int) -> None: ... + def cancel(self, *args, **kwargs) -> Any: ... + def play(self, storage_options: rosbag2_py._storage.StorageOptions, play_options: PlayOptions) -> None: ... + +class RecordOptions: + all_services: bool + all_topics: bool + compression_format: str + compression_mode: str + compression_queue_size: int + compression_threads: int + exclude_regex: str + exclude_service_events: List[str] + exclude_topic_types: List[str] + exclude_topics: List[str] + ignore_leaf_topics: bool + include_hidden_topics: bool + include_unpublished_topics: bool + is_discovery_disabled: bool + node_prefix: str + regex: str + rmw_serialization_format: str + services: List[str] + start_paused: bool + topic_polling_interval: datetime.timedelta + topic_qos_profile_overrides: dict + topic_types: List[str] + topics: List[str] + use_sim_time: bool + def __init__(self) -> None: ... + +class Recorder: + def __init__(self) -> None: ... + def cancel(self, *args, **kwargs) -> Any: ... + def record(self, storage_options: rosbag2_py._storage.StorageOptions, record_options: RecordOptions, node_name: str = ...) -> None: ... + +def bag_rewrite(arg0: List[rosbag2_py._storage.StorageOptions], arg1: str) -> None: ... diff --git a/rosbag2_py/src/rosbag2_py/_transport.cpp b/rosbag2_py/src/rosbag2_py/_transport.cpp index 574519ac41..3c64c4dbef 100644 --- a/rosbag2_py/src/rosbag2_py/_transport.cpp +++ b/rosbag2_py/src/rosbag2_py/_transport.cpp @@ -161,7 +161,13 @@ namespace rosbag2_py class Player { public: +<<<<<<< HEAD explicit Player(const std::string & log_level = "info") +======= + using SignalHandlerType = void (*)(int); + + Player() +>>>>>>> 32bd5c3a (Gracefully handle SIGINT and SIGTERM signals for play and burst CLI (#1557)) { Arguments arguments({"--ros-args", "--log-level", log_level}); rclcpp::init(arguments.argc(), arguments.argv()); @@ -172,10 +178,17 @@ class Player rclcpp::shutdown(); } + static void cancel() + { + exit_ = true; + wait_for_exit_cv_.notify_all(); + } + void play( const rosbag2_storage::StorageOptions & storage_options, PlayOptions & play_options) { +<<<<<<< HEAD auto reader = rosbag2_transport::ReaderWriterFactory::make_reader(storage_options); auto player = std::make_shared( std::move(reader), storage_options, play_options); @@ -190,6 +203,9 @@ class Player exec.cancel(); spin_thread.join(); +======= + play_impl(storage_options, play_options, false); +>>>>>>> 32bd5c3a (Gracefully handle SIGINT and SIGTERM signals for play and burst CLI (#1557)) } void burst( @@ -197,6 +213,7 @@ class Player PlayOptions & play_options, size_t num_messages) { +<<<<<<< HEAD auto reader = rosbag2_transport::ReaderWriterFactory::make_reader(storage_options); auto player = std::make_shared( std::move(reader), storage_options, play_options); @@ -216,13 +233,133 @@ class Player exec.cancel(); spin_thread.join(); play_thread.join(); +======= + play_impl(storage_options, play_options, true, num_messages); +>>>>>>> 32bd5c3a (Gracefully handle SIGINT and SIGTERM signals for play and burst CLI (#1557)) + } + +protected: + static void signal_handler(int sig_num) + { + if (sig_num == SIGINT || sig_num == SIGTERM) { + deferred_sig_number_ = sig_num; + rosbag2_py::Player::cancel(); + } + } + + static void install_signal_handlers() + { + deferred_sig_number_ = -1; + old_sigterm_handler_ = std::signal(SIGTERM, &rosbag2_py::Player::signal_handler); + old_sigint_handler_ = std::signal(SIGINT, &rosbag2_py::Player::signal_handler); + } + + static void uninstall_signal_handlers() + { + if (old_sigterm_handler_ != SIG_ERR) { + std::signal(SIGTERM, old_sigterm_handler_); + old_sigterm_handler_ = SIG_ERR; + } + if (old_sigint_handler_ != SIG_ERR) { + std::signal(SIGINT, old_sigint_handler_); + old_sigint_handler_ = SIG_ERR; + } + deferred_sig_number_ = -1; + } + + static void process_deferred_signal() + { + auto call_signal_handler = [](const SignalHandlerType & signal_handler, int sig_num) { + if (signal_handler != SIG_ERR && signal_handler != SIG_IGN && signal_handler != SIG_DFL) { + signal_handler(sig_num); + } + }; + + if (deferred_sig_number_ == SIGINT) { + call_signal_handler(old_sigint_handler_, deferred_sig_number_); + } else if (deferred_sig_number_ == SIGTERM) { + call_signal_handler(old_sigterm_handler_, deferred_sig_number_); + } + } + + void play_impl( + const rosbag2_storage::StorageOptions & storage_options, + PlayOptions & play_options, + bool burst = false, + size_t burst_num_messages = 0) + { + install_signal_handlers(); + try { + auto reader = rosbag2_transport::ReaderWriterFactory::make_reader(storage_options); + auto player = std::make_shared( + std::move(reader), storage_options, play_options); + + rclcpp::executors::SingleThreadedExecutor exec; + exec.add_node(player); + auto spin_thread = std::thread( + [&exec]() { + exec.spin(); + }); + player->play(); + + auto wait_for_exit_thread = std::thread( + [&]() { + std::unique_lock lock(wait_for_exit_mutex_); + wait_for_exit_cv_.wait(lock, [] {return rosbag2_py::Player::exit_.load();}); + player->stop(); + }); + { + // Release the GIL for long-running play, so that calling Python code + // can use other threads + py::gil_scoped_release release; + if (burst) { + player->burst(burst_num_messages); + } + player->wait_for_playback_to_finish(); + } + + rosbag2_py::Player::cancel(); // Need to trigger exit from wait_for_exit_thread + if (wait_for_exit_thread.joinable()) { + wait_for_exit_thread.join(); + } + + exec.cancel(); + if (spin_thread.joinable()) { + spin_thread.join(); + } + exec.remove_node(player); + } catch (...) { + process_deferred_signal(); + uninstall_signal_handlers(); + throw; + } + process_deferred_signal(); + uninstall_signal_handlers(); } + + static std::atomic_bool exit_; + static std::condition_variable wait_for_exit_cv_; + static SignalHandlerType old_sigint_handler_; + static SignalHandlerType old_sigterm_handler_; + static int deferred_sig_number_; + std::mutex wait_for_exit_mutex_; }; +Player::SignalHandlerType Player::old_sigint_handler_ {SIG_ERR}; +Player::SignalHandlerType Player::old_sigterm_handler_ {SIG_ERR}; +int Player::deferred_sig_number_{-1}; +std::atomic_bool Player::exit_{false}; +std::condition_variable Player::wait_for_exit_cv_{}; + class Recorder { public: +<<<<<<< HEAD explicit Recorder(const std::string & log_level = "info") +======= + using SignalHandlerType = void (*)(int); + Recorder() +>>>>>>> 32bd5c3a (Gracefully handle SIGINT and SIGTERM signals for play and burst CLI (#1557)) { Arguments arguments({"--ros-args", "--log-level", log_level}); rclcpp::init(arguments.argc(), arguments.argv()); @@ -238,15 +375,7 @@ class Recorder RecordOptions & record_options, std::string & node_name) { - auto old_sigterm_handler = std::signal( - SIGTERM, [](int /* signal */) { - rosbag2_py::Recorder::cancel(); - }); - auto old_sigint_handler = std::signal( - SIGINT, [](int /* signal */) { - rosbag2_py::Recorder::cancel(); - }); - + install_signal_handlers(); try { exit_ = false; auto exec = std::make_unique(); @@ -280,22 +409,12 @@ class Recorder } exec->remove_node(recorder); } catch (...) { - // Return old signal handlers anyway - if (old_sigterm_handler != SIG_ERR) { - std::signal(SIGTERM, old_sigterm_handler); - } - if (old_sigint_handler != SIG_ERR) { - std::signal(SIGTERM, old_sigint_handler); - } + process_deferred_signal(); + uninstall_signal_handlers(); throw; } - // Return old signal handlers - if (old_sigterm_handler != SIG_ERR) { - std::signal(SIGTERM, old_sigterm_handler); - } - if (old_sigint_handler != SIG_ERR) { - std::signal(SIGTERM, old_sigint_handler); - } + process_deferred_signal(); + uninstall_signal_handlers(); } static void cancel() @@ -305,11 +424,60 @@ class Recorder } protected: + static void signal_handler(int sig_num) + { + if (sig_num == SIGINT || sig_num == SIGTERM) { + deferred_sig_number_ = sig_num; + rosbag2_py::Recorder::cancel(); + } + } + + static void install_signal_handlers() + { + deferred_sig_number_ = -1; + old_sigterm_handler_ = std::signal(SIGTERM, &rosbag2_py::Recorder::signal_handler); + old_sigint_handler_ = std::signal(SIGINT, &rosbag2_py::Recorder::signal_handler); + } + + static void uninstall_signal_handlers() + { + if (old_sigterm_handler_ != SIG_ERR) { + std::signal(SIGTERM, old_sigterm_handler_); + old_sigterm_handler_ = SIG_ERR; + } + if (old_sigint_handler_ != SIG_ERR) { + std::signal(SIGINT, old_sigint_handler_); + old_sigint_handler_ = SIG_ERR; + } + deferred_sig_number_ = -1; + } + + static void process_deferred_signal() + { + auto call_signal_handler = [](const SignalHandlerType & signal_handler, int sig_num) { + if (signal_handler != SIG_ERR && signal_handler != SIG_IGN && signal_handler != SIG_DFL) { + signal_handler(sig_num); + } + }; + + if (deferred_sig_number_ == SIGINT) { + call_signal_handler(old_sigint_handler_, deferred_sig_number_); + } else if (deferred_sig_number_ == SIGTERM) { + call_signal_handler(old_sigterm_handler_, deferred_sig_number_); + } + } + static std::atomic_bool exit_; static std::condition_variable wait_for_exit_cv_; + static SignalHandlerType old_sigint_handler_; + static SignalHandlerType old_sigterm_handler_; + static int deferred_sig_number_; std::mutex wait_for_exit_mutex_; }; +Recorder::SignalHandlerType Recorder::old_sigint_handler_ {SIG_ERR}; +Recorder::SignalHandlerType Recorder::old_sigterm_handler_ {SIG_ERR}; +int Recorder::deferred_sig_number_{-1}; std::atomic_bool Recorder::exit_{false}; std::condition_variable Recorder::wait_for_exit_cv_{}; @@ -430,7 +598,10 @@ PYBIND11_MODULE(_transport, m) { .def(py::init<>()) .def(py::init()) .def("play", &rosbag2_py::Player::play, py::arg("storage_options"), py::arg("play_options")) - .def("burst", &rosbag2_py::Player::burst) + .def( + "burst", &rosbag2_py::Player::burst, py::arg("storage_options"), py::arg("play_options"), + py::arg("num_messages")) + .def_static("cancel", &rosbag2_py::Player::cancel) ; py::class_(m, "Recorder") diff --git a/rosbag2_py/test/test_transport.py b/rosbag2_py/test/test_transport.py index 4fa6d194b6..1c4c45742c 100644 --- a/rosbag2_py/test/test_transport.py +++ b/rosbag2_py/test/test_transport.py @@ -13,6 +13,8 @@ # limitations under the License. import datetime +from pathlib import Path +import re import threading from common import get_rosbag_options, wait_for @@ -26,6 +28,10 @@ from std_msgs.msg import String +RESOURCES_PATH = Path(__file__).parent / 'resources' +PLAYBACK_UNTIL_TIMESTAMP_REGEX_STRING = r'\[rosbag2_player]: Playback until timestamp: -1' + + def test_options_qos_conversion(): # Tests that the to-and-from C++ conversions are working properly in the pybind structs simple_overrides = { @@ -106,3 +112,38 @@ def test_record_cancel(tmp_path, storage_id): storage_path = bag_path / metadata.relative_file_paths[0] assert wait_for(lambda: storage_path.is_file(), timeout=rclpy.duration.Duration(seconds=3)) + + +@pytest.mark.parametrize('storage_id', TESTED_STORAGE_IDS) +def test_play_cancel(storage_id, capfd): + bag_path = str(RESOURCES_PATH / storage_id / 'talker') + storage_options, converter_options = get_rosbag_options(bag_path, storage_id) + + player = rosbag2_py.Player() + + play_options = rosbag2_py.PlayOptions() + play_options.loop = True + play_options.start_paused = True + + player_thread = threading.Thread( + target=player.play, + args=(storage_options, play_options), + daemon=True) + player_thread.start() + + def check_playback_start_output(cumulative_out, cumulative_err): + out, err = capfd.readouterr() + cumulative_err += err + cumulative_out += out + expected_string_regex = re.compile(PLAYBACK_UNTIL_TIMESTAMP_REGEX_STRING) + matches = expected_string_regex.search(cumulative_err) + return matches is not None + + captured_out = '' + captured_err = '' + assert wait_for(lambda: check_playback_start_output(captured_out, captured_err), + timeout=rclpy.duration.Duration(seconds=3)) + + player.cancel() + player_thread.join(3) + assert not player_thread.is_alive() diff --git a/rosbag2_transport/src/rosbag2_transport/player.cpp b/rosbag2_transport/src/rosbag2_transport/player.cpp index 2623ec17d1..58611f46b3 100644 --- a/rosbag2_transport/src/rosbag2_transport/player.cpp +++ b/rosbag2_transport/src/rosbag2_transport/player.cpp @@ -384,7 +384,12 @@ bool Player::play_next() return false; } +<<<<<<< HEAD RCLCPP_INFO_STREAM(get_logger(), "Playing next message."); +======= + // Use RCLCPP_DEBUG_STREAM to avoid delays in the burst mode + RCLCPP_DEBUG_STREAM(owner_->get_logger(), "Playing next message."); +>>>>>>> 32bd5c3a (Gracefully handle SIGINT and SIGTERM signals for play and burst CLI (#1557)) // Temporary take over playback from play_messages_from_queue() std::lock_guard main_play_loop_lk(skip_message_in_main_play_loop_mutex_); @@ -434,6 +439,7 @@ size_t Player::burst(const size_t num_messages) } } + RCLCPP_INFO_STREAM(owner_->get_logger(), "Burst " << messages_played << " messages."); return messages_played; } From b1d93b12b033564a52fba3756d3837fc614e0e25 Mon Sep 17 00:00:00 2001 From: Michael Orlov Date: Tue, 4 Jun 2024 16:16:13 -0700 Subject: [PATCH 2/2] Address merge conflicts Signed-off-by: Michael Orlov --- rosbag2_py/rosbag2_py/_transport.pyi | 67 ------------------- rosbag2_py/src/rosbag2_py/_transport.cpp | 65 ++++-------------- .../src/rosbag2_transport/player.cpp | 8 +-- 3 files changed, 15 insertions(+), 125 deletions(-) delete mode 100644 rosbag2_py/rosbag2_py/_transport.pyi diff --git a/rosbag2_py/rosbag2_py/_transport.pyi b/rosbag2_py/rosbag2_py/_transport.pyi deleted file mode 100644 index 2d3f771100..0000000000 --- a/rosbag2_py/rosbag2_py/_transport.pyi +++ /dev/null @@ -1,67 +0,0 @@ -from typing import Any, List - -import datetime -import rosbag2_py._storage - -class PlayOptions: - clock_publish_frequency: float - clock_publish_on_topic_publish: bool - clock_topics: List[str] - delay: float - disable_keyboard_controls: bool - disable_loan_message: bool - loop: bool - node_prefix: str - playback_duration: float - playback_until_timestamp: int - rate: float - read_ahead_queue_size: int - start_offset: float - start_paused: bool - topic_qos_profile_overrides: dict - topic_remapping_options: List[str] - topics_regex_to_exclude: str - topics_regex_to_filter: str - topics_to_filter: List[str] - wait_acked_timeout: int - def __init__(self) -> None: ... - -class Player: - def __init__(self) -> None: ... - def burst(self, storage_options: rosbag2_py._storage.StorageOptions, play_options: PlayOptions, num_messages: int) -> None: ... - def cancel(self, *args, **kwargs) -> Any: ... - def play(self, storage_options: rosbag2_py._storage.StorageOptions, play_options: PlayOptions) -> None: ... - -class RecordOptions: - all_services: bool - all_topics: bool - compression_format: str - compression_mode: str - compression_queue_size: int - compression_threads: int - exclude_regex: str - exclude_service_events: List[str] - exclude_topic_types: List[str] - exclude_topics: List[str] - ignore_leaf_topics: bool - include_hidden_topics: bool - include_unpublished_topics: bool - is_discovery_disabled: bool - node_prefix: str - regex: str - rmw_serialization_format: str - services: List[str] - start_paused: bool - topic_polling_interval: datetime.timedelta - topic_qos_profile_overrides: dict - topic_types: List[str] - topics: List[str] - use_sim_time: bool - def __init__(self) -> None: ... - -class Recorder: - def __init__(self) -> None: ... - def cancel(self, *args, **kwargs) -> Any: ... - def record(self, storage_options: rosbag2_py._storage.StorageOptions, record_options: RecordOptions, node_name: str = ...) -> None: ... - -def bag_rewrite(arg0: List[rosbag2_py._storage.StorageOptions], arg1: str) -> None: ... diff --git a/rosbag2_py/src/rosbag2_py/_transport.cpp b/rosbag2_py/src/rosbag2_py/_transport.cpp index 3c64c4dbef..9e906d103e 100644 --- a/rosbag2_py/src/rosbag2_py/_transport.cpp +++ b/rosbag2_py/src/rosbag2_py/_transport.cpp @@ -161,13 +161,9 @@ namespace rosbag2_py class Player { public: -<<<<<<< HEAD - explicit Player(const std::string & log_level = "info") -======= using SignalHandlerType = void (*)(int); - Player() ->>>>>>> 32bd5c3a (Gracefully handle SIGINT and SIGTERM signals for play and burst CLI (#1557)) + explicit Player(const std::string & log_level = "info") { Arguments arguments({"--ros-args", "--log-level", log_level}); rclcpp::init(arguments.argc(), arguments.argv()); @@ -188,24 +184,7 @@ class Player const rosbag2_storage::StorageOptions & storage_options, PlayOptions & play_options) { -<<<<<<< HEAD - auto reader = rosbag2_transport::ReaderWriterFactory::make_reader(storage_options); - auto player = std::make_shared( - std::move(reader), storage_options, play_options); - - rclcpp::executors::SingleThreadedExecutor exec; - exec.add_node(player); - auto spin_thread = std::thread( - [&exec]() { - exec.spin(); - }); - player->play(); - - exec.cancel(); - spin_thread.join(); -======= play_impl(storage_options, play_options, false); ->>>>>>> 32bd5c3a (Gracefully handle SIGINT and SIGTERM signals for play and burst CLI (#1557)) } void burst( @@ -213,29 +192,7 @@ class Player PlayOptions & play_options, size_t num_messages) { -<<<<<<< HEAD - auto reader = rosbag2_transport::ReaderWriterFactory::make_reader(storage_options); - auto player = std::make_shared( - std::move(reader), storage_options, play_options); - - rclcpp::executors::SingleThreadedExecutor exec; - exec.add_node(player); - auto spin_thread = std::thread( - [&exec]() { - exec.spin(); - }); - auto play_thread = std::thread( - [&player]() { - player->play(); - }); - player->burst(num_messages); - - exec.cancel(); - spin_thread.join(); - play_thread.join(); -======= play_impl(storage_options, play_options, true, num_messages); ->>>>>>> 32bd5c3a (Gracefully handle SIGINT and SIGTERM signals for play and burst CLI (#1557)) } protected: @@ -288,6 +245,7 @@ class Player bool burst = false, size_t burst_num_messages = 0) { + exit_ = false; install_signal_handlers(); try { auto reader = rosbag2_transport::ReaderWriterFactory::make_reader(storage_options); @@ -300,7 +258,6 @@ class Player [&exec]() { exec.spin(); }); - player->play(); auto wait_for_exit_thread = std::thread( [&]() { @@ -313,12 +270,19 @@ class Player // can use other threads py::gil_scoped_release release; if (burst) { + auto play_thread = std::thread( + [&player]() { + player->play(); + }); player->burst(burst_num_messages); + rosbag2_py::Player::cancel(); // Need to trigger exit from wait_for_exit_thread + play_thread.join(); + } else { + player->play(); + rosbag2_py::Player::cancel(); // Need to trigger exit from wait_for_exit_thread } - player->wait_for_playback_to_finish(); } - rosbag2_py::Player::cancel(); // Need to trigger exit from wait_for_exit_thread if (wait_for_exit_thread.joinable()) { wait_for_exit_thread.join(); } @@ -354,12 +318,9 @@ std::condition_variable Player::wait_for_exit_cv_{}; class Recorder { public: -<<<<<<< HEAD - explicit Recorder(const std::string & log_level = "info") -======= using SignalHandlerType = void (*)(int); - Recorder() ->>>>>>> 32bd5c3a (Gracefully handle SIGINT and SIGTERM signals for play and burst CLI (#1557)) + + explicit Recorder(const std::string & log_level = "info") { Arguments arguments({"--ros-args", "--log-level", log_level}); rclcpp::init(arguments.argc(), arguments.argv()); diff --git a/rosbag2_transport/src/rosbag2_transport/player.cpp b/rosbag2_transport/src/rosbag2_transport/player.cpp index 58611f46b3..67d4891ec1 100644 --- a/rosbag2_transport/src/rosbag2_transport/player.cpp +++ b/rosbag2_transport/src/rosbag2_transport/player.cpp @@ -384,12 +384,8 @@ bool Player::play_next() return false; } -<<<<<<< HEAD - RCLCPP_INFO_STREAM(get_logger(), "Playing next message."); -======= // Use RCLCPP_DEBUG_STREAM to avoid delays in the burst mode - RCLCPP_DEBUG_STREAM(owner_->get_logger(), "Playing next message."); ->>>>>>> 32bd5c3a (Gracefully handle SIGINT and SIGTERM signals for play and burst CLI (#1557)) + RCLCPP_DEBUG_STREAM(get_logger(), "Playing next message."); // Temporary take over playback from play_messages_from_queue() std::lock_guard main_play_loop_lk(skip_message_in_main_play_loop_mutex_); @@ -439,7 +435,7 @@ size_t Player::burst(const size_t num_messages) } } - RCLCPP_INFO_STREAM(owner_->get_logger(), "Burst " << messages_played << " messages."); + RCLCPP_INFO_STREAM(get_logger(), "Burst " << messages_played << " messages."); return messages_played; }