QGCMAVLinkLogPlayer.cc 16.6 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
    currPacketCount(0),
Lorenz Meier's avatar
Lorenz Meier committed
25
    lastLogDirectory(QDesktopServices::storageLocation(QDesktopServices::DesktopLocation)),
26
    ui(new Ui::QGCMAVLinkLogPlayer)
27 28
{
    ui->setupUi(this);
29
    ui->horizontalLayout->setAlignment(Qt::AlignTop);
30

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

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

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

44 45
    setAccelerationFactorInt(49);
    ui->speedSlider->setValue(49);
46
    ui->positionSlider->setValue(ui->positionSlider->minimum());
Lorenz Meier's avatar
Lorenz Meier committed
47 48 49 50 51

    ui->playButton->setEnabled(false);
    ui->speedSlider->setEnabled(false);
    ui->positionSlider->setEnabled(false);

Lorenz Meier's avatar
Lorenz Meier committed
52
    loadSettings();
53 54 55 56
}

QGCMAVLinkLogPlayer::~QGCMAVLinkLogPlayer()
{
Lorenz Meier's avatar
Lorenz Meier committed
57
    storeSettings();
58 59 60
    delete ui;
}

lm's avatar
lm committed
61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84
void QGCMAVLinkLogPlayer::playPause(bool enabled)
{
    if (enabled)
    {
        play();
    }
    else
    {
        pause();
    }
}

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

85 86
void QGCMAVLinkLogPlayer::play()
{
lm's avatar
lm committed
87 88
    if (logFile.isOpen())
    {
89
        ui->selectFileButton->setEnabled(false);
lm's avatar
lm committed
90 91
        if (logLink)
        {
92 93
            logLink->disconnect();
            LinkManager::instance()->removeLink(logLink);
94 95 96 97 98
            delete logLink;
        }
        logLink = new MAVLinkSimulationLink("");

        // Start timer
lm's avatar
lm committed
99 100
        if (mavlinkLogFormat)
        {
101
            loopTimer.start(1);
lm's avatar
lm committed
102 103 104
        }
        else
        {
105 106 107 108 109 110
            // 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);
111
            loopTimer.start(interval*accelerationFactor);
112
        }
lm's avatar
lm committed
113
        isPlaying = true;
114
        ui->logStatsLabel->setText(tr("Started playing.."));
115
        ui->playButton->setIcon(QIcon(":files/images/actions/media-playback-pause.svg"));
lm's avatar
lm committed
116 117 118
    }
    else
    {
119 120 121 122 123 124 125 126 127 128 129 130 131
        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
132
    isPlaying = false;
133
    loopTimer.stop();
134
    ui->playButton->setIcon(QIcon(":files/images/actions/media-playback-start.svg"));
135
    ui->selectFileButton->setEnabled(true);
lm's avatar
lm committed
136 137
    if (logLink)
    {
138 139 140 141 142
        logLink->disconnect();
        LinkManager::instance()->removeLink(logLink);
        delete logLink;
        logLink = NULL;
    }
143 144
}

145
bool QGCMAVLinkLogPlayer::reset(int packetIndex)
146
{
147
    // Reset only for valid values
lm's avatar
lm committed
148 149 150
    const unsigned int packetSize = timeLen + packetLen;
    if (packetIndex >= 0 && packetIndex*packetSize <= logFile.size() - packetSize)
    {
151 152 153 154
        bool result = true;
        pause();
        loopCounter = 0;
        logFile.reset();
lm's avatar
lm committed
155 156 157

        if (!logFile.seek(packetIndex*packetSize))
        {
158 159 160 161 162 163
            // Fallback: Start from scratch
            logFile.reset();
            ui->logStatsLabel->setText(tr("Changing packet index failed, back to start."));
            result = false;
        }

164
        ui->playButton->setIcon(QIcon(":files/images/actions/media-playback-start.svg"));
165
        ui->positionSlider->blockSignals(true);
lm's avatar
lm committed
166
        int sliderVal = (packetIndex / (double)(logFile.size()/packetSize)) * (ui->positionSlider->maximum() - ui->positionSlider->minimum());
167 168 169 170
        ui->positionSlider->setValue(sliderVal);
        ui->positionSlider->blockSignals(false);
        startTime = 0;
        return result;
lm's avatar
lm committed
171 172 173
    }
    else
    {
174 175
        return false;
    }
176 177
}

Lorenz Meier's avatar
Lorenz Meier committed
178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204
void QGCMAVLinkLogPlayer::loadSettings()
{
    QSettings settings;
    settings.beginGroup("QGC_MAVLINKLOGPLAYER");
    lastLogDirectory = settings.value("LAST_LOG_DIRECTORY", lastLogDirectory).toString();
    settings.endGroup();
}

void QGCMAVLinkLogPlayer::storeSettings()
{
    QSettings settings;
    settings.beginGroup("QGC_MAVLINKLOGPLAYER");
    settings.setValue("LAST_LOG_DIRECTORY", lastLogDirectory);
    settings.endGroup();
    settings.sync();
}

/**
 * @brief Select a log file
 * @param startDirectory Directory where the file dialog will be opened
 * @return filename of the logFile
 */
bool QGCMAVLinkLogPlayer::selectLogFile()
{
    return selectLogFile(lastLogDirectory);
}

205
/**
Lorenz Meier's avatar
Lorenz Meier committed
206
 * @brief Select a log file
207 208 209 210
 * @param startDirectory Directory where the file dialog will be opened
 * @return filename of the logFile
 */
bool QGCMAVLinkLogPlayer::selectLogFile(const QString startDirectory)
211
{
212
    QString fileName = QFileDialog::getOpenFileName(this, tr("Specify MAVLink log file name to replay"), startDirectory, tr("MAVLink or Binary Logfile (*.mavlink *.bin *.log)"));
213

214 215 216 217 218 219
    if (fileName == "")
    {
        return false;
    }
    else
    {
Lorenz Meier's avatar
Lorenz Meier committed
220
        lastLogDirectory = fileName;
221 222
        return loadLogFile(fileName);
    }
223 224
}

225 226 227 228 229 230 231 232
/**
 * @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
233 234
    if (f < 0.0f)
    {
235
        accelerationFactor = 1.0f / (-f/2.0f);
lm's avatar
lm committed
236 237 238
    }
    else
    {
239 240 241
        accelerationFactor = 1+(f/2.0f);
    }

242
    // Update timer interval
lm's avatar
lm committed
243 244
    if (!mavlinkLogFormat)
    {
245 246 247 248 249 250 251 252 253 254
        // 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);
    }

255 256
    //qDebug() << "FACTOR:" << accelerationFactor;

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

260
bool QGCMAVLinkLogPlayer::loadLogFile(const QString& file)
261
{
Lorenz Meier's avatar
Lorenz Meier committed
262 263 264 265 266
    // Enable controls
    ui->playButton->setEnabled(true);
    ui->speedSlider->setEnabled(true);
    ui->positionSlider->setEnabled(true);

lm's avatar
lm committed
267
    // Check if logging is still enabled
lm's avatar
lm committed
268 269
    if (mavlink->loggingEnabled())
    {
lm's avatar
lm committed
270 271 272 273
        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."));
    }

274
    // Ensure that the playback process is stopped
lm's avatar
lm committed
275 276
    if (logFile.isOpen())
    {
277
        pause();
278 279
        logFile.close();
    }
280 281
    logFile.setFileName(file);

lm's avatar
lm committed
282 283
    if (!logFile.open(QFile::ReadOnly))
    {
284
        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));
285
        logFile.setFileName("");
286
        return false;
lm's avatar
lm committed
287 288 289
    }
    else
    {
290 291 292 293
        QFileInfo logFileInfo(file);
        logFile.reset();
        startTime = 0;
        ui->logFileNameLabel->setText(tr("%1").arg(logFileInfo.baseName()));
294

295 296 297
        // Select if binary or MAVLink log format is used
        mavlinkLogFormat = file.endsWith(".mavlink");

lm's avatar
lm committed
298 299
        if (mavlinkLogFormat)
        {
300 301
            // Get the time interval from the logfile
            QByteArray timestamp = logFile.read(timeLen);
302

303 304
            // First timestamp
            quint64 starttime = *((quint64*)(timestamp.constData()));
305

306 307 308 309 310 311
            // Last timestamp
            logFile.seek(logFile.size()-packetLen-timeLen);
            QByteArray timestamp2 = logFile.read(timeLen);
            quint64 endtime = *((quint64*)(timestamp2.constData()));
            // Reset everything
            logFile.reset();
312

313
            qDebug() << "Starttime:" << starttime << "End:" << endtime;
314

315 316 317 318 319 320
            // 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;
321

322
            QString timelabel = tr("%1h:%2m:%3s").arg(hours, 2).arg(minutes, 2).arg(seconds, 2);
323 324
            currPacketCount = logFileInfo.size()/(MAVLINK_MAX_PACKET_LEN+sizeof(quint64));
            ui->logStatsLabel->setText(tr("%2 MB, %3 packets, %4").arg(logFileInfo.size()/1000000.0f, 0, 'f', 2).arg(currPacketCount).arg(timelabel));
lm's avatar
lm committed
325 326 327
        }
        else
        {
328 329 330 331
            // Load in binary mode

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

lm's avatar
lm committed
333 334
            if (parts.count() > 1)
            {
335 336 337
                bool ok;
                int rate = parts.last().toInt(&ok);
                // 9600 baud to 100 MBit
lm's avatar
lm committed
338 339
                if (ok && (rate > 9600 && rate < 100000000))
                {
340 341 342 343 344 345 346 347 348 349 350 351
                    // 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);
352
            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));
353
        }
354 355 356 357

        // Reset current state
        reset(0);

358
        return true;
359
    }
360 361
}

362 363 364 365
/**
 * Jumps to the current percentage of the position slider
 */
void QGCMAVLinkLogPlayer::jumpToSliderVal(int slidervalue)
366
{
367
    loopTimer.stop();
368 369 370 371 372 373
    // 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
374 375 376 377
    if (reset(packetIndex))
    {
        if (mavlinkLogFormat)
        {
378
            ui->logStatsLabel->setText(tr("Jumped to packet %1").arg(packetIndex));
379
        }
380
    }
381
}
382

383 384 385 386 387 388 389 390
/**
 * 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.
 */
391
void QGCMAVLinkLogPlayer::logLoop()
392
{
lm's avatar
lm committed
393 394
    if (mavlinkLogFormat)
    {
395
        bool ok;
396

397
        // First check initialization
lm's avatar
lm committed
398 399
        if (startTime == 0)
        {
400
            QByteArray startBytes = logFile.read(timeLen);
401

402
            // Check if the correct number of bytes could be read
lm's avatar
lm committed
403 404
            if (startBytes.length() != timeLen)
            {
405 406 407 408 409
                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;
            }
410

411 412 413 414
            // Convert data to timestamp
            startTime = *((quint64*)(startBytes.constData()));
            currentStartTime = QGC::groundTimeUsecs();
            ok = true;
415

416
            //qDebug() << "START TIME: " << startTime;
417

418
            // Check if these bytes could be correctly decoded
419
            // TODO
lm's avatar
lm committed
420 421
            if (!ok)
            {
422 423 424 425 426 427
                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;
            }
        }
428 429


430
        // Initialization seems fine, load next chunk
431
        //this is ok because before we already read the timestamp of this paket before
432
        QByteArray chunk = logFile.read(timeLen+packetLen);
433
        QByteArray packet = chunk.left(packetLen);
434

435 436
        // Emit this packet
        emit bytesReady(logLink, packet);
437

438
        // Check if reached end of file before reading next timestamp
439
        if (chunk.length() < (timeLen + packetLen) || logFile.atEnd())
lm's avatar
lm committed
440
        {
441 442
            // Reached end of file
            reset();
443

444 445 446 447 448
            QString status = tr("Reached end of MAVLink log file.");
            ui->logStatsLabel->setText(status);
            MainWindow::instance()->showStatusMessage(status);
            return;
        }
449

450
        // End of file not reached, read next timestamp
451
        // which is located after current packet
452
        QByteArray rawTime = chunk.mid(packetLen);
453

454 455 456
        // This is the timestamp of the next packet
        quint64 time = *((quint64*)(rawTime.constData()));
        ok = true;
lm's avatar
lm committed
457 458
        if (!ok)
        {
459 460 461 462
            // 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
463 464 465
        }
        else
        {
466 467 468
            // Normal processing, passed all checks
            // start timer to match time offset between
            // this and next packet
469 470


471 472
            // Offset in ms
            qint64 timediff = (time - startTime)/accelerationFactor;
473

474 475
            // Immediately load any data within
            // a 3 ms interval
476

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

479
            //qDebug() << "nextExecutionTime:" << nextExecutionTime << "QGC START TIME:" << currentStartTime << "LOG START TIME:" << startTime;
480

lm's avatar
lm committed
481 482
            if (nextExecutionTime < 2)
            {
483
                logLoop();
lm's avatar
lm committed
484 485 486
            }
            else
            {
487 488
                loopTimer.start(nextExecutionTime);
            }
489
        }
lm's avatar
lm committed
490 491 492
    }
    else
    {
493 494 495 496 497 498 499 500
        // 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
501 502
        if (chunk.length() < len || logFile.atEnd())
        {
503 504 505 506 507 508 509 510
            // Reached end of file
            reset();

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

515 516
    // Update status label
    // Update progress bar
517
    if (loopCounter % 40 == 0 || currPacketCount < 500)
lm's avatar
lm committed
518
    {
519 520 521 522 523 524
        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);
525
    }
526
    loopCounter++;
527
}
528 529 530 531

void QGCMAVLinkLogPlayer::changeEvent(QEvent *e)
{
    QWidget::changeEvent(e);
lm's avatar
lm committed
532 533
    switch (e->type())
    {
534 535 536 537 538 539 540
    case QEvent::LanguageChange:
        ui->retranslateUi(this);
        break;
    default:
        break;
    }
}