Browse Source

Merge pull request #6815 from DonLakeFlyer/LogReplay

Log Replay: Back up further from end of file to handle more cases
QGC4.4
Don Gagne 7 years ago committed by GitHub
parent
commit
f52b7748ef
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 2
      src/comm/LogReplayLink.cc

2
src/comm/LogReplayLink.cc

@ -269,7 +269,7 @@ bool LogReplayLink::_loadLogFile(void) @@ -269,7 +269,7 @@ bool LogReplayLink::_loadLogFile(void)
// timestamp size. This guarantees that we will hit a MAVLink packet before
// the end of the file. Unfortunately, it basically guarantees that we will
// hit more than one. This is why we have to search for a bit.
qint64 fileLoc = _logFile.size() - MAVLINK_MAX_PACKET_LEN - cbTimestamp;
qint64 fileLoc = _logFile.size() - ((MAVLINK_MAX_PACKET_LEN - cbTimestamp) * 2);
_logFile.seek(fileLoc);
quint64 endTimeUSecs = startTimeUSecs; // Set a sane default for the endtime
mavlink_message_t msg;

Loading…
Cancel
Save