8#include <QtQmlIntegration/QtQmlIntegration>
30 void loadSettings(QSettings &settings,
const QString &root)
override;
31 void saveSettings(QSettings &settings,
const QString &root)
const override;
32 QString
settingsURL()
const override {
return QStringLiteral(
"LogReplaySettings.qml"); }
33 QString
settingsTitle()
const override {
return tr(
"Log Replay Link Settings"); }
81 void _readNextLogEntry();
84 quint64 _parseTimestamp(
const QByteArray &bytes);
86 quint64 _findLastTimestamp();
87 quint64 _readNextMavlinkMessage(QByteArray &bytes);
89 void _resetPlaybackToBeginning();
90 void _signalCurrentLogTimeSecs();
93 QTimer *_readTickTimer =
nullptr;
95 bool _isConnected =
false;
96 uint8_t _mavlinkChannel = 0;
98 quint64 _logCurrentTimeUSecs = 0;
99 quint64 _logStartTimeUSecs = 0;
100 quint64 _logEndTimeUSecs = 0;
101 quint64 _logDurationUSecs = 0;
103 qreal _playbackSpeed = 1;
104 quint64 _playbackStartTimeMSecs = 0;
105 quint64 _playbackStartLogTimeUSecs = 0;
108 quint64 _logFileSize = 0;
110 static constexpr size_t kTimestamp =
sizeof(quint64);
142 void _writeBytes(
const QByteArray &bytes)
override { Q_UNUSED(bytes); }
144 void _onDisconnected();
146 void _onDataReceived(
const QByteArray &data);
149 bool _connect()
override;
153 QThread *_workerThread =
nullptr;
154 std::atomic<bool> _disconnectedEmitted{
false};
std::shared_ptr< LinkConfiguration > SharedLinkConfigurationPtr
struct __mavlink_message mavlink_message_t
Interface holding link specific settings.
The link interface defines the interface for all links used to communicate with the ground station ap...
QString logFilenameShort() const
QString settingsURL() const override
Settings URL, Pure virtual method providing the URL for the (QML) settings dialog.
LinkType type() const override
QString settingsTitle() const override
Settings Title, Pure virtual method providing the Title for the (QML) settings dialog.
void copyFrom(const LinkConfiguration *source) override
void saveSettings(QSettings &settings, const QString &root) const override
void loadSettings(QSettings &settings, const QString &root) override
virtual ~LogReplayConfiguration()
QString logFilename() const
void setLogFilename(const QString &logFilename)
bool isLogReplay() const final
void disconnect() override
bool isConnected() const override
void playbackPercentCompleteChanged(qreal percentComplete)
void logFileStats(uint32_t logDurationSecs)
void currentLogTimeSecs(uint32_t secs)
void setPlaybackSpeed(qreal playbackSpeed)
void movePlayhead(qreal percentComplete)
void currentLogTimeSecs(uint32_t secs)
void dataReceived(const QByteArray &data)
void setPlaybackSpeed(qreal playbackSpeed)
void logFileStats(uint32_t logDurationSecs)
void errorOccurred(const QString &errorString)
void movePlayhead(qreal percentComplete)
void playbackPercentCompleteChanged(qreal percentComplete)