QGCMAVLinkLogPlayer.cc 15 KB
Newer Older
1 2 3 4
#include <QFileDialog>
#include <QMessageBox>
#include <QDesktopServices>

5
#include "MainWindow.h"
6
#include "QGCMAVLinkLogPlayer.h"
7
#include "QGC.h"
8 9 10
#include "ui_QGCMAVLinkLogPlayer.h"

QGCMAVLinkLogPlayer::QGCMAVLinkLogPlayer(MAVLinkProtocol* mavlink, QWidget *parent) :
11 12 13 14 15 16 17 18 19 20 21 22
    QWidget(parent),
    lineCounter(0),
    totalLines(0),
    startTime(0),
    endTime(0),
    currentStartTime(0),
    accelerationFactor(1.0f),
    mavlink(mavlink),
    logLink(NULL),
    loopCounter(0),
    mavlinkLogFormat(true),
    binaryBaudRate(57600),
lm's avatar
lm committed
23
    isPlaying(false),
24
    ui(new Ui::QGCMAVLinkLogPlayer)
25 26 27 28
{
    ui->setupUi(this);
    ui->gridLayout->setAlignment(Qt::AlignTop);

29 30 31
    // Connect protocol
    connect(this, SIGNAL(bytesReady(LinkInterface*,QByteArray)), mavlink, SLOT(receiveBytes(LinkInterface*,QByteArray)));

32 33 34
    // Setup timer
    connect(&loopTimer, SIGNAL(timeout()), this, SLOT(logLoop()));

35 36
    // Setup buttons
    connect(ui->selectFileButton, SIGNAL(clicked()), this, SLOT(selectLogFile()));
lm's avatar
lm committed
37
    connect(ui->playButton, SIGNAL(clicked()), this, SLOT(playPauseToggle()));
38
    connect(ui->speedSlider, SIGNAL(valueChanged(int)), this, SLOT(setAccelerationFactorInt(int)));
39 40
    connect(ui->positionSlider, SIGNAL(valueChanged(int)), this, SLOT(jumpToSliderVal(int)));
    connect(ui->positionSlider, SIGNAL(sliderPressed()), this, SLOT(pause()));
41

42 43
    setAccelerationFactorInt(49);
    ui->speedSlider->setValue(49);
44
    ui->positionSlider->setValue(ui->positionSlider->minimum());
45 46 47 48 49 50 51
}

QGCMAVLinkLogPlayer::~QGCMAVLinkLogPlayer()
{
    delete ui;
}

lm's avatar
lm committed
52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75
void QGCMAVLinkLogPlayer::playPause(bool enabled)
{
    if (enabled)
    {
        play();
    }
    else
    {
        pause();
    }
}

void QGCMAVLinkLogPlayer::playPauseToggle()
{
    if (isPlaying)
    {
        pause();
    }
    else
    {
        play();
    }
}

76 77
void QGCMAVLinkLogPlayer::play()
{
lm's avatar
lm committed
78 79
    if (logFile.isOpen())
    {
80
        ui->selectFileButton->setEnabled(false);
lm's avatar
lm committed
81 82
        if (logLink)
        {
83 84
            logLink->disconnect();
            LinkManager::instance()->removeLink(logLink);
85 86 87 88 89
            delete logLink;
        }
        logLink = new MAVLinkSimulationLink("");

        // Start timer
lm's avatar
lm committed
90 91
        if (mavlinkLogFormat)
        {
92
            loopTimer.start(1);
lm's avatar
lm committed
93 94 95
        }
        else
        {
96 97 98 99 100 101
            // 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);
102
            loopTimer.start(interval*accelerationFactor);
103
        }
lm's avatar
lm committed
104 105 106 107 108
        isPlaying = true;
        ui->playButton->setIcon(QIcon(":images/actions/media-playback-pause.svg"));
    }
    else
    {
109 110 111 112 113 114 115 116 117 118 119 120 121
        ui->playButton->setChecked(false);
        QMessageBox msgBox;
        msgBox.setIcon(QMessageBox::Information);
        msgBox.setText(tr("No logfile selected"));
        msgBox.setInformativeText(tr("Please select first a MAVLink log file before playing it."));
        msgBox.setStandardButtons(QMessageBox::Ok);
        msgBox.setDefaultButton(QMessageBox::Ok);
        msgBox.exec();
    }
}

void QGCMAVLinkLogPlayer::pause()
{
lm's avatar
lm committed
122
    isPlaying = false;
123
    loopTimer.stop();
lm's avatar
lm committed
124
    ui->playButton->setIcon(QIcon(":images/actions/media-playback-start.svg"));
125
    ui->selectFileButton->setEnabled(true);
lm's avatar
lm committed
126 127
    if (logLink)
    {
128 129 130 131 132
        logLink->disconnect();
        LinkManager::instance()->removeLink(logLink);
        delete logLink;
        logLink = NULL;
    }
133 134
}

135
bool QGCMAVLinkLogPlayer::reset(int packetIndex)
136
{
137
    // Reset only for valid values
lm's avatar
lm committed
138 139 140
    const unsigned int packetSize = timeLen + packetLen;
    if (packetIndex >= 0 && packetIndex*packetSize <= logFile.size() - packetSize)
    {
141 142 143 144
        bool result = true;
        pause();
        loopCounter = 0;
        logFile.reset();
lm's avatar
lm committed
145 146 147

        if (!logFile.seek(packetIndex*packetSize))
        {
148 149 150 151 152 153
            // Fallback: Start from scratch
            logFile.reset();
            ui->logStatsLabel->setText(tr("Changing packet index failed, back to start."));
            result = false;
        }

lm's avatar
lm committed
154
        ui->playButton->setIcon(QIcon(":images/actions/media-playback-start.svg"));
155
        ui->positionSlider->blockSignals(true);
lm's avatar
lm committed
156
        int sliderVal = (packetIndex / (double)(logFile.size()/packetSize)) * (ui->positionSlider->maximum() - ui->positionSlider->minimum());
157 158 159 160
        ui->positionSlider->setValue(sliderVal);
        ui->positionSlider->blockSignals(false);
        startTime = 0;
        return result;
lm's avatar
lm committed
161 162 163
    }
    else
    {
164 165
        return false;
    }
166 167
}

168
bool QGCMAVLinkLogPlayer::selectLogFile()
169
{
170
    QString fileName = QFileDialog::getOpenFileName(this, tr("Specify MAVLink log file name to replay"), QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), tr("MAVLink or Binary Logfile (*.mavlink *.bin *.log)"));
171

172 173 174 175 176 177 178 179
    if (fileName == "")
    {
        return false;
    }
    else
    {
        return loadLogFile(fileName);
    }
180 181
}

182 183 184 185 186 187 188 189
/**
 * @param factor 0: 0.01X, 50: 1.0X, 100: 100.0X
 */
void QGCMAVLinkLogPlayer::setAccelerationFactorInt(int factor)
{
    float f = factor+1.0f;
    f -= 50.0f;

lm's avatar
lm committed
190 191
    if (f < 0.0f)
    {
192
        accelerationFactor = 1.0f / (-f/2.0f);
lm's avatar
lm committed
193 194 195
    }
    else
    {
196 197 198
        accelerationFactor = 1+(f/2.0f);
    }

199
    // Update timer interval
lm's avatar
lm committed
200 201
    if (!mavlinkLogFormat)
    {
202 203 204 205 206 207 208 209 210 211
        // 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.stop();
        loopTimer.start(interval/accelerationFactor);
    }

212 213
    //qDebug() << "FACTOR:" << accelerationFactor;

214
    ui->speedLabel->setText(tr("Speed: %1X").arg(accelerationFactor, 5, 'f', 2, '0'));
215 216
}

217
bool QGCMAVLinkLogPlayer::loadLogFile(const QString& file)
218
{
lm's avatar
lm committed
219
    // Check if logging is still enabled
lm's avatar
lm committed
220 221
    if (mavlink->loggingEnabled())
    {
lm's avatar
lm committed
222 223 224 225
        mavlink->enableLogging(false);
        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."));
    }

226
    // Ensure that the playback process is stopped
lm's avatar
lm committed
227 228
    if (logFile.isOpen())
    {
229
        pause();
230 231
        logFile.close();
    }
232 233
    logFile.setFileName(file);

lm's avatar
lm committed
234 235
    if (!logFile.open(QFile::ReadOnly))
    {
236
        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));
237
        logFile.setFileName("");
238
        return false;
lm's avatar
lm committed
239 240 241
    }
    else
    {
242 243 244 245
        QFileInfo logFileInfo(file);
        logFile.reset();
        startTime = 0;
        ui->logFileNameLabel->setText(tr("%1").arg(logFileInfo.baseName()));
246

247 248 249
        // Select if binary or MAVLink log format is used
        mavlinkLogFormat = file.endsWith(".mavlink");

lm's avatar
lm committed
250 251
        if (mavlinkLogFormat)
        {
252 253
            // Get the time interval from the logfile
            QByteArray timestamp = logFile.read(timeLen);
254

255 256
            // First timestamp
            quint64 starttime = *((quint64*)(timestamp.constData()));
257

258 259 260 261 262 263
            // Last timestamp
            logFile.seek(logFile.size()-packetLen-timeLen);
            QByteArray timestamp2 = logFile.read(timeLen);
            quint64 endtime = *((quint64*)(timestamp2.constData()));
            // Reset everything
            logFile.reset();
264

265
            qDebug() << "Starttime:" << starttime << "End:" << endtime;
266

267 268 269 270 271 272
            // WARNING: Order matters in this computation
            int seconds = (endtime - starttime)/1000000;
            int minutes = seconds / 60;
            int hours = minutes / 60;
            seconds -= 60*minutes;
            minutes -= 60*hours;
273

274 275
            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));
lm's avatar
lm committed
276 277 278
        }
        else
        {
279 280 281 282
            // Load in binary mode

            // Set baud rate if any present
            QStringList parts = logFileInfo.baseName().split("_");
283

lm's avatar
lm committed
284 285
            if (parts.count() > 1)
            {
286 287 288
                bool ok;
                int rate = parts.last().toInt(&ok);
                // 9600 baud to 100 MBit
lm's avatar
lm committed
289 290
                if (ok && (rate > 9600 && rate < 100000000))
                {
291 292 293 294 295 296 297 298 299 300 301 302
                    // 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);
303
            ui->logStatsLabel->setText(tr("%2 MB, %4 at %5 KB/s").arg(logFileInfo.size()/1000000.0f, 0, 'f', 2).arg(timelabel).arg(binaryBaudRate/10.0f/1024.0f, 0, 'f', 2));
304
        }
305
        return true;
306
    }
307 308
}

309 310 311 312
/**
 * Jumps to the current percentage of the position slider
 */
void QGCMAVLinkLogPlayer::jumpToSliderVal(int slidervalue)
313
{
314
    loopTimer.stop();
315 316 317 318 319 320
    // Set the logfile to the correct percentage and
    // align to the timestamp values
    int packetCount = logFile.size() / (packetLen + timeLen);
    int packetIndex = (packetCount - 1) * (slidervalue / (double)(ui->positionSlider->maximum() - ui->positionSlider->minimum()));

    // Do only accept valid jumps
lm's avatar
lm committed
321 322 323 324
    if (reset(packetIndex))
    {
        if (mavlinkLogFormat)
        {
325
            ui->logStatsLabel->setText(tr("Jumped to packet %1").arg(packetIndex));
326
        }
327
    }
328
}
329

330 331 332 333 334 335 336 337
/**
 * This function is the "mainloop" of the log player, reading one line
 * and adjusting the mainloop timer to read the next line in time.
 * It might not perfectly match the timing of the log file,
 * but it will never induce a static drift into the log file replay.
 * For scientific logging, the use of onboard timestamps and the log
 * functionality of the line chart plot is recommended.
 */
338
void QGCMAVLinkLogPlayer::logLoop()
339
{
lm's avatar
lm committed
340 341
    if (mavlinkLogFormat)
    {
342
        bool ok;
343

344
        // First check initialization
lm's avatar
lm committed
345 346
        if (startTime == 0)
        {
347
            QByteArray startBytes = logFile.read(timeLen);
348

349
            // Check if the correct number of bytes could be read
lm's avatar
lm committed
350 351
            if (startBytes.length() != timeLen)
            {
352 353 354 355 356
                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;
            }
357

358 359 360 361
            // Convert data to timestamp
            startTime = *((quint64*)(startBytes.constData()));
            currentStartTime = QGC::groundTimeUsecs();
            ok = true;
362

363
            //qDebug() << "START TIME: " << startTime;
364

365
            // Check if these bytes could be correctly decoded
lm's avatar
lm committed
366 367
            if (!ok)
            {
368 369 370 371 372 373
                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();
                return;
            }
        }
374 375


376 377 378
        // Initialization seems fine, load next chunk
        QByteArray chunk = logFile.read(timeLen+packetLen);
        QByteArray packet = chunk.mid(0, packetLen);
379

380 381
        // Emit this packet
        emit bytesReady(logLink, packet);
382

383
        // Check if reached end of file before reading next timestamp
lm's avatar
lm committed
384 385
        if (chunk.length() < timeLen+packetLen || logFile.atEnd())
        {
386 387
            // Reached end of file
            reset();
388

389 390 391 392 393
            QString status = tr("Reached end of MAVLink log file.");
            ui->logStatsLabel->setText(status);
            MainWindow::instance()->showStatusMessage(status);
            return;
        }
394

395 396
        // End of file not reached, read next timestamp
        QByteArray rawTime = chunk.mid(packetLen);
397

398 399 400
        // This is the timestamp of the next packet
        quint64 time = *((quint64*)(rawTime.constData()));
        ok = true;
lm's avatar
lm committed
401 402
        if (!ok)
        {
403 404 405 406
            // Convert it to 64bit number
            QString status = tr("Time conversion error during log replay. Continuing..");
            ui->logStatsLabel->setText(status);
            MainWindow::instance()->showStatusMessage(status);
lm's avatar
lm committed
407 408 409
        }
        else
        {
410 411 412
            // Normal processing, passed all checks
            // start timer to match time offset between
            // this and next packet
413 414


415 416
            // Offset in ms
            qint64 timediff = (time - startTime)/accelerationFactor;
417

418 419
            // Immediately load any data within
            // a 3 ms interval
420

421
            int nextExecutionTime = (((qint64)currentStartTime + (qint64)timediff) - (qint64)QGC::groundTimeUsecs())/1000;
422

423
            //qDebug() << "nextExecutionTime:" << nextExecutionTime << "QGC START TIME:" << currentStartTime << "LOG START TIME:" << startTime;
424

lm's avatar
lm committed
425 426
            if (nextExecutionTime < 2)
            {
427
                logLoop();
lm's avatar
lm committed
428 429 430
            }
            else
            {
431 432
                loopTimer.start(nextExecutionTime);
            }
433
        }
lm's avatar
lm committed
434 435 436
    }
    else
    {
437 438 439 440 441 442 443 444
        // 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
lm's avatar
lm committed
445 446
        if (chunk.length() < len || logFile.atEnd())
        {
447 448 449 450 451 452 453 454
            // Reached end of file
            reset();

            QString status = tr("Reached end of binary log file.");
            ui->logStatsLabel->setText(status);
            MainWindow::instance()->showStatusMessage(status);
            return;
        }
455 456 457
    }
    // Ui update: Only every 20 messages
    // to prevent flickering and high CPU load
458

459 460
    // Update status label
    // Update progress bar
lm's avatar
lm committed
461 462
    if (loopCounter % 40 == 0)
    {
463 464 465 466 467 468
        QFileInfo logFileInfo(logFile);
        int progress = (ui->positionSlider->maximum()-ui->positionSlider->minimum())*(logFile.pos()/static_cast<float>(logFileInfo.size()));
        //qDebug() << "Progress:" << progress;
        ui->positionSlider->blockSignals(true);
        ui->positionSlider->setValue(progress);
        ui->positionSlider->blockSignals(false);
469
    }
470
    loopCounter++;
471
}
472 473 474 475

void QGCMAVLinkLogPlayer::changeEvent(QEvent *e)
{
    QWidget::changeEvent(e);
lm's avatar
lm committed
476 477
    switch (e->type())
    {
478 479 480 481 482 483 484
    case QEvent::LanguageChange:
        ui->retranslateUi(this);
        break;
    default:
        break;
    }
}