Commit b997b4d8 authored by pixhawk's avatar pixhawk

Added binary format option to MAVLink log player

parent cb002ae9
...@@ -18,6 +18,8 @@ QGCMAVLinkLogPlayer::QGCMAVLinkLogPlayer(MAVLinkProtocol* mavlink, QWidget *pare ...@@ -18,6 +18,8 @@ QGCMAVLinkLogPlayer::QGCMAVLinkLogPlayer(MAVLinkProtocol* mavlink, QWidget *pare
mavlink(mavlink), mavlink(mavlink),
logLink(NULL), logLink(NULL),
loopCounter(0), loopCounter(0),
mavlinkLogFormat(true),
binaryBaudRate(57600),
ui(new Ui::QGCMAVLinkLogPlayer) ui(new Ui::QGCMAVLinkLogPlayer)
{ {
ui->setupUi(this); ui->setupUi(this);
...@@ -62,7 +64,20 @@ void QGCMAVLinkLogPlayer::play() ...@@ -62,7 +64,20 @@ void QGCMAVLinkLogPlayer::play()
logLink = new MAVLinkSimulationLink(""); logLink = new MAVLinkSimulationLink("");
// Start timer // Start timer
loopTimer.start(1); if (mavlinkLogFormat)
{
loopTimer.start(1);
}
else
{
// Read len bytes at a time
int len = 100;
// Calculate the number of times to read 100 bytes per second
// to guarantee the baud rate, then divide 1000 by the number of read
// operations to obtain the interval in milliseconds
int interval = 1000 / ((binaryBaudRate / 10) / len);
loopTimer.start(interval);
}
} }
else else
{ {
...@@ -124,7 +139,7 @@ bool QGCMAVLinkLogPlayer::reset(int packetIndex) ...@@ -124,7 +139,7 @@ bool QGCMAVLinkLogPlayer::reset(int packetIndex)
void QGCMAVLinkLogPlayer::selectLogFile() void QGCMAVLinkLogPlayer::selectLogFile()
{ {
QString fileName = QFileDialog::getOpenFileName(this, tr("Specify MAVLink log file name"), QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), tr("MAVLink Logfile (*.mavlink);;")); QString fileName = QFileDialog::getOpenFileName(this, tr("Specify MAVLink log file name"), QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), tr("MAVLink or Binary Logfile (*.mavlink; *.bin);;"));
loadLogFile(fileName); loadLogFile(fileName);
} }
...@@ -180,6 +195,11 @@ void QGCMAVLinkLogPlayer::loadLogFile(const QString& file) ...@@ -180,6 +195,11 @@ void QGCMAVLinkLogPlayer::loadLogFile(const QString& file)
startTime = 0; startTime = 0;
ui->logFileNameLabel->setText(tr("%1").arg(logFileInfo.baseName())); ui->logFileNameLabel->setText(tr("%1").arg(logFileInfo.baseName()));
// Select if binary or MAVLink log format is used
mavlinkLogFormat = file.endsWith(".mavlink");
if (mavlinkLogFormat)
{
// Get the time interval from the logfile // Get the time interval from the logfile
QByteArray timestamp = logFile.read(timeLen); QByteArray timestamp = logFile.read(timeLen);
...@@ -205,6 +225,32 @@ void QGCMAVLinkLogPlayer::loadLogFile(const QString& file) ...@@ -205,6 +225,32 @@ void QGCMAVLinkLogPlayer::loadLogFile(const QString& file)
QString timelabel = tr("%1h:%2m:%3s").arg(hours, 2).arg(minutes, 2).arg(seconds, 2); QString timelabel = tr("%1h:%2m:%3s").arg(hours, 2).arg(minutes, 2).arg(seconds, 2);
ui->logStatsLabel->setText(tr("%2 MB, %3 packets, %4").arg(logFileInfo.size()/1000000.0f, 0, 'f', 2).arg(logFileInfo.size()/(MAVLINK_MAX_PACKET_LEN+sizeof(quint64))).arg(timelabel)); ui->logStatsLabel->setText(tr("%2 MB, %3 packets, %4").arg(logFileInfo.size()/1000000.0f, 0, 'f', 2).arg(logFileInfo.size()/(MAVLINK_MAX_PACKET_LEN+sizeof(quint64))).arg(timelabel));
} }
else
{
QStringList parts = file.split("_");
if (parts.count() > 1)
{
bool ok;
int rate = parts.last().toInt(&ok);
// 9600 baud to 100 MBit
if (ok && (rate > 9600 && rate < 100000000))
{
// Accept this as valid baudrate
binaryBaudRate = rate;
}
}
int seconds = logFileInfo.size() / (binaryBaudRate / 10);
int minutes = seconds / 60;
int hours = minutes / 60;
seconds -= 60*minutes;
minutes -= 60*hours;
QString timelabel = tr("%1h:%2m:%3s").arg(hours, 2).arg(minutes, 2).arg(seconds, 2);
ui->logStatsLabel->setText(tr("%2 MB, %4 at %5 KB/s").arg(logFileInfo.size()/1000000.0f, 0, 'f', 2).arg(timelabel).arg(binaryBaudRate/10/1024));
}
}
} }
/** /**
...@@ -236,6 +282,8 @@ void QGCMAVLinkLogPlayer::jumpToSliderVal(int slidervalue) ...@@ -236,6 +282,8 @@ void QGCMAVLinkLogPlayer::jumpToSliderVal(int slidervalue)
*/ */
void QGCMAVLinkLogPlayer::logLoop() void QGCMAVLinkLogPlayer::logLoop()
{ {
if (mavlinkLogFormat)
{
bool ok; bool ok;
// First check initialization // First check initialization
...@@ -346,6 +394,30 @@ void QGCMAVLinkLogPlayer::logLoop() ...@@ -346,6 +394,30 @@ void QGCMAVLinkLogPlayer::logLoop()
// Update progress bar // Update progress bar
} }
} }
else
{
// Binary format - read at fixed rate
const int len = 100;
QByteArray chunk = logFile.read(len);
// Emit this packet
emit bytesReady(logLink, chunk);
// Check if reached end of file before reading next timestamp
if (chunk.length() < len || logFile.atEnd())
{
// Reached end of file
reset();
QString status = tr("Reached end of binary log file.");
ui->logStatsLabel->setText(status);
MainWindow::instance()->showStatusMessage(status);
return;
}
}
}
void QGCMAVLinkLogPlayer::changeEvent(QEvent *e) void QGCMAVLinkLogPlayer::changeEvent(QEvent *e)
{ {
......
...@@ -61,6 +61,8 @@ protected: ...@@ -61,6 +61,8 @@ protected:
QFile logFile; QFile logFile;
QTimer loopTimer; QTimer loopTimer;
int loopCounter; int loopCounter;
bool mavlinkLogFormat;
int binaryBaudRate;
static const int packetLen = MAVLINK_MAX_PACKET_LEN; static const int packetLen = MAVLINK_MAX_PACKET_LEN;
static const int timeLen = sizeof(quint64); static const int timeLen = sizeof(quint64);
void changeEvent(QEvent *e); void changeEvent(QEvent *e);
......
...@@ -205,10 +205,15 @@ void WaypointView::changedCurrent(int state) ...@@ -205,10 +205,15 @@ void WaypointView::changedCurrent(int state)
void WaypointView::updateValues() void WaypointView::updateValues()
{ {
// Deactivate signals from the WP
wp->blockSignals(true);
// update frame // update frame
MAV_FRAME frame = wp->getFrame(); MAV_FRAME frame = wp->getFrame();
int frame_index = m_ui->comboBox_frame->findData(frame); int frame_index = m_ui->comboBox_frame->findData(frame);
m_ui->comboBox_frame->setCurrentIndex(frame_index); if (m_ui->comboBox_frame->currentIndex() != frame_index)
{
m_ui->comboBox_frame->setCurrentIndex(frame_index);
}
switch(frame) switch(frame)
{ {
case(MAV_FRAME_LOCAL): case(MAV_FRAME_LOCAL):
...@@ -249,6 +254,7 @@ void WaypointView::updateValues() ...@@ -249,6 +254,7 @@ void WaypointView::updateValues()
m_ui->idLabel->setText(QString("%1").arg(wp->getId()));\ m_ui->idLabel->setText(QString("%1").arg(wp->getId()));\
m_ui->orbitSpinBox->setValue(wp->getOrbit()); m_ui->orbitSpinBox->setValue(wp->getOrbit());
m_ui->holdTimeSpinBox->setValue(wp->getHoldTime()); m_ui->holdTimeSpinBox->setValue(wp->getHoldTime());
wp->blockSignals(false);
} }
void WaypointView::setCurrent(bool state) void WaypointView::setCurrent(bool state)
......
...@@ -234,6 +234,9 @@ QProgressBar::chunk#thrustBar { ...@@ -234,6 +234,9 @@ QProgressBar::chunk#thrustBar {
<property name="toolTip"> <property name="toolTip">
<string>Position X coordinate</string> <string>Position X coordinate</string>
</property> </property>
<property name="wrapping">
<bool>false</bool>
</property>
<property name="prefix"> <property name="prefix">
<string>N </string> <string>N </string>
</property> </property>
......
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