QGCMAVLinkLogPlayer.cc 16.3 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
    loadSettings();
48 49 50 51
}

QGCMAVLinkLogPlayer::~QGCMAVLinkLogPlayer()
{
Lorenz Meier's avatar
Lorenz Meier committed
52
    storeSettings();
53 54 55
    delete ui;
}

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

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

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

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

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

        if (!logFile.seek(packetIndex*packetSize))
        {
153 154 155 156 157 158
            // Fallback: Start from scratch
            logFile.reset();
            ui->logStatsLabel->setText(tr("Changing packet index failed, back to start."));
            result = false;
        }

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

Lorenz Meier's avatar
Lorenz Meier committed
173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199
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);
}

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

209 210 211 212 213 214
    if (fileName == "")
    {
        return false;
    }
    else
    {
Lorenz Meier's avatar
Lorenz Meier committed
215
        lastLogDirectory = fileName;
216 217
        return loadLogFile(fileName);
    }
218 219
}

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

237
    // Update timer interval
lm's avatar
lm committed
238 239
    if (!mavlinkLogFormat)
    {
240 241 242 243 244 245 246 247 248 249
        // 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);
    }

250 251
    //qDebug() << "FACTOR:" << accelerationFactor;

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

255
bool QGCMAVLinkLogPlayer::loadLogFile(const QString& file)
256
{
lm's avatar
lm committed
257
    // Check if logging is still enabled
lm's avatar
lm committed
258 259
    if (mavlink->loggingEnabled())
    {
lm's avatar
lm committed
260 261 262 263
        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."));
    }

264
    // Ensure that the playback process is stopped
lm's avatar
lm committed
265 266
    if (logFile.isOpen())
    {
267
        pause();
268 269
        logFile.close();
    }
270 271
    logFile.setFileName(file);

lm's avatar
lm committed
272 273
    if (!logFile.open(QFile::ReadOnly))
    {
274
        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));
275
        logFile.setFileName("");
276
        return false;
lm's avatar
lm committed
277 278 279
    }
    else
    {
280 281 282 283
        QFileInfo logFileInfo(file);
        logFile.reset();
        startTime = 0;
        ui->logFileNameLabel->setText(tr("%1").arg(logFileInfo.baseName()));
284

285 286 287
        // Select if binary or MAVLink log format is used
        mavlinkLogFormat = file.endsWith(".mavlink");

lm's avatar
lm committed
288 289
        if (mavlinkLogFormat)
        {
290 291
            // Get the time interval from the logfile
            QByteArray timestamp = logFile.read(timeLen);
292

293 294
            // First timestamp
            quint64 starttime = *((quint64*)(timestamp.constData()));
295

296 297 298 299 300 301
            // Last timestamp
            logFile.seek(logFile.size()-packetLen-timeLen);
            QByteArray timestamp2 = logFile.read(timeLen);
            quint64 endtime = *((quint64*)(timestamp2.constData()));
            // Reset everything
            logFile.reset();
302

303
            qDebug() << "Starttime:" << starttime << "End:" << endtime;
304

305 306 307 308 309 310
            // 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;
311

312
            QString timelabel = tr("%1h:%2m:%3s").arg(hours, 2).arg(minutes, 2).arg(seconds, 2);
313 314
            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
315 316 317
        }
        else
        {
318 319 320 321
            // Load in binary mode

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

lm's avatar
lm committed
323 324
            if (parts.count() > 1)
            {
325 326 327
                bool ok;
                int rate = parts.last().toInt(&ok);
                // 9600 baud to 100 MBit
lm's avatar
lm committed
328 329
                if (ok && (rate > 9600 && rate < 100000000))
                {
330 331 332 333 334 335 336 337 338 339 340 341
                    // 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);
342
            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));
343
        }
344 345 346 347

        // Reset current state
        reset(0);

348
        return true;
349
    }
350 351
}

352 353 354 355
/**
 * Jumps to the current percentage of the position slider
 */
void QGCMAVLinkLogPlayer::jumpToSliderVal(int slidervalue)
356
{
357
    loopTimer.stop();
358 359 360 361 362 363
    // 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
364 365 366 367
    if (reset(packetIndex))
    {
        if (mavlinkLogFormat)
        {
368
            ui->logStatsLabel->setText(tr("Jumped to packet %1").arg(packetIndex));
369
        }
370
    }
371
}
372

373 374 375 376 377 378 379 380
/**
 * 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.
 */
381
void QGCMAVLinkLogPlayer::logLoop()
382
{
lm's avatar
lm committed
383 384
    if (mavlinkLogFormat)
    {
385
        bool ok;
386

387
        // First check initialization
lm's avatar
lm committed
388 389
        if (startTime == 0)
        {
390
            QByteArray startBytes = logFile.read(timeLen);
391

392
            // Check if the correct number of bytes could be read
lm's avatar
lm committed
393 394
            if (startBytes.length() != timeLen)
            {
395 396 397 398 399
                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;
            }
400

401 402 403 404
            // Convert data to timestamp
            startTime = *((quint64*)(startBytes.constData()));
            currentStartTime = QGC::groundTimeUsecs();
            ok = true;
405

406
            //qDebug() << "START TIME: " << startTime;
407

408
            // Check if these bytes could be correctly decoded
409
            // TODO
lm's avatar
lm committed
410 411
            if (!ok)
            {
412 413 414 415 416 417
                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;
            }
        }
418 419


420
        // Initialization seems fine, load next chunk
421
        //this is ok because before we already read the timestamp of this paket before
422
        QByteArray chunk = logFile.read(timeLen+packetLen);
423
        QByteArray packet = chunk.left(packetLen);
424

425 426
        // Emit this packet
        emit bytesReady(logLink, packet);
427

428
        // Check if reached end of file before reading next timestamp
429
        if (chunk.length() < (timeLen + packetLen) || logFile.atEnd())
lm's avatar
lm committed
430
        {
431 432
            // Reached end of file
            reset();
433

434 435 436 437 438
            QString status = tr("Reached end of MAVLink log file.");
            ui->logStatsLabel->setText(status);
            MainWindow::instance()->showStatusMessage(status);
            return;
        }
439

440
        // End of file not reached, read next timestamp
441
        // which is located after current packet
442
        QByteArray rawTime = chunk.mid(packetLen);
443

444 445 446
        // This is the timestamp of the next packet
        quint64 time = *((quint64*)(rawTime.constData()));
        ok = true;
lm's avatar
lm committed
447 448
        if (!ok)
        {
449 450 451 452
            // 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
453 454 455
        }
        else
        {
456 457 458
            // Normal processing, passed all checks
            // start timer to match time offset between
            // this and next packet
459 460


461 462
            // Offset in ms
            qint64 timediff = (time - startTime)/accelerationFactor;
463

464 465
            // Immediately load any data within
            // a 3 ms interval
466

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

469
            //qDebug() << "nextExecutionTime:" << nextExecutionTime << "QGC START TIME:" << currentStartTime << "LOG START TIME:" << startTime;
470

lm's avatar
lm committed
471 472
            if (nextExecutionTime < 2)
            {
473
                logLoop();
lm's avatar
lm committed
474 475 476
            }
            else
            {
477 478
                loopTimer.start(nextExecutionTime);
            }
479
        }
lm's avatar
lm committed
480 481 482
    }
    else
    {
483 484 485 486 487 488 489 490
        // 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
491 492
        if (chunk.length() < len || logFile.atEnd())
        {
493 494 495 496 497 498 499 500
            // Reached end of file
            reset();

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

505 506
    // Update status label
    // Update progress bar
507
    if (loopCounter % 40 == 0 || currPacketCount < 500)
lm's avatar
lm committed
508
    {
509 510 511 512 513 514
        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);
515
    }
516
    loopCounter++;
517
}
518 519 520 521

void QGCMAVLinkLogPlayer::changeEvent(QEvent *e)
{
    QWidget::changeEvent(e);
lm's avatar
lm committed
522 523
    switch (e->type())
    {
524 525 526 527 528 529 530
    case QEvent::LanguageChange:
        ui->retranslateUi(this);
        break;
    default:
        break;
    }
}