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#include "QGCMAVLinkTypes.h"
6
7#include <QtCore/QFile>
8#include <QtQmlIntegration/QtQmlIntegration>
9
10#include <atomic>
11
12class QTimer;
13
14/*===========================================================================*/
15
17{
18 Q_OBJECT
19 QML_ELEMENT
20 QML_UNCREATABLE("")
21 Q_PROPERTY(QString filename READ logFilename WRITE setLogFilename NOTIFY filenameChanged)
22
23public:
24 explicit LogReplayConfiguration(const QString &name, QObject *parent = nullptr);
25 explicit LogReplayConfiguration(const LogReplayConfiguration *copy, QObject *parent = nullptr);
27
28 LinkType type() const override { return LinkConfiguration::TypeLogReplay; }
29 void copyFrom(const LinkConfiguration *source) override;
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"); }
34
35 QString logFilenameShort() const;
36 QString logFilename() const { return _logFilename; }
37 void setLogFilename(const QString &logFilename);
38
39signals:
41
42private:
43 QString _logFilename;
44};
45
46/*===========================================================================*/
47
48class LogReplayWorker : public QObject
49{
50 Q_OBJECT
51
52public:
53 explicit LogReplayWorker(const LogReplayConfiguration *config, QObject *parent = nullptr);
55
56 bool isConnected() const { return _isConnected; }
57 bool isPlaying() const;
58
59signals:
60 void connected();
62 void errorOccurred(const QString &errorString);
63 void dataReceived(const QByteArray &data);
64 void logFileStats(uint32_t logDurationSecs);
68 void playbackPercentCompleteChanged(qreal percentComplete);
69 void currentLogTimeSecs(uint32_t secs);
70
71public slots:
72 void setup();
73 void connectToLog();
74 void disconnectFromLog();
75 void play();
76 void pause();
77 void setPlaybackSpeed(qreal playbackSpeed);
78 void movePlayhead(qreal percentComplete);
79
80private slots:
81 void _readNextLogEntry();
82
83private:
84 quint64 _parseTimestamp(const QByteArray &bytes);
85 quint64 _seekToNextMavlinkMessage(mavlink_message_t &nextMsg);
86 quint64 _findLastTimestamp();
87 quint64 _readNextMavlinkMessage(QByteArray &bytes);
88 bool _loadLogFile();
89 void _resetPlaybackToBeginning();
90 void _signalCurrentLogTimeSecs();
91
92 const LogReplayConfiguration *_logReplayConfig = nullptr;
93 QTimer *_readTickTimer = nullptr;
94
95 bool _isConnected = false;
96 uint8_t _mavlinkChannel = 0;
97
98 quint64 _logCurrentTimeUSecs = 0;
99 quint64 _logStartTimeUSecs = 0;
100 quint64 _logEndTimeUSecs = 0;
101 quint64 _logDurationUSecs = 0;
102
103 qreal _playbackSpeed = 1;
104 quint64 _playbackStartTimeMSecs = 0;
105 quint64 _playbackStartLogTimeUSecs = 0;
106
107 QFile _logFile;
108 quint64 _logFileSize = 0;
109
110 static constexpr size_t kTimestamp = sizeof(quint64);
111};
112
113/*===========================================================================*/
114
116{
117 Q_OBJECT
118
119public:
120 explicit LogReplayLink(SharedLinkConfigurationPtr &config, QObject *parent = nullptr);
121 virtual ~LogReplayLink();
122
123 bool isConnected() const override;
124 void disconnect() override;
125 bool isLogReplay() const final { return true; }
126
127 bool isPlaying() const;
128 void play();
129 void pause();
130 void setPlaybackSpeed(qreal playbackSpeed);
131 void movePlayhead(qreal percentComplete);
132
133signals:
134 void logFileStats(uint32_t logDurationSecs);
138 void playbackPercentCompleteChanged(qreal percentComplete);
139 void currentLogTimeSecs(uint32_t secs);
140
141private slots:
142 void _writeBytes(const QByteArray &bytes) override { Q_UNUSED(bytes); }
143 void _onConnected();
144 void _onDisconnected();
145 void _onErrorOccurred(const QString &errorString);
146 void _onDataReceived(const QByteArray &data);
147
148private:
149 bool _connect() override;
150
151 const LogReplayConfiguration *_logReplayConfig = nullptr;
152 LogReplayWorker *_worker = nullptr;
153 QThread *_workerThread = nullptr;
154 std::atomic<bool> _disconnectedEmitted{false};
155};
std::shared_ptr< LinkConfiguration > SharedLinkConfigurationPtr
QString errorString
struct __mavlink_message mavlink_message_t
Interface holding link specific settings.
QString name() const
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)
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)