From 4649beffdf2587256e636c36e432b0a2aed1bbca Mon Sep 17 00:00:00 2001 From: Holden Date: Fri, 2 Aug 2024 15:00:46 -0400 Subject: [PATCH] Comms: Convert LogReplayLink to Signals/Slots --- src/Comms/LinkInterface.h | 2 +- src/Comms/LogReplayLink.cc | 544 +++++++++++++++++-------------------- src/Comms/LogReplayLink.h | 247 ++++++++--------- 3 files changed, 367 insertions(+), 426 deletions(-) diff --git a/src/Comms/LinkInterface.h b/src/Comms/LinkInterface.h index 27b78ee21ba5..57401a002f73 100644 --- a/src/Comms/LinkInterface.h +++ b/src/Comms/LinkInterface.h @@ -33,7 +33,7 @@ class LinkInterface : public QThread Q_INVOKABLE virtual void disconnect() = 0; virtual bool isConnected() const = 0; - virtual bool isLogReplay() { return false; } + virtual bool isLogReplay() const { return false; } virtual bool isSecureConnection() { return false; } ///< Returns true if the connection is secure (e.g. USB, wired ethernet) SharedLinkConfigurationPtr linkConfiguration() { return _config; } diff --git a/src/Comms/LogReplayLink.cc b/src/Comms/LogReplayLink.cc index b0112b6a0d1f..50850ba87714 100644 --- a/src/Comms/LogReplayLink.cc +++ b/src/Comms/LogReplayLink.cc @@ -12,189 +12,199 @@ #include "LinkManager.h" #include "QGCApplication.h" #include "MultiVehicleManager.h" -#ifndef __mobile__ +#if !defined(Q_OS_ANDROID) && !defined(Q_OS_IOS) #include "MAVLinkProtocol.h" +#else +#include "MAVLinkLib.h" #endif +#include +#include #include #include -#include +// #include -LogReplayLinkConfiguration::LogReplayLinkConfiguration(const QString& name) - : LinkConfiguration(name) +QGC_LOGGING_CATEGORY(LogReplayLinkLog, "qgc.comms.logreplaylink") + +const QString LogReplayLink::_errorTitle = QStringLiteral("Log Replay Link Error"); + +LogReplayLinkConfiguration::LogReplayLinkConfiguration(const QString &name, QObject *parent) + : LinkConfiguration(name, parent) { - + // qCDebug(LogReplayLinkLog) << Q_FUNC_INFO << this; +} + +LogReplayLinkConfiguration::LogReplayLinkConfiguration(LogReplayLinkConfiguration *copy, QObject *parent) + : LinkConfiguration(copy, parent) +{ + // qCDebug(LogReplayLinkLog) << Q_FUNC_INFO << this; + + Q_CHECK_PTR(copy); + + LogReplayLinkConfiguration::copyFrom(copy); } -LogReplayLinkConfiguration::LogReplayLinkConfiguration(LogReplayLinkConfiguration* copy) - : LinkConfiguration(copy) +LogReplayLinkConfiguration::~LogReplayLinkConfiguration() { - _logFilename = copy->logFilename(); + // qCDebug(LogReplayLinkLog) << Q_FUNC_INFO << this; +} + +QString LogReplayLinkConfiguration::logFilenameShort() +{ + return QFileInfo(_logFilename).fileName(); +} + +void LogReplayLinkConfiguration::setLogFilename(const QString &logFilename) +{ + if (logFilename != _logFilename) { + _logFilename = logFilename; + emit fileNameChanged(); + } } void LogReplayLinkConfiguration::copyFrom(LinkConfiguration *source) { + Q_CHECK_PTR(source); LinkConfiguration::copyFrom(source); - auto* ssource = qobject_cast(source); - if (ssource) { - _logFilename = ssource->logFilename(); - } else { - qWarning() << "Internal error"; - } + + const LogReplayLinkConfiguration* const logReplaySource = qobject_cast(source); + Q_CHECK_PTR(logReplaySource); + + setLogFilename(logReplaySource->logFilename()); } -void LogReplayLinkConfiguration::saveSettings(QSettings& settings, const QString& root) +void LogReplayLinkConfiguration::loadSettings(QSettings &settings, const QString &root) { settings.beginGroup(root); - settings.setValue(_logFilenameKey, _logFilename); + + setLogFilename(settings.value("logFilename", _logFilename).toString()); + settings.endGroup(); } -void LogReplayLinkConfiguration::loadSettings(QSettings& settings, const QString& root) +void LogReplayLinkConfiguration::saveSettings(QSettings &settings, const QString &root) { settings.beginGroup(root); - _logFilename = settings.value(_logFilenameKey, "").toString(); + + settings.setValue("logFilename", _logFilename); + settings.endGroup(); } -QString LogReplayLinkConfiguration::logFilenameShort(void) -{ - QFileInfo fi(_logFilename); - return fi.fileName(); -} +/*===========================================================================*/ -LogReplayLink::LogReplayLink(SharedLinkConfigurationPtr& config) - : LinkInterface (config) - , _logReplayConfig (qobject_cast(config.get())) - , _connected (false) - , _mavlinkChannel (0) - , _logCurrentTimeUSecs (0) - , _logStartTimeUSecs (0) - , _logEndTimeUSecs (0) - , _logDurationUSecs (0) - , _playbackSpeed (1) - , _playbackStartTimeMSecs (0) - , _playbackStartLogTimeUSecs (0) - , _mavlink (nullptr) - , _logFileSize (0) +LogReplayLink::LogReplayLink(SharedLinkConfigurationPtr &config, QObject *parent) + : LinkInterface(config, parent) + , _logReplayConfig(qobject_cast(config.get())) + , _readTickTimer(new QTimer(this)) { - if (!_logReplayConfig) { - qWarning() << "Internal error"; - } + // qCDebug(LogReplayLinkLog) << Q_FUNC_INFO << this; - _errorTitle = tr("Log Replay Error"); - - _readTickTimer.moveToThread(this); - - 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); - - moveToThread(this); + (void) QObject::connect(_readTickTimer, &QTimer::timeout, this, &LogReplayLink::_readNextLogEntry); } -LogReplayLink::~LogReplayLink(void) +LogReplayLink::~LogReplayLink() { - disconnect(); + LogReplayLink::disconnect(); + + // qCDebug(LogReplayLinkLog) << Q_FUNC_INFO << this; } -bool LogReplayLink::_connect(void) +bool LogReplayLink::_connect() { - // Disallow replay when any links are connected if (qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()) { - emit communicationError(_errorTitle, tr("You must close all connections prior to replaying a log.")); + _replayError(QStringLiteral("You must close all connections prior to replaying a log.")); return false; } - if (isRunning()) { - quit(); - wait(); - } - start(HighPriority); + // if (isRunning()) { + // quit(); + // wait(); + // } + + // start(HighPriority); return true; } -void LogReplayLink::disconnect(void) +void LogReplayLink::disconnect() { if (_connected) { - quit(); - wait(); + // quit(); + // wait(); _connected = false; emit disconnected(); } } -void LogReplayLink::run(void) +void LogReplayLink::run() { - // Load the log file if (!_loadLogFile()) { return; } - + _connected = true; emit connected(); - - // Start playback + _play(); - // Run normal event loop until exit - exec(); - - _readTickTimer.stop(); + // exec(); + + (void) QMetaObject::invokeMethod(_readTickTimer, "stop", Qt::AutoConnection); +} + +bool LogReplayLink::isPlaying() const +{ + return _readTickTimer->isActive(); +} + +void LogReplayLink::play() +{ + (void) QMetaObject::invokeMethod(this, "_play", Qt::AutoConnection); +} + +void LogReplayLink::pause() +{ + (void) QMetaObject::invokeMethod(this, "_pause", Qt::AutoConnection); } -void LogReplayLink::_replayError(const QString& errorMsg) +void LogReplayLink::setPlaybackSpeed(qreal playbackSpeed) { - qDebug() << _errorTitle << errorMsg; - emit communicationError(_errorTitle, errorMsg); + (void) QMetaObject::invokeMethod(this, "_setPlaybackSpeed", Qt::AutoConnection, playbackSpeed); } -/// Since this is log replay, we just drops writes on the floor -void LogReplayLink::_writeBytes(const QByteArray &bytes) +void LogReplayLink::_replayError(const QString &errorMsg) { - Q_UNUSED(bytes); + emit communicationError(QStringLiteral("Log Replay Link Error"), QStringLiteral("Link: %1, %2.").arg(_logReplayConfig->name(), errorMsg)); } -/// 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) +quint64 LogReplayLink::_parseTimestamp(const QByteArray &bytes) { - quint64 timestamp = qFromBigEndian(*((quint64*)(bytes.constData()))); - 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. + quint64 timestamp = qFromBigEndian(*reinterpret_cast(bytes.constData())); + const quint64 currentTimestamp = static_cast(QDateTime::currentMSecsSinceEpoch()) * 1000; if (timestamp > currentTimestamp) { timestamp = qbswap(timestamp); } - + return timestamp; } -/// 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) +quint64 LogReplayLink::_readNextMavlinkMessage(QByteArray &bytes) { - char nextByte; - mavlink_status_t status; - bytes.clear(); - while (_logFile.getChar(&nextByte)) { // Loop over every byte + mavlink_status_t status; + char nextByte; + while (_logFile.getChar(&nextByte)) { mavlink_message_t message; - bool messageFound = mavlink_parse_char(_mavlinkChannel, nextByte, &message, &status); + const 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); + (void) bytes.append(nextByte); if (messageFound) { - // Return the timestamp for the next message - QByteArray rawTime = _logFile.read(cbTimestamp); + const QByteArray rawTime = _logFile.read(kTimestamp); return _parseTimestamp(rawTime); } } @@ -202,55 +212,45 @@ quint64 LogReplayLink::_readNextMavlinkMessage(QByteArray& bytes) return 0; } -/// Seeks to the beginning of the next successfully parsed mavlink message in the log file. -/// @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) +quint64 LogReplayLink::_seekToNextMavlinkMessage(mavlink_message_t &nextMsg) { - char nextByte; - mavlink_status_t status; - qint64 messageStartPos = -1; - mavlink_reset_channel_status(_mavlinkChannel); + mavlink_status_t status; + qint64 messageStartPos = -1; + char nextByte; while (_logFile.getChar(&nextByte)) { - bool messageFound = mavlink_parse_char(_mavlinkChannel, nextByte, nextMsg, &status); + const bool messageFound = mavlink_parse_char(_mavlinkChannel, nextByte, &nextMsg, &status); if (status.parse_state == MAVLINK_PARSE_STATE_GOT_STX) { - // This is the possible beginning of a mavlink message - messageStartPos = _logFile.pos() - 1; + messageStartPos = (_logFile.pos() - 1); } - - // 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. - if (messageFound && messageStartPos != -1) { - _logFile.seek(messageStartPos - cbTimestamp); - QByteArray rawTime = _logFile.read(cbTimestamp); + + if (messageFound && (messageStartPos != -1)) { + (void) _logFile.seek(messageStartPos - kTimestamp); + const QByteArray rawTime = _logFile.read(kTimestamp); return _parseTimestamp(rawTime); } } - + return 0; } -quint64 LogReplayLink::_findLastTimestamp(void) +quint64 LogReplayLink::_findLastTimestamp() { - char nextByte; - mavlink_status_t status; - quint64 lastTimestamp = 0; - mavlink_message_t msg; + quint64 lastTimestamp = 0; - // 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)); + (void) _logFile.reset(); + while (_logFile.bytesAvailable() > kTimestamp) { + lastTimestamp = _parseTimestamp(_logFile.read(kTimestamp)); bool endOfMessage = false; + char nextByte; while (!endOfMessage && _logFile.getChar(&nextByte)) { + mavlink_message_t msg; + mavlink_status_t status; endOfMessage = mavlink_parse_char(_mavlinkChannel, nextByte, &msg, &status); } } @@ -258,79 +258,65 @@ quint64 LogReplayLink::_findLastTimestamp(void) return lastTimestamp; } -bool LogReplayLink::_loadLogFile(void) +bool LogReplayLink::_loadLogFile() { - QString errorMsg; - QString logFilename = _logReplayConfig->logFilename(); + const QString logFilename = _logReplayConfig->logFilename(); QFileInfo logFileInfo; int logDurationSecondsTotal; quint64 startTimeUSecs; quint64 endTimeUSecs; + QString errorMsg; if (_logFile.isOpen()) { - errorMsg = tr("Attempt to load new log while log being played"); + errorMsg = QStringLiteral("Attempt to load new log while log being played"); goto Error; } - + _logFile.setFileName(logFilename); if (!_logFile.open(QFile::ReadOnly)) { - errorMsg = tr("Unable to open log file: '%1', error: %2").arg(logFilename).arg(_logFile.errorString()); + errorMsg = QStringLiteral("Unable to open log file: '%1', error: %2").arg(logFilename, _logFile.errorString()); goto Error; } + logFileInfo.setFile(logFilename); _logFileSize = logFileInfo.size(); - - startTimeUSecs = _parseTimestamp(_logFile.read(cbTimestamp)); - endTimeUSecs = _findLastTimestamp(); + startTimeUSecs = _parseTimestamp(_logFile.read(kTimestamp)); + endTimeUSecs = _findLastTimestamp(); if (endTimeUSecs <= startTimeUSecs) { - errorMsg = tr("The log file '%1' is corrupt or empty.").arg(logFilename); + errorMsg = QStringLiteral("The log file '%1' is corrupt or empty.").arg(logFilename); goto Error; } - // 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(); + (void) _logFile.reset(); - logDurationSecondsTotal = (_logDurationUSecs) / 1000000; - + logDurationSecondsTotal = _logDurationUSecs / 1000000; emit logFileStats(logDurationSecondsTotal); - + 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) +void LogReplayLink::_readNextLogEntry() { - QByteArray bytes; - - // Now parse MAVLink messages, grabbing their timestamps as we go. We stop once we - // have at least 3ms until the next one. - - // We track what the next execution time should be in milliseconds, which we use to set - // the next timer interrupt. int timeToNextExecutionMSecs = 0; - while (timeToNextExecutionMSecs < 3) { - // Read the next mavlink message from the log - qint64 nextTimeUSecs = _readNextMavlinkMessage(bytes); + QByteArray bytes; + const qint64 nextTimeUSecs = _readNextMavlinkMessage(bytes); emit bytesReceived(this, bytes); - emit playbackPercentCompleteChanged(((float)(_logCurrentTimeUSecs - _logStartTimeUSecs) / (float)_logDurationUSecs) * 100); + emit playbackPercentCompleteChanged((static_cast(_logCurrentTimeUSecs - _logStartTimeUSecs) / static_cast(_logDurationUSecs)) * 100); if (_logFile.atEnd()) { _finishPlayback(); @@ -339,60 +325,53 @@ void LogReplayLink::_readNextLogEntry(void) _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; - + const quint64 currentTimeMSecs = static_cast(QDateTime::currentMSecsSinceEpoch()); + const quint64 desiredPlayheadMovementTimeMSecs = ((_logCurrentTimeUSecs - _playbackStartLogTimeUSecs) / 1000) / _playbackSpeed; + const quint64 desiredCurrentTimeMSecs = _playbackStartTimeMSecs + desiredPlayheadMovementTimeMSecs; timeToNextExecutionMSecs = desiredCurrentTimeMSecs - currentTimeMSecs; } _signalCurrentLogTimeSecs(); - // And schedule the next execution of this function. - _readTickTimer.start(timeToNextExecutionMSecs); + (void) QMetaObject::invokeMethod(_readTickTimer, "start", Qt::AutoConnection, timeToNextExecutionMSecs); } -void LogReplayLink::_play(void) +void LogReplayLink::_play() { - qgcApp()->toolbox()->linkManager()->setConnectionsSuspended(tr("Connect not allowed during Flight Data replay.")); -#ifndef __mobile__ + qgcApp()->toolbox()->linkManager()->setConnectionsSuspended(QStringLiteral("Connect not allowed during Flight Data replay.")); +#if !defined(Q_OS_ANDROID) && !defined(Q_OS_IOS) qgcApp()->toolbox()->mavlinkProtocol()->suspendLogForReplay(true); #endif - - // 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(); } - + _playbackStartTimeMSecs = (quint64)QDateTime::currentMSecsSinceEpoch(); _playbackStartLogTimeUSecs = _logCurrentTimeUSecs; - _readTickTimer.start(1); - + (void) QMetaObject::invokeMethod(_readTickTimer, "start", Qt::AutoConnection, 1); + emit playbackStarted(); } -void LogReplayLink::_pause(void) +void LogReplayLink::_pause() { qgcApp()->toolbox()->linkManager()->setConnectionsAllowed(); -#ifndef __mobile__ +#if !defined(Q_OS_ANDROID) && !defined(Q_OS_IOS) qgcApp()->toolbox()->mavlinkProtocol()->suspendLogForReplay(false); #endif - - _readTickTimer.stop(); - + + (void) QMetaObject::invokeMethod(_readTickTimer, "stop", Qt::AutoConnection); + emit playbackPaused(); } -void LogReplayLink::_resetPlaybackToBeginning(void) +void LogReplayLink::_resetPlaybackToBeginning() { if (_logFile.isOpen()) { _logFile.reset(); } - - // And since we haven't starting playback, clear the time of initial playback and the current timestamp. + _playbackStartTimeMSecs = 0; _playbackStartLogTimeUSecs = 0; _logCurrentTimeUSecs = _logStartTimeUSecs; @@ -401,125 +380,104 @@ void LogReplayLink::_resetPlaybackToBeginning(void) void LogReplayLink::movePlayhead(qreal percentComplete) { if (isPlaying()) { - _pauseOnThread(); - QSignalSpy waitForPause(this, SIGNAL(playbackPaused())); - waitForPause.wait(); - if (_readTickTimer.isActive()) { + pause(); + // QSignalSpy waitForPause(this, SIGNAL(playbackPaused())); + // (void) waitForPause.wait(); + if (_readTickTimer->isActive()) { return; } } - if (percentComplete < 0) { - percentComplete = 0; - } - if (percentComplete > 100) { - percentComplete = 100; - } - - qreal percentCompleteMult = percentComplete / 100.0; - - // 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. + percentComplete = qBound(0., percentComplete, 100.); + const qreal percentCompleteMult = percentComplete / 100.0; + const qint64 newFilePos = static_cast(percentCompleteMult * static_cast(_logFile.size())); if (!_logFile.seek(newFilePos)) { - _replayError(tr("Unable to seek to new position")); + _replayError(QStringLiteral("Unable to seek to new position")); return; } - // 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; + _logCurrentTimeUSecs = _seekToNextMavlinkMessage(dummy); + qreal newRelativeTimeUSecs = static_cast(_logCurrentTimeUSecs - _logStartTimeUSecs); + const qreal baudRate = _logFile.size() / static_cast(_logDurationUSecs) / 1e6; + const qreal desiredTimeUSecs = percentCompleteMult * _logDurationUSecs; + const qint64 offset = (newRelativeTimeUSecs - desiredTimeUSecs) * baudRate; if (!_logFile.seek(_logFile.pos() + offset)) { - _replayError(tr("Unable to seek to new position")); + _replayError(QStringLiteral("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); + _logCurrentTimeUSecs = _seekToNextMavlinkMessage(dummy); _signalCurrentLogTimeSecs(); - // Now update the UI with our actual final position. - newRelativeTimeUSecs = (qreal)(_logCurrentTimeUSecs - _logStartTimeUSecs); - percentComplete = (newRelativeTimeUSecs / _logDurationUSecs) * 100; + newRelativeTimeUSecs = static_cast(_logCurrentTimeUSecs - _logStartTimeUSecs); + percentComplete = ((newRelativeTimeUSecs / _logDurationUSecs) * 100); emit playbackPercentCompleteChanged(percentComplete); } void LogReplayLink::_setPlaybackSpeed(qreal playbackSpeed) { _playbackSpeed = playbackSpeed; - - // Let _readNextLogEntry update to correct speed - _playbackStartTimeMSecs = (quint64)QDateTime::currentMSecsSinceEpoch(); + _playbackStartTimeMSecs = static_cast(QDateTime::currentMSecsSinceEpoch()); _playbackStartLogTimeUSecs = _logCurrentTimeUSecs; - _readTickTimer.start(1); + (void) QMetaObject::invokeMethod(_readTickTimer, "start", Qt::AutoConnection, 1); } -/// @brief Called when playback is complete -void LogReplayLink::_finishPlayback(void) +void LogReplayLink::_finishPlayback() { _pause(); - + emit playbackAtEnd(); } -void LogReplayLink::_signalCurrentLogTimeSecs(void) +void LogReplayLink::_signalCurrentLogTimeSecs() { emit currentLogTimeSecs((_logCurrentTimeUSecs - _logStartTimeUSecs) / 1000000); } -LogReplayLinkController::LogReplayLinkController(void) - : _link (nullptr) - , _isPlaying (false) - , _percentComplete (0) - , _playheadSecs (0) - , _playbackSpeed (1) +/*===========================================================================*/ + +LogReplayLinkController::LogReplayLinkController(QObject *parent) + : QObject(parent) +{ + // qCDebug(LogReplayLinkLog) << Q_FUNC_INFO << this; +} + +LogReplayLinkController::~LogReplayLinkController() { + // qCDebug(LogReplayLinkLog) << Q_FUNC_INFO << this; } -void LogReplayLinkController::setLink(LogReplayLink* link) +void LogReplayLinkController::setLink(LogReplayLink *link) { if (_link) { - disconnect(_link); - disconnect(this, &LogReplayLinkController::playbackSpeedChanged, _link, &LogReplayLink::setPlaybackSpeed); + (void) QObject::disconnect(_link); + (void) QObject::disconnect(this, &LogReplayLinkController::playbackSpeedChanged, _link, &LogReplayLink::setPlaybackSpeed); + _isPlaying = false; + emit isPlayingChanged(_isPlaying); _percentComplete = 0; + emit percentCompleteChanged(_percentComplete); _playheadTime.clear(); + emit playheadTimeChanged(_playheadTime); _totalTime.clear(); + emit totalTimeChanged(_totalTime); _link = nullptr; - emit isPlayingChanged(false); - emit percentCompleteChanged(0); - emit playheadTimeChanged(QString()); - emit totalTimeChanged(QString()); - emit linkChanged(nullptr); + emit linkChanged(_link); } if (link) { _link = link; - 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); + (void) QObject::connect(_link, &LogReplayLink::logFileStats, this, &LogReplayLinkController::_logFileStats, Qt::AutoConnection); + (void) QObject::connect(_link, &LogReplayLink::playbackStarted, this, &LogReplayLinkController::_playbackStarted, Qt::AutoConnection); + (void) QObject::connect(_link, &LogReplayLink::playbackPaused, this, &LogReplayLinkController::_playbackPaused, Qt::AutoConnection); + (void) QObject::connect(_link, &LogReplayLink::playbackPercentCompleteChanged, this, &LogReplayLinkController::_playbackPercentCompleteChanged, Qt::AutoConnection); + (void) QObject::connect(_link, &LogReplayLink::currentLogTimeSecs, this, &LogReplayLinkController::_currentLogTimeSecs, Qt::AutoConnection); + (void) QObject::connect(_link, &LogReplayLink::disconnected, this, &LogReplayLinkController::_linkDisconnected, Qt::AutoConnection); - connect(this, &LogReplayLinkController::playbackSpeedChanged, _link, &LogReplayLink::setPlaybackSpeed); + (void) QObject::connect(this, &LogReplayLinkController::playbackSpeedChanged, _link, &LogReplayLink::setPlaybackSpeed, Qt::AutoConnection); emit linkChanged(_link); } @@ -534,66 +492,68 @@ void LogReplayLinkController::setIsPlaying(bool isPlaying) } } -void LogReplayLinkController::setPercentComplete(qreal percentComplete) -{ - _link->movePlayhead(percentComplete); -} - -void LogReplayLinkController::_logFileStats(int logDurationSecs) +void LogReplayLinkController::_logFileStats(uint32_t logDurationSecs) { - _totalTime = _secondsToHMS(logDurationSecs); - emit totalTimeChanged(_totalTime); + const QString totalTime = _secondsToHMS(logDurationSecs); + if (totalTime != _totalTime) { + _totalTime = totalTime; + emit totalTimeChanged(_totalTime); + } } -void LogReplayLinkController::_playbackStarted(void) +void LogReplayLinkController::_playbackStarted() { - _isPlaying = true; - emit isPlayingChanged(true); + if (!_isPlaying) { + _isPlaying = true; + emit isPlayingChanged(_isPlaying); + } } -void LogReplayLinkController::_playbackPaused(void) +void LogReplayLinkController::_playbackPaused() { - _isPlaying = false; - emit isPlayingChanged(true); + if (_isPlaying) { + _isPlaying = false; + emit isPlayingChanged(_isPlaying); + } } -void LogReplayLinkController::_playbackAtEnd(void) +void LogReplayLinkController::_playbackAtEnd() { - _isPlaying = false; - emit isPlayingChanged(true); + if (_isPlaying) { + _isPlaying = false; + emit isPlayingChanged(_isPlaying); + } } void LogReplayLinkController::_playbackPercentCompleteChanged(qreal percentComplete) { - _percentComplete = percentComplete; - emit percentCompleteChanged(_percentComplete); + if (percentComplete != _percentComplete) { + _percentComplete = percentComplete; + emit percentCompleteChanged(_percentComplete); + } } -void LogReplayLinkController::_currentLogTimeSecs(int secs) +void LogReplayLinkController::_currentLogTimeSecs(uint32_t secs) { - if (_playheadSecs != secs) { + if (secs != _playheadSecs) { _playheadSecs = secs; _playheadTime = _secondsToHMS(secs); emit playheadTimeChanged(_playheadTime); } } -void LogReplayLinkController::_linkDisconnected(void) -{ - setLink(nullptr); -} - -QString LogReplayLinkController::_secondsToHMS(int seconds) +QString LogReplayLinkController::_secondsToHMS(uint32_t seconds) { - int secondsPart = seconds; - int minutesPart = secondsPart / 60; - int hoursPart = minutesPart / 60; - secondsPart -= 60 * minutesPart; - minutesPart -= 60 * hoursPart; + uint32_t secondsPart = seconds; + uint32_t minutesPart = secondsPart / 60; + const uint32_t hoursPart = minutesPart / 60; + secondsPart -= (60 * minutesPart); + minutesPart -= (60 * hoursPart); - 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')); + QString result = QStringLiteral("%2m:%3s").arg(minutesPart, 2, 10, QLatin1Char('0')).arg(secondsPart, 2, 10, QLatin1Char('0')); + if (hoursPart != 0) { + (void) result.prepend(QStringLiteral("%1h:").arg(hoursPart, 2, 10, QLatin1Char('0'))); } + + return result; } diff --git a/src/Comms/LogReplayLink.h b/src/Comms/LogReplayLink.h index 8034f0afb9a1..c3307bfd66d7 100644 --- a/src/Comms/LogReplayLink.h +++ b/src/Comms/LogReplayLink.h @@ -9,184 +9,165 @@ #pragma once +#include + #include "LinkConfiguration.h" #include "LinkInterface.h" -#include "QGCMAVLink.h" -#include -#include +Q_DECLARE_LOGGING_CATEGORY(LogReplayLinkLog) + +typedef struct __mavlink_message mavlink_message_t; -class LinkManager; -class MAVLinkProtocol; +class QTimer; class LogReplayLinkConfiguration : public LinkConfiguration { Q_OBJECT -public: - Q_PROPERTY(QString fileName READ logFilename WRITE setLogFilename NOTIFY fileNameChanged) - - LogReplayLinkConfiguration(const QString& name); - LogReplayLinkConfiguration(LogReplayLinkConfiguration* copy); + Q_PROPERTY(QString fileName READ logFilename WRITE setLogFilename NOTIFY fileNameChanged) - QString logFilename(void) { return _logFilename; } - void setLogFilename(const QString logFilename) { _logFilename = logFilename; emit fileNameChanged(); } +public: + explicit LogReplayLinkConfiguration(const QString &name, QObject *parent = nullptr); + explicit LogReplayLinkConfiguration(LogReplayLinkConfiguration *copy, QObject *parent = nullptr); + virtual ~LogReplayLinkConfiguration(); - QString logFilenameShort(void); + QString logFilenameShort(); + QString logFilename() const { return _logFilename; } + void setLogFilename(const QString &logFilename); - // Virtuals from LinkConfiguration - LinkType type (void) override { return LinkConfiguration::TypeLogReplay; } - void copyFrom (LinkConfiguration* source) override; - void loadSettings (QSettings& settings, const QString& root) override; - void saveSettings (QSettings& settings, const QString& root) override; - QString settingsURL (void) override { return "LogReplaySettings.qml"; } - QString settingsTitle (void) override { return tr("Log Replay Link Settings"); } + LinkType type() override { return LinkConfiguration::TypeLogReplay; } + void copyFrom(LinkConfiguration *source) override; + void loadSettings(QSettings &settings, const QString &root) override; + void saveSettings(QSettings &settings, const QString &root) override; + QString settingsURL() override { return QStringLiteral("LogReplaySettings.qml"); } + QString settingsTitle() override { return QStringLiteral("Log Replay Link Settings"); } signals: void fileNameChanged(); private: - static constexpr const char* _logFilenameKey = "logFilename"; - QString _logFilename; + QString _logFilename; }; -/// Pseudo link that reads a telemetry log and feeds it into the application. +/*===========================================================================*/ + class LogReplayLink : public LinkInterface { Q_OBJECT public: - LogReplayLink(SharedLinkConfigurationPtr& config); + explicit LogReplayLink(SharedLinkConfigurationPtr &config, QObject *parent = nullptr); virtual ~LogReplayLink(); - /// @return true: log is currently playing, false: log playback is paused - bool isPlaying(void) { return _readTickTimer.isActive(); } - - void play (void) { emit _playOnThread(); } - void pause (void) { emit _pauseOnThread(); } - void movePlayhead (qreal percentComplete); - - // overrides from LinkInterface - bool isConnected(void) const override { return _connected; } - bool isLogReplay(void) override { return true; } - void disconnect (void) override; + bool isPlaying() const; + void play(); + void pause(); + void setPlaybackSpeed(qreal playbackSpeed); + void movePlayhead(qreal percentComplete); -public slots: - /// Sets the acceleration factor: -100: 0.01X, 0: 1.0X, 100: 100.0X - void setPlaybackSpeed(qreal playbackSpeed) { emit _setPlaybackSpeedOnThread(playbackSpeed); } + void run() override {} + bool isConnected() const override { return _connected; } + void disconnect() override; + bool isLogReplay() const override { return true; } signals: - void logFileStats (int logDurationSecs); - void playbackStarted (void); - void playbackPaused (void); - void playbackAtEnd (void); - void playbackPercentCompleteChanged (qreal percentComplete); - void currentLogTimeSecs (int secs); - - // Internal signals - void _playOnThread (void); - void _pauseOnThread (void); - void _setPlaybackSpeedOnThread (qreal playbackSpeed); + void logFileStats(uint32_t logDurationSecs); + void playbackStarted(); + void playbackPaused(); + void playbackAtEnd(); + void playbackPercentCompleteChanged(qreal percentComplete); + void currentLogTimeSecs(uint32_t secs); private slots: - // LinkInterface overrides - void _writeBytes(const QByteArray &bytes) override; - - void _readNextLogEntry (void); - void _play (void); - void _pause (void); - void _setPlaybackSpeed (qreal playbackSpeed); + void _writeBytes(const QByteArray &bytes) override { Q_UNUSED(bytes); } + void _play(); + void _pause(); + void _setPlaybackSpeed(qreal playbackSpeed); + void _readNextLogEntry(); private: - - // LinkInterface overrides - bool _connect(void) override; - - void _replayError (const QString& errorMsg); - quint64 _parseTimestamp (const QByteArray& bytes); - quint64 _seekToNextMavlinkMessage (mavlink_message_t* nextMsg); - quint64 _findLastTimestamp (void); - quint64 _readNextMavlinkMessage (QByteArray& bytes); - bool _loadLogFile (void); - void _finishPlayback (void); - void _resetPlaybackToBeginning (void); - void _signalCurrentLogTimeSecs (void); - - // QThread overrides - void run(void) override; - - LogReplayLinkConfiguration* _logReplayConfig; - - bool _connected; - uint8_t _mavlinkChannel; - QTimer _readTickTimer; ///< Timer which signals a read of next log record - - QString _errorTitle; ///< Title for communicatorError signals - - quint64 _logCurrentTimeUSecs; ///< The timestamp of the next message in the log file. - quint64 _logStartTimeUSecs; ///< The first timestamp in the current log file. - quint64 _logEndTimeUSecs; ///< The last timestamp in the current log file. - quint64 _logDurationUSecs; - - qreal _playbackSpeed; - quint64 _playbackStartTimeMSecs; ///< The time when the logfile was first played back. This is used to pace out replaying the messages to fix long-term drift/skew. 0 indicates that the player hasn't initiated playback of this log file. - quint64 _playbackStartLogTimeUSecs; - - MAVLinkProtocol* _mavlink; - QFile _logFile; - quint64 _logFileSize; - - static const int cbTimestamp = sizeof(quint64); + bool _connect() override; + void _replayError(const QString &errorMsg); + quint64 _parseTimestamp(const QByteArray &bytes); + quint64 _seekToNextMavlinkMessage(mavlink_message_t &nextMsg); + quint64 _findLastTimestamp(); + quint64 _readNextMavlinkMessage(QByteArray &bytes); + bool _loadLogFile(); + void _finishPlayback(); + void _resetPlaybackToBeginning(); + void _signalCurrentLogTimeSecs(); + + LogReplayLinkConfiguration *_logReplayConfig = nullptr; + QTimer *_readTickTimer = nullptr; + bool _connected = false; + uint8_t _mavlinkChannel = 0; + + quint64 _logCurrentTimeUSecs = 0; + quint64 _logStartTimeUSecs = 0; + quint64 _logEndTimeUSecs = 0; + quint64 _logDurationUSecs = 0; + + qreal _playbackSpeed = 1; + quint64 _playbackStartTimeMSecs = 0; + quint64 _playbackStartLogTimeUSecs = 0; + + QFile _logFile; + quint64 _logFileSize = 0; + + static const QString _errorTitle; + + static constexpr size_t kTimestamp = sizeof(quint64); }; +/*===========================================================================*/ + class LogReplayLinkController : public QObject { Q_OBJECT -public: - Q_PROPERTY(LogReplayLink* link READ link WRITE setLink NOTIFY linkChanged) - Q_PROPERTY(bool isPlaying READ isPlaying WRITE setIsPlaying NOTIFY isPlayingChanged) - Q_PROPERTY(qreal percentComplete READ percentComplete WRITE setPercentComplete NOTIFY percentCompleteChanged) - Q_PROPERTY(QString totalTime MEMBER _totalTime NOTIFY totalTimeChanged) - Q_PROPERTY(QString playheadTime MEMBER _playheadTime NOTIFY playheadTimeChanged) - Q_PROPERTY(qreal playbackSpeed MEMBER _playbackSpeed NOTIFY playbackSpeedChanged) - - LogReplayLinkController(void); + Q_PROPERTY(LogReplayLink *link READ link WRITE setLink NOTIFY linkChanged) + Q_PROPERTY(bool isPlaying READ isPlaying WRITE setIsPlaying NOTIFY isPlayingChanged) + Q_PROPERTY(qreal percentComplete READ percentComplete WRITE setPercentComplete NOTIFY percentCompleteChanged) + Q_PROPERTY(QString totalTime MEMBER _totalTime NOTIFY totalTimeChanged) + Q_PROPERTY(QString playheadTime MEMBER _playheadTime NOTIFY playheadTimeChanged) + Q_PROPERTY(qreal playbackSpeed MEMBER _playbackSpeed NOTIFY playbackSpeedChanged) - LogReplayLink* link (void) { return _link; } - bool isPlaying (void) const{ return _isPlaying; } - qreal percentComplete (void) const{ return _percentComplete; } +public: + explicit LogReplayLinkController(QObject *parent = nullptr); + ~LogReplayLinkController(); - void setLink (LogReplayLink* link); - void setIsPlaying (bool isPlaying); - void setPercentComplete (qreal percentComplete); + LogReplayLink *link() { return _link; } + void setLink(LogReplayLink *link); + bool isPlaying() const { return _isPlaying; } + void setIsPlaying(bool isPlaying); + qreal percentComplete() const { return _percentComplete; } + void setPercentComplete(qreal percentComplete) { _link->movePlayhead(percentComplete); } signals: - void linkChanged (LogReplayLink* link); - void isPlayingChanged (bool isPlaying); - void percentCompleteChanged (qreal percentComplete); - void playheadTimeChanged (QString playheadTime); - void totalTimeChanged (QString totalTime); - void playbackSpeedChanged (qreal playbackSpeed); + void linkChanged(LogReplayLink *link); + void isPlayingChanged(bool isPlaying); + void percentCompleteChanged(qreal percentComplete); + void playheadTimeChanged(const QString &playheadTime); + void totalTimeChanged(const QString &totalTime); + void playbackSpeedChanged(qreal playbackSpeed); private slots: - void _logFileStats (int logDurationSecs); - void _playbackStarted (void); - void _playbackPaused (void); - void _playbackAtEnd (void); - void _playbackPercentCompleteChanged (qreal percentComplete); - void _currentLogTimeSecs (int secs); - void _linkDisconnected (void); + void _logFileStats(uint32_t logDurationSecs); + void _playbackStarted(); + void _playbackPaused(); + void _playbackAtEnd(); + void _playbackPercentCompleteChanged(qreal percentComplete); + void _currentLogTimeSecs(uint32_t secs); + void _linkDisconnected() { setLink(nullptr); } private: - QString _secondsToHMS(int seconds); - - LogReplayLink* _link; - bool _isPlaying; - qreal _percentComplete; - int _playheadSecs; - QString _playheadTime; - QString _totalTime; - qreal _playbackSpeed; + static QString _secondsToHMS(uint32_t seconds); + + bool _isPlaying = false; + qreal _percentComplete = 0; + uint32_t _playheadSecs = 0; + qreal _playbackSpeed = 1; + QString _playheadTime; + QString _totalTime; + LogReplayLink *_link = nullptr; }; -