QGCMAVLinkLogPlayer.h 4.16 KB
Newer Older
1 2 3 4 5 6 7
#ifndef QGCMAVLINKLOGPLAYER_H
#define QGCMAVLINKLOGPLAYER_H

#include <QWidget>
#include <QFile>

#include "MAVLinkProtocol.h"
8
#include "LinkInterface.h"
9
#include "MAVLinkSimulationLink.h"
10

11 12 13
namespace Ui
{
class QGCMAVLinkLogPlayer;
14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29
}

/**
 * @brief Replays MAVLink log files
 *
 * This class allows to replay MAVLink logs at varying speeds.
 * captured flights can be replayed, shown to others and analyzed
 * in-depth later on.
 */
class QGCMAVLinkLogPlayer : public QWidget
{
    Q_OBJECT

public:
    explicit QGCMAVLinkLogPlayer(MAVLinkProtocol* mavlink, QWidget *parent = 0);
    ~QGCMAVLinkLogPlayer();
30 31 32 33 34 35 36 37 38
    bool isPlayingLogFile()
    {
        return isPlaying;
    }

    bool isLogFileSelected()
    {
        return logFile.isOpen();
    }
39 40

public slots:
lm's avatar
lm committed
41 42
    /** @brief Toggle between play and pause */
    void playPauseToggle();
43 44
    /** @brief Replay the logfile */
    void play();
45
    /** @brief Pause the log player. */
46
    void pause();
47 48
    /** @brief Reset the internal log player state, including the UI */
    void reset();
49
    /** @brief Load log file */
50
    bool loadLogFile(const QString& file);
51 52
    /** @brief Jump to a position in the logfile */
    void jumpToSliderVal(int slidervalue);
53 54 55 56
    /** @brief The logging mainloop */
    void logLoop();
    /** @brief Set acceleration factor in percent */
    void setAccelerationFactorInt(int factor);
57

58 59 60
signals:
    /** @brief Send ready bytes */
    void bytesReady(LinkInterface* link, const QByteArray& bytes);
61
    void logFileEndReached();
62

63
protected:
64 65 66 67
    quint64 playbackStartTime;     ///< 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. In units of milliseconds since epoch UTC.
    quint64 logCurrentTime;        ///< The timestamp of the next message in the log file. In units of microseconds since epoch UTC.
    quint64 logStartTime;          ///< The first timestamp in the current log file. In units of microseconds since epoch UTC.
    quint64 logEndTime;            ///< The last timestamp in the current log file. In units of microseconds since epoch UTC.
68
    float accelerationFactor;
69
    MAVLinkProtocol* mavlink;
70
    MAVLinkSimulationLink* logLink;
71 72
    QFile logFile;
    QTimer loopTimer;
73
    int loopCounter;
74
    bool mavlinkLogFormat; ///< If the logfile is stored in the timestamped MAVLink log format
75
    int binaryBaudRate;
76
    static const int defaultBinaryBaudRate = 57600;
lm's avatar
lm committed
77
    bool isPlaying;
78
    unsigned int currPacketCount;
79 80
    static const int packetLen = MAVLINK_MAX_PACKET_LEN;
    static const int timeLen = sizeof(quint64);
81
    void changeEvent(QEvent *e);
Don Gagne's avatar
Don Gagne committed
82 83 84
    
private slots:
    void _selectLogFileForPlayback(void);
Lorenz Meier's avatar
Lorenz Meier committed
85

86 87
private:
    Ui::QGCMAVLinkLogPlayer *ui;
88
	virtual void paintEvent(QPaintEvent *);
89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117

    /** @brief Parse out a quint64 timestamp in microseconds in the proper endianness. */
    quint64 parseTimestamp(const QByteArray &data);

    /**
     * This function parses out the next MAVLink message and its corresponding timestamp.
     *
     * It makes no assumptions about where in the file we currently are. It leaves the file right
     * at the beginning of the successfully parsed message. Note that this function will not attempt to
     * correct for any MAVLink parsing failures, so it always returns the next successfully-parsed
     * message.
     *
     * @param msg[output] Where the final parsed message output will go.
     * @return A Unix timestamp in microseconds UTC or 0 if parsing failed
     */
    quint64 findNextMavlinkMessage(mavlink_message_t *msg);

    /**
     * Updates the QSlider UI to be at the given percentage.
     * @param percent A percentage value between 0.0% and 100.0%.
     */
    void updatePositionSliderUi(float percent);

    /**
     * Jumps to a new position in the current playback file as a percentage.
     * @param percentage The position of the file to jump to as a percentage.
     * @return True if the new file position was successfully jumped to, false otherwise
     */
    bool jumpToPlaybackLocation(float percentage);
Don Gagne's avatar
Don Gagne committed
118 119 120
    
    void _finishPlayback(void);
    void _playbackError(void);
121 122 123
};

#endif // QGCMAVLINKLOGPLAYER_H