From e407e164d6f69c6dea17cb59ca07fef4629e26aa Mon Sep 17 00:00:00 2001 From: eric Date: Wed, 29 Apr 2020 16:39:23 -0400 Subject: [PATCH] Overwrite message receipt time to prevent gaps. --- tools/rosbag/src/recorder.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/tools/rosbag/src/recorder.cpp b/tools/rosbag/src/recorder.cpp index a4628ffe87..4fead982f5 100644 --- a/tools/rosbag/src/recorder.cpp +++ b/tools/rosbag/src/recorder.cpp @@ -409,9 +409,12 @@ void Recorder::startWriting() { 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_) { - bag_.write(out.second.topic, out.second.time, *out.second.msg); + // 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); } }