LogReplayLink.h 7.52 KB
Newer Older
1 2
/****************************************************************************
 *
3
 *   (c) 2009-2018 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

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; }
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          ();
39
    QString     settingsURL             () { return "LogReplaySettings.qml"; }
40
    QString     settingsTitle           () { return tr("Log Replay Link Settings"); }
41

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

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

class LogReplayLink : public LinkInterface
{
    Q_OBJECT

    friend class LinkManager;
55

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

Don Gagne's avatar
Don Gagne committed
60 61
    /// Start replay at current position
    void play(void) { emit _playOnThread(); }
62

Don Gagne's avatar
Don Gagne committed
63 64
    /// Pause replay
    void pause(void) { emit _pauseOnThread(); }
65

Don Gagne's avatar
Don Gagne committed
66
    /// Move the playhead to the specified percent complete
67
    void movePlayhead(qreal percentComplete);
68

Don Gagne's avatar
Don Gagne committed
69 70
    /// Sets the acceleration factor: -100: 0.01X, 0: 1.0X, 100: 100.0X
    void setAccelerationFactor(int factor) { emit _setAccelerationFactorOnThread(factor); }
71

Don Gagne's avatar
Don Gagne committed
72 73 74 75 76 77 78 79 80 81 82 83 84
    // Virtuals from LinkInterface
    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; }

    // 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.
    bool connect(void);
    bool disconnect(void);

85
private slots:
86
    virtual void _writeBytes(const QByteArray bytes);
87

Don Gagne's avatar
Don Gagne committed
88 89 90 91 92
signals:
    void logFileStats(bool logTimestamped, int logDurationSecs, int binaryBaudRate);
    void playbackStarted(void);
    void playbackPaused(void);
    void playbackAtEnd(void);
93
    void playbackPercentCompleteChanged(qreal percentComplete);
94
    void currentLogTimeSecs(int secs);
95

Don Gagne's avatar
Don Gagne committed
96 97 98 99 100 101 102 103 104 105 106 107 108
    // Internal signals
    void _playOnThread(void);
    void _pauseOnThread(void);
    void _setAccelerationFactorOnThread(int factor);

private slots:
    void _readNextLogEntry(void);
    void _play(void);
    void _pause(void);
    void _setAccelerationFactor(int factor);

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

Don Gagne's avatar
Don Gagne committed
112 113 114
    void _replayError(const QString& errorMsg);
    quint64 _parseTimestamp(const QByteArray& bytes);
    quint64 _seekToNextMavlinkMessage(mavlink_message_t* nextMsg);
Don Gagne's avatar
Don Gagne committed
115
    quint64 _readNextMavlinkMessage(QByteArray& bytes);
Don Gagne's avatar
Don Gagne committed
116 117 118
    bool _loadLogFile(void);
    void _finishPlayback(void);
    void _resetPlaybackToBeginning(void);
119
    void _signalCurrentLogTimeSecs(void);
120

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

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

128
    LogReplayLinkConfiguration* _logReplayConfig;
Don Gagne's avatar
Don Gagne committed
129 130

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

134
    QString _errorTitle; ///< Title for communicatorError signals
135

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

Don Gagne's avatar
Don Gagne committed
141 142
    static const int    _defaultBinaryBaudRate = 57600;
    int                 _binaryBaudRate;        ///< Playback rate for binary log format
143

Don Gagne's avatar
Don Gagne committed
144 145
    float   _replayAccelerationFactor;  ///< Factor to apply to playback rate
    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.
146

Don Gagne's avatar
Don Gagne committed
147 148 149 150
    MAVLinkProtocol*    _mavlink;
    QFile               _logFile;
    quint64             _logFileSize;
    bool                _logTimestamped;    ///< true: Timestamped log format, false: no timestamps
151

Don Gagne's avatar
Don Gagne committed
152 153 154
    static const int cbTimestamp = sizeof(quint64);
};

155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202
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)

    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);

private slots:
    void _logFileStats                   (bool logTimestamped, int logDurationSecs, int binaryBaudRate);
    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;
};