You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
96 lines
2.3 KiB
96 lines
2.3 KiB
#ifndef QGCMAVLINKLOGPLAYER_H |
|
#define QGCMAVLINKLOGPLAYER_H |
|
|
|
#include <QWidget> |
|
#include <QFile> |
|
|
|
#include "MAVLinkProtocol.h" |
|
#include "LinkInterface.h" |
|
#include "MAVLinkSimulationLink.h" |
|
|
|
namespace Ui |
|
{ |
|
class QGCMAVLinkLogPlayer; |
|
} |
|
|
|
/** |
|
* @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(); |
|
bool isPlayingLogFile() |
|
{ |
|
return isPlaying; |
|
} |
|
|
|
bool isLogFileSelected() |
|
{ |
|
return logFile.isOpen(); |
|
} |
|
|
|
public slots: |
|
/** @brief Toggle between play and pause */ |
|
void playPauseToggle(); |
|
/** @brief Play / pause the log */ |
|
void playPause(bool play); |
|
/** @brief Replay the logfile */ |
|
void play(); |
|
/** @brief Pause the logfile */ |
|
void pause(); |
|
/** @brief Reset the logfile */ |
|
bool reset(int packetIndex=0); |
|
/** @brief Select logfile */ |
|
bool selectLogFile(const QString startDirectory); |
|
/** @brief Select logfile */ |
|
bool selectLogFile(); |
|
/** @brief Load log file */ |
|
bool loadLogFile(const QString& file); |
|
/** @brief Jump to a position in the logfile */ |
|
void jumpToSliderVal(int slidervalue); |
|
/** @brief The logging mainloop */ |
|
void logLoop(); |
|
/** @brief Set acceleration factor in percent */ |
|
void setAccelerationFactorInt(int factor); |
|
|
|
signals: |
|
/** @brief Send ready bytes */ |
|
void bytesReady(LinkInterface* link, const QByteArray& bytes); |
|
|
|
protected: |
|
int lineCounter; |
|
int totalLines; |
|
quint64 startTime; |
|
quint64 endTime; |
|
quint64 currentStartTime; |
|
float accelerationFactor; |
|
MAVLinkProtocol* mavlink; |
|
MAVLinkSimulationLink* logLink; |
|
QFile logFile; |
|
QTimer loopTimer; |
|
int loopCounter; |
|
bool mavlinkLogFormat; |
|
int binaryBaudRate; |
|
bool isPlaying; |
|
unsigned int currPacketCount; |
|
static const int packetLen = MAVLINK_MAX_PACKET_LEN; |
|
static const int timeLen = sizeof(quint64); |
|
QString lastLogDirectory; |
|
void changeEvent(QEvent *e); |
|
|
|
void loadSettings(); |
|
void storeSettings(); |
|
|
|
private: |
|
Ui::QGCMAVLinkLogPlayer *ui; |
|
}; |
|
|
|
#endif // QGCMAVLINKLOGPLAYER_H
|
|
|