Commit 321f21f2 authored by Bryant Mairs's avatar Bryant Mairs

QGC data logging now records small MAVLink messages.

Previously MAVLink data streams recorded by QGC would use a fixed block size of the maximum MAVLink message length and fill in only the bytes written by the message. This wasted space, make manual parsing difficult, and broke compatibility with scripts provided in the MAVLink project (issue #174).

This patch alters logging to output only a packed data stream (64-bit big endian unix timestamp in microseconds since epoch + MAVLink message) instead of the unpacked data stream previously output. Additionally the previous logging code used the system endianness for packing in the timestamp, this has now been switched to always be big endian regardless of platform. All the documentation specifies big endian, so the code now follows the docs here.

Additionally data playback has been modified to playback both the new packed data streams as well as the old data streams, even those with improper endianness for their timestamps.

Finally, a variety of bugs have been fixed, along with some additional features and user experience changes, hopefully for the better. All existing functionality has been preserved as well.
parent fda0d238
......@@ -16,6 +16,7 @@
#include <QMessageBox>
#include <QSettings>
#include <QDesktopServices>
#include <QtEndian>
#include "MAVLinkProtocol.h"
#include "UASInterface.h"
......@@ -358,19 +359,26 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
// Log data
if (m_loggingEnabled && m_logfile)
{
uint8_t buf[MAVLINK_MAX_PACKET_LEN+sizeof(quint64)] = {0};
quint64 time = QGC::groundTimeUsecs();
memcpy(buf, (void*)&time, sizeof(quint64));
// Write message to buffer
mavlink_msg_to_send_buffer(buf+sizeof(quint64), &message);
//we need to write the maximum package length for having a
//consistent file structure and beeing able to parse it again
int len = MAVLINK_MAX_PACKET_LEN + sizeof(quint64);
uint8_t buf[MAVLINK_MAX_PACKET_LEN+sizeof(quint64)];
// Write the uint64 time in microseconds in big endian format before the message.
// This timestamp is saved in UTC time. We are only saving in ms precision because
// getting more than this isn't possible with Qt without a ton of extra code.
quint64 time = (quint64)QDateTime::currentMSecsSinceEpoch() * 1000;
qToBigEndian(time, buf);
// Then write the message to the buffer
int len = mavlink_msg_to_send_buffer(buf + sizeof(quint64), &message);
// Determine how many bytes were written by adding the timestamp size to the message size
len += sizeof(quint64);
// Now write this timestamp/message pair to the log.
QByteArray b((const char*)buf, len);
if(m_logfile->write(b) != len)
{
// If there's an error logging data, raise an alert and stop logging.
emit protocolStatusMessage(tr("MAVLink Logging failed"), tr("Could not write to file %1, disabling logging.").arg(m_logfile->fileName()));
// Stop logging
enableLogging(false);
}
}
......
This diff is collapsed.
......@@ -52,10 +52,10 @@ public slots:
void playPause(bool play);
/** @brief Replay the logfile */
void play();
/** @brief Pause the logfile */
/** @brief Pause the log player. */
void pause();
/** @brief Reset the logfile */
bool reset(int packetIndex=0);
/** @brief Reset the internal log player state, including the UI */
void reset();
/** @brief Select logfile */
bool selectLogFile(const QString startDirectory);
/** @brief Select logfile */
......@@ -72,21 +72,22 @@ public slots:
signals:
/** @brief Send ready bytes */
void bytesReady(LinkInterface* link, const QByteArray& bytes);
void logFileEndReached();
protected:
int lineCounter;
int totalLines;
quint64 startTime;
quint64 endTime;
quint64 currentStartTime;
quint64 playbackStartTime; ///< 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.
quint64 logCurrentTime; ///< The timestamp of the next message in the log file. In units of microseconds since epoch UTC.
quint64 logStartTime; ///< The first timestamp in the current log file. In units of microseconds since epoch UTC.
quint64 logEndTime; ///< The last timestamp in the current log file. In units of microseconds since epoch UTC.
float accelerationFactor;
MAVLinkProtocol* mavlink;
MAVLinkSimulationLink* logLink;
QFile logFile;
QTimer loopTimer;
int loopCounter;
bool mavlinkLogFormat;
bool mavlinkLogFormat; ///< If the logfile is stored in the timestamped MAVLink log format
int binaryBaudRate;
static const int defaultBinaryBaudRate = 57600;
bool isPlaying;
unsigned int currPacketCount;
static const int packetLen = MAVLINK_MAX_PACKET_LEN;
......@@ -100,6 +101,35 @@ protected:
private:
Ui::QGCMAVLinkLogPlayer *ui;
virtual void paintEvent(QPaintEvent *);
/** @brief Parse out a quint64 timestamp in microseconds in the proper endianness. */
quint64 parseTimestamp(const QByteArray &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
*/
quint64 findNextMavlinkMessage(mavlink_message_t *msg);
/**
* Updates the QSlider UI to be at the given percentage.
* @param percent A percentage value between 0.0% and 100.0%.
*/
void updatePositionSliderUi(float percent);
/**
* Jumps to a new position in the current playback file as a percentage.
* @param percentage The position of the file to jump to as a percentage.
* @return True if the new file position was successfully jumped to, false otherwise
*/
bool jumpToPlaybackLocation(float percentage);
};
#endif // QGCMAVLINKLOGPLAYER_H
......@@ -29,7 +29,7 @@
<item>
<widget class="QLabel" name="logStatsLabel">
<property name="text">
<string>No logfile selected..</string>
<string/>
</property>
</widget>
</item>
......@@ -54,6 +54,16 @@
<property name="checkable">
<bool>true</bool>
</property>
<property name="checked">
<bool>false</bool>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="timeLabel">
<property name="text">
<string>Time</string>
</property>
</widget>
</item>
<item>
......@@ -119,7 +129,7 @@
<item>
<widget class="QLabel" name="logFileNameLabel">
<property name="text">
<string>-</string>
<string>No logfile selected..</string>
</property>
</widget>
</item>
......
......@@ -37,7 +37,7 @@ QGCStatusBar::QGCStatusBar(QWidget *parent) :
{
setObjectName("QGC_STATUSBAR");
toggleLoggingButton = new QPushButton("Logging", this);
toggleLoggingButton = new QPushButton(tr("Log to file"), this);
toggleLoggingButton->setCheckable(true);
addPermanentWidget(toggleLoggingButton);
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment