LogReplayLink.cc 18.7 KB
Newer Older
1 2 3 4 5 6 7 8
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/
Don Gagne's avatar
Don Gagne committed
9 10 11 12


#include "LogReplayLink.h"
#include "LinkManager.h"
13
#include "QGCApplication.h"
Don Gagne's avatar
Don Gagne committed
14 15

#include <QFileInfo>
DonLakeFlyer's avatar
DonLakeFlyer committed
16
#include <QtEndian>
17
#include <QSignalSpy>
Don Gagne's avatar
Don Gagne committed
18 19 20

const char*  LogReplayLinkConfiguration::_logFilenameKey = "logFilename";

21
LogReplayLinkConfiguration::LogReplayLinkConfiguration(const QString& name)
22
    : LinkConfiguration(name)
Don Gagne's avatar
Don Gagne committed
23 24 25 26
{
    
}

27
LogReplayLinkConfiguration::LogReplayLinkConfiguration(LogReplayLinkConfiguration* copy)
28
    : LinkConfiguration(copy)
Don Gagne's avatar
Don Gagne committed
29 30 31 32 33 34 35 36
{
    _logFilename = copy->logFilename();
}

void LogReplayLinkConfiguration::copyFrom(LinkConfiguration *source)
{
    LinkConfiguration::copyFrom(source);
    LogReplayLinkConfiguration* ssource = dynamic_cast<LogReplayLinkConfiguration*>(source);
DonLakeFlyer's avatar
DonLakeFlyer committed
37 38 39 40 41
    if (ssource) {
        _logFilename = ssource->logFilename();
    } else {
        qWarning() << "Internal error";
    }
Don Gagne's avatar
Don Gagne committed
42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68
}

void LogReplayLinkConfiguration::saveSettings(QSettings& settings, const QString& root)
{
    settings.beginGroup(root);
    settings.setValue(_logFilenameKey, _logFilename);
    settings.endGroup();
}

void LogReplayLinkConfiguration::loadSettings(QSettings& settings, const QString& root)
{
    settings.beginGroup(root);
    _logFilename = settings.value(_logFilenameKey, "").toString();
    settings.endGroup();
}

void LogReplayLinkConfiguration::updateSettings(void)
{
    // Doesn't support changing filename on the fly is already connected
}

QString LogReplayLinkConfiguration::logFilenameShort(void)
{
    QFileInfo fi(_logFilename);
    return fi.fileName();
}

69
LogReplayLink::LogReplayLink(SharedLinkConfigurationPointer& config)
70 71 72 73
    : LinkInterface     (config)
    , _logReplayConfig  (qobject_cast<LogReplayLinkConfiguration*>(config.data()))
    , _connected        (false)
    , _playbackSpeed    (1)
Don Gagne's avatar
Don Gagne committed
74
{
DonLakeFlyer's avatar
DonLakeFlyer committed
75 76 77
    if (!_logReplayConfig) {
        qWarning() << "Internal error";
    }
78 79

    _errorTitle = tr("Log Replay Error");
Don Gagne's avatar
Don Gagne committed
80 81 82
    
    _readTickTimer.moveToThread(this);
    
83 84 85 86
    QObject::connect(&_readTickTimer, &QTimer::timeout,                 this, &LogReplayLink::_readNextLogEntry);
    QObject::connect(this, &LogReplayLink::_playOnThread,               this, &LogReplayLink::_play);
    QObject::connect(this, &LogReplayLink::_pauseOnThread,              this, &LogReplayLink::_pause);
    QObject::connect(this, &LogReplayLink::_setPlaybackSpeedOnThread,   this, &LogReplayLink::_setPlaybackSpeed);
Don Gagne's avatar
Don Gagne committed
87 88 89 90 91 92 93 94 95 96 97 98
    
    moveToThread(this);
}

LogReplayLink::~LogReplayLink(void)
{
    _disconnect();
}

bool LogReplayLink::_connect(void)
{
    // Disallow replay when any links are connected
99
    if (qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()) {
100
        emit communicationError(_errorTitle, tr("You must close all connections prior to replaying a log."));
Don Gagne's avatar
Don Gagne committed
101 102 103
        return false;
    }

Don Gagne's avatar
Don Gagne committed
104 105 106 107 108 109
    _mavlinkChannel = qgcApp()->toolbox()->linkManager()->_reserveMavlinkChannel();
    if (_mavlinkChannel == 0) {
        qWarning() << "No mavlink channels available";
        return false;
    }

Don Gagne's avatar
Don Gagne committed
110 111 112 113 114 115 116 117
    if (isRunning()) {
        quit();
        wait();
    }
    start(HighPriority);
    return true;
}

Don Gagne's avatar
Don Gagne committed
118
void LogReplayLink::_disconnect(void)
Don Gagne's avatar
Don Gagne committed
119 120 121 122 123
{
    if (_connected) {
        quit();
        wait();
        _connected = false;
Don Gagne's avatar
Don Gagne committed
124 125 126 127 128

        if (_mavlinkChannel != 0) {
            qgcApp()->toolbox()->linkManager()->_freeMavlinkChannel(_mavlinkChannel);
        }

Don Gagne's avatar
Don Gagne committed
129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147
        emit disconnected();
    }
}

void LogReplayLink::run(void)
{
    // Load the log file
    if (!_loadLogFile()) {
        return;
    }
    
    _connected = true;
    emit connected();
    
    // Start playback
    _play();

    // Run normal event loop until exit
    exec();
148 149
    
    _readTickTimer.stop();
Don Gagne's avatar
Don Gagne committed
150 151 152 153 154 155 156 157 158
}

void LogReplayLink::_replayError(const QString& errorMsg)
{
    qDebug() << _errorTitle << errorMsg;
    emit communicationError(_errorTitle, errorMsg);
}

/// Since this is log replay, we just drops writes on the floor
159
void LogReplayLink::_writeBytes(const QByteArray bytes)
Don Gagne's avatar
Don Gagne committed
160 161 162 163 164 165 166 167
{
    Q_UNUSED(bytes);
}

/// Parses a BigEndian quint64 timestamp
/// @return A Unix timestamp in microseconds UTC for found message or 0 if parsing failed
quint64 LogReplayLink::_parseTimestamp(const QByteArray& bytes)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
168
    quint64 timestamp = qFromBigEndian(*((quint64*)(bytes.constData())));
Don Gagne's avatar
Don Gagne committed
169 170 171 172 173
    quint64 currentTimestamp = ((quint64)QDateTime::currentMSecsSinceEpoch()) * 1000;
    
    // Now if the parsed timestamp is in the future, it must be an old file where the timestamp was stored as
    // little endian, so switch it.
    if (timestamp > currentTimestamp) {
DonLakeFlyer's avatar
DonLakeFlyer committed
174
        timestamp = qbswap(timestamp);
Don Gagne's avatar
Don Gagne committed
175 176 177 178 179
    }
    
    return timestamp;
}

Don Gagne's avatar
Don Gagne committed
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 205 206 207 208 209
/// Reads the next mavlink message from the log
///     @param bytes[output] Bytes for mavlink message
/// @return Unix timestamp in microseconds UTC for NEXT mavlink message or 0 if no message found
quint64 LogReplayLink::_readNextMavlinkMessage(QByteArray& bytes)
{
    char                nextByte;
    mavlink_status_t    status;

    bytes.clear();

    while (_logFile.getChar(&nextByte)) { // Loop over every byte
        mavlink_message_t message;
        bool messageFound = mavlink_parse_char(_mavlinkChannel, nextByte, &message, &status);

        if (status.parse_state == MAVLINK_PARSE_STATE_GOT_STX) {
            // This is the possible beginning of a mavlink message, clear any partial bytes
            bytes.clear();
        }
        bytes.append(nextByte);

        if (messageFound) {
            // Return the timestamp for the next message
            QByteArray rawTime = _logFile.read(cbTimestamp);
            return _parseTimestamp(rawTime);
        }
    }

    return 0;
}

Ricardo de Almeida Gonzaga's avatar
Ricardo de Almeida Gonzaga committed
210
/// Seeks to the beginning of the next successfully parsed mavlink message in the log file.
Don Gagne's avatar
Don Gagne committed
211 212 213 214
///     @param nextMsg[output] Parsed next message that was found
/// @return A Unix timestamp in microseconds UTC for found message or 0 if parsing failed
quint64 LogReplayLink::_seekToNextMavlinkMessage(mavlink_message_t* nextMsg)
{
215 216 217 218
    char                nextByte;
    mavlink_status_t    status;
    qint64              messageStartPos = -1;

219 220 221
    mavlink_reset_channel_status(_mavlinkChannel);

    while (_logFile.getChar(&nextByte)) {
Don Gagne's avatar
Don Gagne committed
222
        bool messageFound = mavlink_parse_char(_mavlinkChannel, nextByte, nextMsg, &status);
223 224 225 226 227

        if (status.parse_state == MAVLINK_PARSE_STATE_GOT_STX) {
            // This is the possible beginning of a mavlink message
            messageStartPos = _logFile.pos() - 1;
        }
Don Gagne's avatar
Don Gagne committed
228 229 230
        
        // If we've found a message, jump back to the start of the message, grab the timestamp,
        // and go back to the end of this file.
231 232
        if (messageFound && messageStartPos != -1) {
            _logFile.seek(messageStartPos - cbTimestamp);
Don Gagne's avatar
Don Gagne committed
233 234 235 236 237 238 239 240
            QByteArray rawTime = _logFile.read(cbTimestamp);
            return _parseTimestamp(rawTime);
        }
    }
    
    return 0;
}

241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265
quint64 LogReplayLink::_findLastTimestamp(void)
{
    char                nextByte;
    mavlink_status_t    status;
    quint64             lastTimestamp = 0;
    mavlink_message_t   msg;

    // We read through the entire file looking for the last good timestamp. This can be somewhat slow, but trying to work from the
    // end of the file can be way slower due to all the seeking back and forth required. So instead we take the simple reliable approach.

    _logFile.reset();
    mavlink_reset_channel_status(_mavlinkChannel);

    while (_logFile.bytesAvailable() > cbTimestamp) {
        lastTimestamp = _parseTimestamp(_logFile.read(cbTimestamp));

        bool endOfMessage = false;
        while (!endOfMessage && _logFile.getChar(&nextByte)) {
            endOfMessage = mavlink_parse_char(_mavlinkChannel, nextByte, &msg, &status);
        }
    }

    return lastTimestamp;
}

Don Gagne's avatar
Don Gagne committed
266 267 268
bool LogReplayLink::_loadLogFile(void)
{
    QString errorMsg;
269
    QString logFilename = _logReplayConfig->logFilename();
Don Gagne's avatar
Don Gagne committed
270 271
    QFileInfo logFileInfo;
    int logDurationSecondsTotal;
272 273 274
    quint64 startTimeUSecs;
    quint64 endTimeUSecs;

Don Gagne's avatar
Don Gagne committed
275
    if (_logFile.isOpen()) {
276
        errorMsg = tr("Attempt to load new log while log being played");
Don Gagne's avatar
Don Gagne committed
277 278 279 280 281
        goto Error;
    }
    
    _logFile.setFileName(logFilename);
    if (!_logFile.open(QFile::ReadOnly)) {
282
        errorMsg = tr("Unable to open log file: '%1', error: %2").arg(logFilename).arg(_logFile.errorString());
Don Gagne's avatar
Don Gagne committed
283 284 285 286 287
        goto Error;
    }
    logFileInfo.setFile(logFilename);
    _logFileSize = logFileInfo.size();
    
288 289
    startTimeUSecs = _parseTimestamp(_logFile.read(cbTimestamp));
    endTimeUSecs = _findLastTimestamp();
290

291 292 293
    if (endTimeUSecs <= startTimeUSecs) {
        errorMsg = tr("The log file '%1' is corrupt or empty.").arg(logFilename);
        goto Error;
Don Gagne's avatar
Don Gagne committed
294
    }
295 296 297 298 299 300 301 302 303 304 305

    // Remember the start and end time so we can move around this _logFile with the slider.
    _logEndTimeUSecs = endTimeUSecs;
    _logStartTimeUSecs = startTimeUSecs;
    _logDurationUSecs = endTimeUSecs - startTimeUSecs;
    _logCurrentTimeUSecs = startTimeUSecs;

    // Reset our log file so when we go to read it for the first time, we start at the beginning.
    _logFile.reset();

    logDurationSecondsTotal = (_logDurationUSecs) / 1000000;
Don Gagne's avatar
Don Gagne committed
306
    
307
    emit logFileStats(logDurationSecondsTotal);
Don Gagne's avatar
Don Gagne committed
308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324
    
    return true;
    
Error:
    if (_logFile.isOpen()) {
        _logFile.close();
    }
    _replayError(errorMsg);
    return false;
}

/// This function will read the next available log entry. It will then start
/// the _readTickTimer timer to read the new log entry at the appropriate 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.
void LogReplayLink::_readNextLogEntry(void)
{
Don Gagne's avatar
Don Gagne committed
325 326
    QByteArray bytes;

327 328
    // Now parse MAVLink messages, grabbing their timestamps as we go. We stop once we
    // have at least 3ms until the next one.
329

330 331 332
    // We track what the next execution time should be in milliseconds, which we use to set
    // the next timer interrupt.
    int timeToNextExecutionMSecs = 0;
333

334 335 336 337 338 339 340
    while (timeToNextExecutionMSecs < 3) {
        // Read the next mavlink message from the log
        qint64 nextTimeUSecs = _readNextMavlinkMessage(bytes);
        emit bytesReceived(this, bytes);
        emit playbackPercentCompleteChanged(((float)(_logCurrentTimeUSecs - _logStartTimeUSecs) / (float)_logDurationUSecs) * 100);

        if (_logFile.atEnd()) {
Don Gagne's avatar
Don Gagne committed
341 342 343
            _finishPlayback();
            return;
        }
344 345 346 347 348 349 350 351 352 353 354

        _logCurrentTimeUSecs = nextTimeUSecs;

        // Calculate how long we should wait in real time until parsing this message.
        // We pace ourselves relative to the start time of playback to fix any drift (initially set in play())

        quint64 currentTimeMSecs =                  (quint64)QDateTime::currentMSecsSinceEpoch();
        quint64 desiredPlayheadMovementTimeMSecs =  ((_logCurrentTimeUSecs - _playbackStartLogTimeUSecs) / 1000) / _playbackSpeed;
        quint64 desiredCurrentTimeMSecs =           _playbackStartTimeMSecs + desiredPlayheadMovementTimeMSecs;

        timeToNextExecutionMSecs = desiredCurrentTimeMSecs - currentTimeMSecs;
Don Gagne's avatar
Don Gagne committed
355
    }
356 357 358 359 360

    _signalCurrentLogTimeSecs();

    // And schedule the next execution of this function.
    _readTickTimer.start(timeToNextExecutionMSecs);
Don Gagne's avatar
Don Gagne committed
361 362 363 364
}

void LogReplayLink::_play(void)
{
365
    qgcApp()->toolbox()->linkManager()->setConnectionsSuspended(tr("Connect not allowed during Flight Data replay."));
Don Gagne's avatar
Don Gagne committed
366
#ifndef __mobile__
367
    qgcApp()->toolbox()->mavlinkProtocol()->suspendLogForReplay(true);
Don Gagne's avatar
Don Gagne committed
368
#endif
Don Gagne's avatar
Don Gagne committed
369 370 371 372 373 374
    
    // Make sure we aren't at the end of the file, if we are, reset to the beginning and play from there.
    if (_logFile.atEnd()) {
        _resetPlaybackToBeginning();
    }
    
375 376 377
    _playbackStartTimeMSecs = (quint64)QDateTime::currentMSecsSinceEpoch();
    _playbackStartLogTimeUSecs = _logCurrentTimeUSecs;
    _readTickTimer.start(1);
Don Gagne's avatar
Don Gagne committed
378 379 380 381 382 383
    
    emit playbackStarted();
}

void LogReplayLink::_pause(void)
{
384
    qgcApp()->toolbox()->linkManager()->setConnectionsAllowed();
Don Gagne's avatar
Don Gagne committed
385
#ifndef __mobile__
386
    qgcApp()->toolbox()->mavlinkProtocol()->suspendLogForReplay(false);
Don Gagne's avatar
Don Gagne committed
387
#endif
Don Gagne's avatar
Don Gagne committed
388 389 390 391 392 393 394 395 396 397 398 399 400 401
    
    _readTickTimer.stop();
    
    emit playbackPaused();
}

void LogReplayLink::_resetPlaybackToBeginning(void)
{
    if (_logFile.isOpen()) {
        _logFile.reset();
    }
    
    // And since we haven't starting playback, clear the time of initial playback and the current timestamp.
    _playbackStartTimeMSecs = 0;
402
    _playbackStartLogTimeUSecs = 0;
Don Gagne's avatar
Don Gagne committed
403 404 405
    _logCurrentTimeUSecs = _logStartTimeUSecs;
}

406
void LogReplayLink::movePlayhead(qreal percentComplete)
Don Gagne's avatar
Don Gagne committed
407 408
{
    if (isPlaying()) {
409
        _pauseOnThread();
410
        QSignalSpy waitForPause(this, SIGNAL(playbackPaused()));
411 412 413 414
        waitForPause.wait();
        if (_readTickTimer.isActive()) {
            return;
        }
Don Gagne's avatar
Don Gagne committed
415 416
    }

417 418 419 420 421
    if (percentComplete < 0) {
        percentComplete = 0;
    }
    if (percentComplete > 100) {
        percentComplete = 100;
Don Gagne's avatar
Don Gagne committed
422 423
    }
    
424
    qreal percentCompleteMult = percentComplete / 100.0;
Don Gagne's avatar
Don Gagne committed
425
    
426 427 428 429 430 431 432 433
    // But if we have a timestamped MAVLink log, then actually aim to hit that percentage in terms of
    // time through the file.
    qint64 newFilePos = (qint64)(percentCompleteMult * (qreal)_logFile.size());

    // Now seek to the appropriate position, failing gracefully if we can't.
    if (!_logFile.seek(newFilePos)) {
        _replayError(tr("Unable to seek to new position"));
        return;
Don Gagne's avatar
Don Gagne committed
434
    }
435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464

    // But we do align to the next MAVLink message for consistency.
    mavlink_message_t dummy;
    _logCurrentTimeUSecs = _seekToNextMavlinkMessage(&dummy);

    // Now calculate the current file location based on time.
    qreal newRelativeTimeUSecs = (qreal)(_logCurrentTimeUSecs - _logStartTimeUSecs);

    // Calculate the effective baud rate of the file in bytes/s.
    qreal baudRate = _logFile.size() / (qreal)_logDurationUSecs / 1e6;

    // And the desired time is:
    qreal desiredTimeUSecs = percentCompleteMult * _logDurationUSecs;

    // And now jump the necessary number of bytes in the proper direction
    qint64 offset = (newRelativeTimeUSecs - desiredTimeUSecs) * baudRate;
    if (!_logFile.seek(_logFile.pos() + offset)) {
        _replayError(tr("Unable to seek to new position"));
        return;
    }

    // And scan until we reach the start of a MAVLink message. We make sure to record this timestamp for
    // smooth jumping around the file.
    _logCurrentTimeUSecs = _seekToNextMavlinkMessage(&dummy);
    _signalCurrentLogTimeSecs();

    // Now update the UI with our actual final position.
    newRelativeTimeUSecs = (qreal)(_logCurrentTimeUSecs - _logStartTimeUSecs);
    percentComplete = (newRelativeTimeUSecs / _logDurationUSecs) * 100;
    emit playbackPercentCompleteChanged(percentComplete);
Don Gagne's avatar
Don Gagne committed
465 466
}

467
void LogReplayLink::_setPlaybackSpeed(qreal playbackSpeed)
Don Gagne's avatar
Don Gagne committed
468
{
469
    _playbackSpeed = playbackSpeed;
Don Gagne's avatar
Don Gagne committed
470
    
471 472 473 474
    // Let _readNextLogEntry update to correct speed
    _playbackStartTimeMSecs = (quint64)QDateTime::currentMSecsSinceEpoch();
    _playbackStartLogTimeUSecs = _logCurrentTimeUSecs;
    _readTickTimer.start(1);
Don Gagne's avatar
Don Gagne committed
475 476 477 478 479 480 481 482 483 484
}

/// @brief Called when playback is complete
void LogReplayLink::_finishPlayback(void)
{
    _pause();
    
    emit playbackAtEnd();
}

485
void LogReplayLink::_signalCurrentLogTimeSecs(void)
Don Gagne's avatar
Don Gagne committed
486
{
487
    emit currentLogTimeSecs((_logCurrentTimeUSecs - _logStartTimeUSecs) / 1000000);
Don Gagne's avatar
Don Gagne committed
488
}
489

490 491 492 493 494
LogReplayLinkController::LogReplayLinkController(void)
    : _link             (nullptr)
    , _isPlaying        (false)
    , _percentComplete  (0)
    , _playheadSecs     (0)
495
    , _playbackSpeed    (1)
496
{
497 498 499 500 501 502
}

void LogReplayLinkController::setLink(LogReplayLink* link)
{
    if (_link) {
        disconnect(_link);
503
        disconnect(this, &LogReplayLinkController::playbackSpeedChanged, _link, &LogReplayLink::setPlaybackSpeed);
504 505 506 507 508 509 510 511 512 513 514 515 516 517 518
        _isPlaying = false;
        _percentComplete = 0;
        _playheadTime.clear();
        _totalTime.clear();
        _link = nullptr;
        emit isPlayingChanged(false);
        emit percentCompleteChanged(0);
        emit playheadTimeChanged(QString());
        emit totalTimeChanged(QString());
        emit linkChanged(nullptr);
    }


    if (link) {
        _link = link;
519

520 521 522 523 524 525
        connect(_link, &LogReplayLink::logFileStats,                      this, &LogReplayLinkController::_logFileStats);
        connect(_link, &LogReplayLink::playbackStarted,                   this, &LogReplayLinkController::_playbackStarted);
        connect(_link, &LogReplayLink::playbackPaused,                    this, &LogReplayLinkController::_playbackPaused);
        connect(_link, &LogReplayLink::playbackPercentCompleteChanged,    this, &LogReplayLinkController::_playbackPercentCompleteChanged);
        connect(_link, &LogReplayLink::currentLogTimeSecs,                this, &LogReplayLinkController::_currentLogTimeSecs);
        connect(_link, &LogReplayLink::disconnected,                      this, &LogReplayLinkController::_linkDisconnected);
526 527 528

        connect(this, &LogReplayLinkController::playbackSpeedChanged, _link, &LogReplayLink::setPlaybackSpeed);

529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546
        emit linkChanged(_link);
    }
}

void LogReplayLinkController::setIsPlaying(bool isPlaying)
{
    if (isPlaying) {
        _link->play();
    } else {
        _link->pause();
    }
}

void LogReplayLinkController::setPercentComplete(qreal percentComplete)
{
    _link->movePlayhead(percentComplete);
}

547
void LogReplayLinkController::_logFileStats(int logDurationSecs)
548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598
{
    _totalTime = _secondsToHMS(logDurationSecs);
    emit totalTimeChanged(_totalTime);
}

void LogReplayLinkController::_playbackStarted(void)
{
    _isPlaying = true;
    emit isPlayingChanged(true);
}

void LogReplayLinkController::_playbackPaused(void)
{
    _isPlaying = false;
    emit isPlayingChanged(true);
}

void LogReplayLinkController::_playbackAtEnd(void)
{
    _isPlaying = false;
    emit isPlayingChanged(true);
}

void LogReplayLinkController::_playbackPercentCompleteChanged(qreal percentComplete)
{
    _percentComplete = percentComplete;
    emit percentCompleteChanged(_percentComplete);
}

void LogReplayLinkController::_currentLogTimeSecs(int secs)
{
    if (_playheadSecs != secs) {
        _playheadSecs = secs;
        _playheadTime = _secondsToHMS(secs);
        emit playheadTimeChanged(_playheadTime);
    }
}

void LogReplayLinkController::_linkDisconnected(void)
{
    setLink(nullptr);
}

QString LogReplayLinkController::_secondsToHMS(int seconds)
{
    int secondsPart  = seconds;
    int minutesPart  = secondsPart / 60;
    int hoursPart    = minutesPart / 60;
    secondsPart -= 60 * minutesPart;
    minutesPart -= 60 * hoursPart;

599 600 601 602 603
    if (hoursPart == 0) {
        return tr("%2m:%3s").arg(minutesPart, 2, 10, QLatin1Char('0')).arg(secondsPart, 2, 10, QLatin1Char('0'));
    } else {
        return tr("%1h:%2m:%3s").arg(hoursPart, 2, 10, QLatin1Char('0')).arg(minutesPart, 2, 10, QLatin1Char('0')).arg(secondsPart, 2, 10, QLatin1Char('0'));
    }
604
}