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