QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
LogReplayLink.h
Go to the documentation of this file.
1#pragma once
2
3#include "LinkConfiguration.h"
4#include "LinkInterface.h"
5
6#include <QtCore/QFile>
7#include <QtCore/QLoggingCategory>
8#include <QtQmlIntegration/QtQmlIntegration>
9
10#include <atomic>
11
12class QTimer;
13
14typedef struct __mavlink_message mavlink_message_t;
15
16Q_DECLARE_LOGGING_CATEGORY(LogReplayLinkLog)
17
18/*===========================================================================*/
19
21{
22 Q_OBJECT
23 QML_ELEMENT
24 QML_UNCREATABLE("")
25 Q_PROPERTY(QString filename READ logFilename WRITE setLogFilename NOTIFY filenameChanged)
26
27public:
28 explicit LogReplayConfiguration(const QString &name, QObject *parent = nullptr);
29 explicit LogReplayConfiguration(const LogReplayConfiguration *copy, QObject *parent = nullptr);
31
32 LinkType type() const override { return LinkConfiguration::TypeLogReplay; }
33 void copyFrom(const LinkConfiguration *source) override;
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"); }
38
39 QString logFilenameShort() const;
40 QString logFilename() const { return _logFilename; }
41 void setLogFilename(const QString &logFilename);
42
43signals:
45
46private:
47 QString _logFilename;
48};
49
50/*===========================================================================*/
51
52class LogReplayWorker : public QObject
53{
54 Q_OBJECT
55
56public:
57 explicit LogReplayWorker(const LogReplayConfiguration *config, QObject *parent = nullptr);
59
60 bool isConnected() const { return _isConnected; }
61 bool isPlaying() const;
62
63signals:
64 void connected();
66 void errorOccurred(const QString &errorString);
67 void dataReceived(const QByteArray &data);
68 void logFileStats(uint32_t logDurationSecs);
72 void playbackPercentCompleteChanged(qreal percentComplete);
73 void currentLogTimeSecs(uint32_t secs);
74
75public slots:
76 void setup();
77 void connectToLog();
78 void disconnectFromLog();
79 void play();
80 void pause();
81 void setPlaybackSpeed(qreal playbackSpeed);
82 void movePlayhead(qreal percentComplete);
83
84private slots:
85 void _readNextLogEntry();
86
87private:
88 quint64 _parseTimestamp(const QByteArray &bytes);
89 quint64 _seekToNextMavlinkMessage(mavlink_message_t &nextMsg);
90 quint64 _findLastTimestamp();
91 quint64 _readNextMavlinkMessage(QByteArray &bytes);
92 bool _loadLogFile();
93 void _resetPlaybackToBeginning();
94 void _signalCurrentLogTimeSecs();
95
96 const LogReplayConfiguration *_logReplayConfig = nullptr;
97 QTimer *_readTickTimer = nullptr;
98
99 bool _isConnected = false;
100 uint8_t _mavlinkChannel = 0;
101
102 quint64 _logCurrentTimeUSecs = 0;
103 quint64 _logStartTimeUSecs = 0;
104 quint64 _logEndTimeUSecs = 0;
105 quint64 _logDurationUSecs = 0;
106
107 qreal _playbackSpeed = 1;
108 quint64 _playbackStartTimeMSecs = 0;
109 quint64 _playbackStartLogTimeUSecs = 0;
110
111 QFile _logFile;
112 quint64 _logFileSize = 0;
113
114 static constexpr size_t kTimestamp = sizeof(quint64);
115};
116
117/*===========================================================================*/
118
120{
121 Q_OBJECT
122
123public:
124 explicit LogReplayLink(SharedLinkConfigurationPtr &config, QObject *parent = nullptr);
125 virtual ~LogReplayLink();
126
127 bool isConnected() const override;
128 void disconnect() override;
129 bool isLogReplay() const final { return true; }
130
131 bool isPlaying() const;
132 void play();
133 void pause();
134 void setPlaybackSpeed(qreal playbackSpeed);
135 void movePlayhead(qreal percentComplete);
136
137signals:
138 void logFileStats(uint32_t logDurationSecs);
142 void playbackPercentCompleteChanged(qreal percentComplete);
143 void currentLogTimeSecs(uint32_t secs);
144
145private slots:
146 void _writeBytes(const QByteArray &bytes) override { Q_UNUSED(bytes); }
147 void _onConnected();
148 void _onDisconnected();
149 void _onErrorOccurred(const QString &errorString);
150 void _onDataReceived(const QByteArray &data);
151
152private:
153 bool _connect() override;
154
155 const LogReplayConfiguration *_logReplayConfig = nullptr;
156 LogReplayWorker *_worker = nullptr;
157 QThread *_workerThread = nullptr;
158 std::atomic<bool> _disconnectedEmitted{false};
159};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
std::shared_ptr< LinkConfiguration > SharedLinkConfigurationPtr
QString errorString
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...
void currentLogTimeSecs(uint32_t secs)
void dataReceived(const QByteArray &data)
void setPlaybackSpeed(qreal playbackSpeed)
void logFileStats(uint32_t logDurationSecs)
void errorOccurred(const QString &errorString)
bool isPlaying() const
void movePlayhead(qreal percentComplete)
void playbackPaused()
bool isConnected() const
void playbackAtEnd()
void playbackStarted()
void playbackPercentCompleteChanged(qreal percentComplete)