MainWindow::instance()->showInfoMessage(tr("MAVLink Logging Stopped during Replay"),tr("MAVLink logging has been stopped during the log replay. To re-enable logging, use the link properties in the communication menu."));
}
// Ensure that the playback process is stopped
// Make sure to stop the logging process and reset everything.
reset();
// And that the old file is closed nicely.
if(logFile.isOpen())
{
pause();
logFile.close();
}
logFile.setFileName(file);
// Now load the new file.
logFile.setFileName(file);
if(!logFile.open(QFile::ReadOnly))
{
MainWindow::instance()->showCriticalMessage(tr("The selected logfile is unreadable"),tr("Please make sure that the file %1 is readable or select a different file").arg(file));
MainWindow::instance()->showCriticalMessage(tr("The selected logfile cannot be processed"),tr("No valid timestamps were found at the end of the logfile.").arg(file));
// Check if the correct number of bytes could be read
if(startBytes.length()!=timeLen)
{
ui->logStatsLabel->setText(tr("Error reading first %1 bytes").arg(timeLen));
MainWindow::instance()->showCriticalMessage(tr("Failed loading MAVLink Logfile"),tr("Error reading first %1 bytes from logfile. Got %2 instead of %1 bytes. Is the logfile readable?").arg(timeLen).arg(startBytes.length()));
reset();
return;
}
// Emit this message to our MAVLink parser.
emitbytesReady(logLink,message);
// Convert data to timestamp
startTime=*((quint64*)(startBytes.constData()));
currentStartTime=QGC::groundTimeUsecs();
ok=true;
//qDebug() << "START TIME: " << startTime;
// Check if these bytes could be correctly decoded
// TODO
if(!ok)
// If we've reached the end of the of the file, make sure we handle that well
if(logFile.atEnd())
{
ui->logStatsLabel->setText(tr("Error decoding first timestamp, aborting."));
MainWindow::instance()->showCriticalMessage(tr("Failed loading MAVLink Logfile"),tr("Could not load initial timestamp from file %1. Is the file corrupted?").arg(logFile.fileName()));
reset();
// For some reason calling pause() here doesn't work, so we update the UI manually here.
quint64playbackStartTime;///< The time when the logfile was first played back. This is used to pace out replaying the messages to fix long-term drift/skew. 0 indicates that the player hasn't initiated playback of this log file. In units of milliseconds since epoch UTC.
quint64logCurrentTime;///< The timestamp of the next message in the log file. In units of microseconds since epoch UTC.
quint64logStartTime;///< The first timestamp in the current log file. In units of microseconds since epoch UTC.
quint64logEndTime;///< The last timestamp in the current log file. In units of microseconds since epoch UTC.
floataccelerationFactor;
MAVLinkProtocol*mavlink;
MAVLinkSimulationLink*logLink;
QFilelogFile;
QTimerloopTimer;
intloopCounter;
boolmavlinkLogFormat;
boolmavlinkLogFormat;///< If the logfile is stored in the timestamped MAVLink log format
intbinaryBaudRate;
staticconstintdefaultBinaryBaudRate=57600;
boolisPlaying;
unsignedintcurrPacketCount;
staticconstintpacketLen=MAVLINK_MAX_PACKET_LEN;
...
...
@@ -100,6 +101,35 @@ protected:
private:
Ui::QGCMAVLinkLogPlayer*ui;
virtualvoidpaintEvent(QPaintEvent*);
/** @brief Parse out a quint64 timestamp in microseconds in the proper endianness. */
quint64parseTimestamp(constQByteArray&data);
/**
* This function parses out the next MAVLink message and its corresponding timestamp.
*
* It makes no assumptions about where in the file we currently are. It leaves the file right
* at the beginning of the successfully parsed message. Note that this function will not attempt to
* correct for any MAVLink parsing failures, so it always returns the next successfully-parsed
* message.
*
* @param msg[output] Where the final parsed message output will go.
* @return A Unix timestamp in microseconds UTC or 0 if parsing failed