Skip to content

Commit

Permalink
Overwrite message receipt time to prevent gaps.
Browse files Browse the repository at this point in the history
  • Loading branch information
eric committed Apr 29, 2020
1 parent 38b5916 commit e407e16
Showing 1 changed file with 4 additions and 1 deletion.
5 changes: 4 additions & 1 deletion tools/rosbag/src/recorder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
}

Expand Down

0 comments on commit e407e16

Please sign in to comment.