QGCMAVLinkLogPlayer.cc 16.8 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

    ui->playButton->setEnabled(false);
    ui->speedSlider->setEnabled(false);
    ui->positionSlider->setEnabled(false);
51 52 53
    ui->speedLabel->setEnabled(false);
    ui->logFileNameLabel->setEnabled(false);
    ui->logStatsLabel->setEnabled(false);
Lorenz Meier's avatar
Lorenz Meier committed
54

Lorenz Meier's avatar
Lorenz Meier committed
55
    loadSettings();
56 57 58 59
}

QGCMAVLinkLogPlayer::~QGCMAVLinkLogPlayer()
{
Lorenz Meier's avatar
Lorenz Meier committed
60
    storeSettings();
61 62 63
    delete ui;
}

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

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

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

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

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

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

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

Lorenz Meier's avatar
Lorenz Meier committed
181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207
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);
}

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

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

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

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

258 259
    //qDebug() << "FACTOR:" << accelerationFactor;

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

263
bool QGCMAVLinkLogPlayer::loadLogFile(const QString& file)
264
{
Lorenz Meier's avatar
Lorenz Meier committed
265 266 267 268
    // Enable controls
    ui->playButton->setEnabled(true);
    ui->speedSlider->setEnabled(true);
    ui->positionSlider->setEnabled(true);
269 270 271
    ui->speedLabel->setEnabled(true);
    ui->logFileNameLabel->setEnabled(true);
    ui->logStatsLabel->setEnabled(true);
Lorenz Meier's avatar
Lorenz Meier committed
272

lm's avatar
lm committed
273
    // Check if logging is still enabled
lm's avatar
lm committed
274 275
    if (mavlink->loggingEnabled())
    {
lm's avatar
lm committed
276 277 278 279
        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."));
    }

280
    // Ensure that the playback process is stopped
lm's avatar
lm committed
281 282
    if (logFile.isOpen())
    {
283
        pause();
284 285
        logFile.close();
    }
286 287
    logFile.setFileName(file);

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

301 302 303
        // Select if binary or MAVLink log format is used
        mavlinkLogFormat = file.endsWith(".mavlink");

lm's avatar
lm committed
304 305
        if (mavlinkLogFormat)
        {
306 307
            // Get the time interval from the logfile
            QByteArray timestamp = logFile.read(timeLen);
308

309 310
            // First timestamp
            quint64 starttime = *((quint64*)(timestamp.constData()));
311

312 313 314 315 316 317
            // Last timestamp
            logFile.seek(logFile.size()-packetLen-timeLen);
            QByteArray timestamp2 = logFile.read(timeLen);
            quint64 endtime = *((quint64*)(timestamp2.constData()));
            // Reset everything
            logFile.reset();
318

319
            qDebug() << "Starttime:" << starttime << "End:" << endtime;
320

321 322 323 324 325 326
            // 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;
327

328
            QString timelabel = tr("%1h:%2m:%3s").arg(hours, 2).arg(minutes, 2).arg(seconds, 2);
329 330
            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
331 332 333
        }
        else
        {
334 335 336 337
            // Load in binary mode

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

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

        // Reset current state
        reset(0);

364
        return true;
365
    }
366 367
}

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

389 390 391 392 393 394 395 396
/**
 * 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.
 */
397
void QGCMAVLinkLogPlayer::logLoop()
398
{
lm's avatar
lm committed
399 400
    if (mavlinkLogFormat)
    {
401
        bool ok;
402

403
        // First check initialization
lm's avatar
lm committed
404 405
        if (startTime == 0)
        {
406
            QByteArray startBytes = logFile.read(timeLen);
407

408
            // Check if the correct number of bytes could be read
lm's avatar
lm committed
409 410
            if (startBytes.length() != timeLen)
            {
411 412 413 414 415
                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;
            }
416

417 418 419 420
            // Convert data to timestamp
            startTime = *((quint64*)(startBytes.constData()));
            currentStartTime = QGC::groundTimeUsecs();
            ok = true;
421

422
            //qDebug() << "START TIME: " << startTime;
423

424
            // Check if these bytes could be correctly decoded
425
            // TODO
lm's avatar
lm committed
426 427
            if (!ok)
            {
428 429 430 431 432 433
                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;
            }
        }
434 435


436
        // Initialization seems fine, load next chunk
437
        //this is ok because before we already read the timestamp of this paket before
438
        QByteArray chunk = logFile.read(timeLen+packetLen);
439
        QByteArray packet = chunk.left(packetLen);
440

441 442
        // Emit this packet
        emit bytesReady(logLink, packet);
443

444
        // Check if reached end of file before reading next timestamp
445
        if (chunk.length() < (timeLen + packetLen) || logFile.atEnd())
lm's avatar
lm committed
446
        {
447 448
            // Reached end of file
            reset();
449

450 451 452 453 454
            QString status = tr("Reached end of MAVLink log file.");
            ui->logStatsLabel->setText(status);
            MainWindow::instance()->showStatusMessage(status);
            return;
        }
455

456
        // End of file not reached, read next timestamp
457
        // which is located after current packet
458
        QByteArray rawTime = chunk.mid(packetLen);
459

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


477 478
            // Offset in ms
            qint64 timediff = (time - startTime)/accelerationFactor;
479

480 481
            // Immediately load any data within
            // a 3 ms interval
482

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

485
            //qDebug() << "nextExecutionTime:" << nextExecutionTime << "QGC START TIME:" << currentStartTime << "LOG START TIME:" << startTime;
486

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

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

521 522
    // Update status label
    // Update progress bar
523
    if (loopCounter % 40 == 0 || currPacketCount < 500)
lm's avatar
lm committed
524
    {
525 526 527 528 529 530
        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);
531
    }
532
    loopCounter++;
533
}
534 535 536 537

void QGCMAVLinkLogPlayer::changeEvent(QEvent *e)
{
    QWidget::changeEvent(e);
lm's avatar
lm committed
538 539
    switch (e->type())
    {
540 541 542 543 544 545 546
    case QEvent::LanguageChange:
        ui->retranslateUi(this);
        break;
    default:
        break;
    }
}