QGCMAVLinkLogPlayer.h 2.15 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 43 44
    /** @brief Toggle between play and pause */
    void playPauseToggle();
    /** @brief Play / pause the log */
    void playPause(bool play);
45 46 47 48
    /** @brief Replay the logfile */
    void play();
    /** @brief Pause the logfile */
    void pause();
49
    /** @brief Reset the logfile */
50
    bool reset(int packetIndex=0);
51
    /** @brief Select logfile */
52
    bool selectLogFile();
53
    /** @brief Load log file */
54
    bool loadLogFile(const QString& file);
55 56
    /** @brief Jump to a position in the logfile */
    void jumpToSliderVal(int slidervalue);
57 58 59 60
    /** @brief The logging mainloop */
    void logLoop();
    /** @brief Set acceleration factor in percent */
    void setAccelerationFactorInt(int factor);
61

62 63 64 65
signals:
    /** @brief Send ready bytes */
    void bytesReady(LinkInterface* link, const QByteArray& bytes);

66 67 68 69 70
protected:
    int lineCounter;
    int totalLines;
    quint64 startTime;
    quint64 endTime;
71 72
    quint64 currentStartTime;
    float accelerationFactor;
73
    MAVLinkProtocol* mavlink;
74
    MAVLinkSimulationLink* logLink;
75 76
    QFile logFile;
    QTimer loopTimer;
77
    int loopCounter;
78 79
    bool mavlinkLogFormat;
    int binaryBaudRate;
lm's avatar
lm committed
80
    bool isPlaying;
81
    unsigned int currPacketCount;
82 83
    static const int packetLen = MAVLINK_MAX_PACKET_LEN;
    static const int timeLen = sizeof(quint64);
84 85 86 87 88 89 90
    void changeEvent(QEvent *e);

private:
    Ui::QGCMAVLinkLogPlayer *ui;
};

#endif // QGCMAVLINKLOGPLAYER_H