From 03f6194cb2e8b4a7891a9f6dc533a2116fc6ce11 Mon Sep 17 00:00:00 2001 From: nleblanc-lr <73852356+nleblanc-lr@users.noreply.github.com> Date: Tue, 1 Oct 2024 13:03:32 -0400 Subject: [PATCH] Copy latched messages once per split with connection header (#37) --- tools/rosbag/src/recorder.cpp | 12 ------------ 1 file changed, 12 deletions(-) diff --git a/tools/rosbag/src/recorder.cpp b/tools/rosbag/src/recorder.cpp index b9b8004474..d77d5a56b3 100644 --- a/tools/rosbag/src/recorder.cpp +++ b/tools/rosbag/src/recorder.cpp @@ -454,18 +454,6 @@ void Recorder::startWriting() { } ROS_INFO("Recording to '%s'.", target_filename_.c_str()); - if (options_.repeat_latched) - { - // Start each new bag file with copies of all latched messages. - ros::Time now = ros::Time::now(); - for (auto const& out : latched_msgs_) - { - // Overwrite the original receipt time, otherwise the new bag will - // have a gap before the new messages start. - bag_.write(out.second.topic, now, *out.second.msg); - } - } - if (options_.repeat_latched) { // Start each new bag file with copies of all latched messages.