LogReplayLink.h 7.74 KB
Newer Older
1
2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4
5
6
7
8
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/
Don Gagne's avatar
Don Gagne committed
9

10
#pragma once
Don Gagne's avatar
Don Gagne committed
11

Don Gagne's avatar
   
Don Gagne committed
12
#include "LinkManager.h"
Don Gagne's avatar
Don Gagne committed
13
14
15
16
17
18
19
#include "MAVLinkProtocol.h"

#include <QTimer>
#include <QFile>

class LogReplayLinkConfiguration : public LinkConfiguration
{
Don Gagne's avatar
Don Gagne committed
20
21
    Q_OBJECT

Don Gagne's avatar
Don Gagne committed
22
public:
23
24
    Q_PROPERTY(QString  fileName    READ logFilename    WRITE setLogFilename    NOTIFY fileNameChanged)

Don Gagne's avatar
Don Gagne committed
25
26
    LogReplayLinkConfiguration(const QString& name);
    LogReplayLinkConfiguration(LogReplayLinkConfiguration* copy);
27

Don Gagne's avatar
Don Gagne committed
28
    QString logFilename(void) { return _logFilename; }
dogmaphobic's avatar
dogmaphobic committed
29
    void setLogFilename(const QString logFilename) { _logFilename = logFilename; emit fileNameChanged(); }
30

Don Gagne's avatar
Don Gagne committed
31
32
33
    QString logFilenameShort(void);

    // Virtuals from LinkConfiguration
34
35
36
37
38
    LinkType    type                    () { return LinkConfiguration::TypeLogReplay; }
    void        copyFrom                (LinkConfiguration* source);
    void        loadSettings            (QSettings& settings, const QString& root);
    void        saveSettings            (QSettings& settings, const QString& root);
    void        updateSettings          ();
dogmaphobic's avatar
dogmaphobic committed
39
    QString     settingsURL             () { return "LogReplaySettings.qml"; }
Gus Grubba's avatar
Gus Grubba committed
40
    QString     settingsTitle           () { return tr("Log Replay Link Settings"); }
Don Gagne's avatar
   
Don Gagne committed
41

42
43
signals:
    void fileNameChanged();
Don Gagne's avatar
Don Gagne committed
44
45
46
47
48
49

private:
    static const char*  _logFilenameKey;
    QString             _logFilename;
};

50
/// Pseudo link that reads a telemetry log and feeds it into the application.
Don Gagne's avatar
Don Gagne committed
51
52
53
54
55
class LogReplayLink : public LinkInterface
{
    Q_OBJECT

    friend class LinkManager;
56

Don Gagne's avatar
Don Gagne committed
57
58
59
public:
    /// @return true: log is currently playing, false: log playback is paused
    bool isPlaying(void) { return _readTickTimer.isActive(); }
60

Don Gagne's avatar
   
Don Gagne committed
61
62
63
    void play           (void) { emit _playOnThread(); }
    void pause          (void) { emit _pauseOnThread(); }
    void movePlayhead   (qreal percentComplete);
64

Don Gagne's avatar
Don Gagne committed
65
    // Virtuals from LinkInterface
Don Gagne's avatar
   
Don Gagne committed
66
67
68
69
70
71
    virtual QString getName             (void) const { return _config->name(); }
    virtual void    requestReset        (void){ }
    virtual bool    isConnected         (void) const { return _connected; }
    virtual qint64  getConnectionSpeed  (void) const { return 100000000; }
    virtual qint64  bytesAvailable      (void) { return 0; }
    virtual bool    isLogReplay         (void) { return true; }
Don Gagne's avatar
Don Gagne committed
72
73
74

    // These are left unimplemented in order to cause linker errors which indicate incorrect usage of
    // connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager.
Don Gagne's avatar
   
Don Gagne committed
75
76
77
78
79
80
    bool connect    (void);
    bool disconnect (void);

public slots:
    /// Sets the acceleration factor: -100: 0.01X, 0: 1.0X, 100: 100.0X
    void setPlaybackSpeed(qreal playbackSpeed) { emit _setPlaybackSpeedOnThread(playbackSpeed); }
Don Gagne's avatar
Don Gagne committed
81

82
private slots:
83
    virtual void _writeBytes(const QByteArray bytes);
84

Don Gagne's avatar
Don Gagne committed
85
signals:
Don Gagne's avatar
   
Don Gagne committed
86
87
88
89
90
91
    void logFileStats                   (int logDurationSecs);
    void playbackStarted                (void);
    void playbackPaused                 (void);
    void playbackAtEnd                  (void);
    void playbackPercentCompleteChanged (qreal percentComplete);
    void currentLogTimeSecs             (int secs);
92

Don Gagne's avatar
Don Gagne committed
93
    // Internal signals
Don Gagne's avatar
   
Don Gagne committed
94
95
96
    void _playOnThread              (void);
    void _pauseOnThread             (void);
    void _setPlaybackSpeedOnThread  (qreal playbackSpeed);
Don Gagne's avatar
Don Gagne committed
97
98

private slots:
Don Gagne's avatar
   
Don Gagne committed
99
100
101
102
    void _readNextLogEntry  (void);
    void _play              (void);
    void _pause             (void);
    void _setPlaybackSpeed  (qreal playbackSpeed);
Don Gagne's avatar
Don Gagne committed
103
104
105

private:
    // Links are only created/destroyed by LinkManager so constructor/destructor is not public
106
    LogReplayLink(SharedLinkConfigurationPointer& config);
Don Gagne's avatar
Don Gagne committed
107
    ~LogReplayLink();
108

Don Gagne's avatar
   
Don Gagne committed
109
110
111
112
113
114
115
116
117
    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);
118

Don Gagne's avatar
Don Gagne committed
119
    // Virtuals from LinkInterface
Don Gagne's avatar
   
Don Gagne committed
120
    virtual bool _connect   (void);
Don Gagne's avatar
Don Gagne committed
121
    virtual void _disconnect(void);
122

Don Gagne's avatar
Don Gagne committed
123
124
    // Virtuals from QThread
    virtual void run(void);
125

126
    LogReplayLinkConfiguration* _logReplayConfig;
Don Gagne's avatar
Don Gagne committed
127
128

    bool    _connected;
Don Gagne's avatar
   
Don Gagne committed
129
    uint8_t _mavlinkChannel;
Don Gagne's avatar
Don Gagne committed
130
    QTimer  _readTickTimer;      ///< Timer which signals a read of next log record
131

DonLakeFlyer's avatar
DonLakeFlyer committed
132
    QString _errorTitle; ///< Title for communicatorError signals
133

Don Gagne's avatar
Don Gagne committed
134
135
136
137
    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;
138

Don Gagne's avatar
   
Don Gagne committed
139
    qreal   _playbackSpeed;
Don Gagne's avatar
Don Gagne committed
140
    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.
Don Gagne's avatar
   
Don Gagne committed
141
    quint64 _playbackStartLogTimeUSecs;
142

Don Gagne's avatar
Don Gagne committed
143
144
145
    MAVLinkProtocol*    _mavlink;
    QFile               _logFile;
    quint64             _logFileSize;
146

Don Gagne's avatar
Don Gagne committed
147
148
149
    static const int cbTimestamp = sizeof(quint64);
};

Don Gagne's avatar
   
Don Gagne committed
150
151
152
153
154
155
156
157
158
159
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)
Don Gagne's avatar
   
Don Gagne committed
160
    Q_PROPERTY(qreal            playbackSpeed   MEMBER _playbackSpeed                               NOTIFY playbackSpeedChanged)
Don Gagne's avatar
   
Don Gagne committed
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177

    LogReplayLinkController(void);

    LogReplayLink*  link            (void) { return _link; }
    bool            isPlaying       (void) { return _isPlaying; }
    qreal           percentComplete (void) { return _percentComplete; }

    void setLink            (LogReplayLink* link);
    void setIsPlaying       (bool isPlaying);
    void setPercentComplete (qreal percentComplete);

signals:
    void linkChanged            (LogReplayLink* link);
    void isPlayingChanged       (bool isPlaying);
    void percentCompleteChanged (qreal percentComplete);
    void playheadTimeChanged    (QString playheadTime);
    void totalTimeChanged       (QString totalTime);
Don Gagne's avatar
   
Don Gagne committed
178
    void playbackSpeedChanged   (qreal playbackSpeed);
Don Gagne's avatar
   
Don Gagne committed
179
180

private slots:
Don Gagne's avatar
   
Don Gagne committed
181
    void _logFileStats                   (int logDurationSecs);
Don Gagne's avatar
   
Don Gagne committed
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
    void _playbackStarted                (void);
    void _playbackPaused                 (void);
    void _playbackAtEnd                  (void);
    void _playbackPercentCompleteChanged (qreal percentComplete);
    void _currentLogTimeSecs             (int secs);
    void _linkDisconnected               (void);

private:
    QString _secondsToHMS(int seconds);

    LogReplayLink*  _link;
    bool            _isPlaying;
    qreal           _percentComplete;
    int             _playheadSecs;
    QString         _playheadTime;
    QString         _totalTime;
Don Gagne's avatar
   
Don Gagne committed
198
    qreal           _playbackSpeed;
Don Gagne's avatar
   
Don Gagne committed
199
200
};