7#include <QtCore/QLoggingCategory>
8#include <QtQmlIntegration/QtQmlIntegration>
25 Q_PROPERTY(QString filename READ logFilename WRITE setLogFilename NOTIFY filenameChanged)
32 LinkType type()
const override {
return LinkConfiguration::TypeLogReplay; }
34 void loadSettings(QSettings &settings,
const QString &root)
override;
35 void saveSettings(QSettings &settings,
const QString &root)
const override;
36 QString settingsURL()
const override {
return QStringLiteral(
"LogReplaySettings.qml"); }
37 QString settingsTitle()
const override {
return tr(
"Log Replay Link Settings"); }
39 QString logFilenameShort()
const;
40 QString logFilename()
const {
return _logFilename; }
41 void setLogFilename(
const QString &logFilename);
85 void _readNextLogEntry();
88 quint64 _parseTimestamp(
const QByteArray &bytes);
90 quint64 _findLastTimestamp();
91 quint64 _readNextMavlinkMessage(QByteArray &bytes);
93 void _resetPlaybackToBeginning();
94 void _signalCurrentLogTimeSecs();
97 QTimer *_readTickTimer =
nullptr;
99 bool _isConnected =
false;
100 uint8_t _mavlinkChannel = 0;
102 quint64 _logCurrentTimeUSecs = 0;
103 quint64 _logStartTimeUSecs = 0;
104 quint64 _logEndTimeUSecs = 0;
105 quint64 _logDurationUSecs = 0;
107 qreal _playbackSpeed = 1;
108 quint64 _playbackStartTimeMSecs = 0;
109 quint64 _playbackStartLogTimeUSecs = 0;
112 quint64 _logFileSize = 0;
114 static constexpr size_t kTimestamp =
sizeof(quint64);
146 void _writeBytes(
const QByteArray &bytes)
override { Q_UNUSED(bytes); }
148 void _onDisconnected();
150 void _onDataReceived(
const QByteArray &data);
153 bool _connect()
override;
157 QThread *_workerThread =
nullptr;
158 std::atomic<bool> _disconnectedEmitted{
false};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
std::shared_ptr< LinkConfiguration > SharedLinkConfigurationPtr
struct __mavlink_message mavlink_message_t
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...
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)