MAVLinkDecoder.h 2.64 KB
Newer Older
lm's avatar
lm committed
1 2 3 4 5 6 7 8 9 10 11 12 13 14
#ifndef MAVLINKDECODER_H
#define MAVLINKDECODER_H

#include <QObject>
#include "MAVLinkProtocol.h"

class MAVLinkDecoder : public QObject
{
    Q_OBJECT
public:
    MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent = 0);

signals:
    void textMessageReceived(int uasid, int componentid, int severity, const QString& text);
15 16 17 18 19 20
    void valueChanged(const int uasId, const QString& name, const QString& unit, const quint8 value, const quint64 msec);
    void valueChanged(const int uasId, const QString& name, const QString& unit, const qint8 value, const quint64 msec);
    void valueChanged(const int uasId, const QString& name, const QString& unit, const quint16 value, const quint64 msec);
    void valueChanged(const int uasId, const QString& name, const QString& unit, const qint16 value, const quint64 msec);
    void valueChanged(const int uasId, const QString& name, const QString& unit, const quint32 value, const quint64 msec);
    void valueChanged(const int uasId, const QString& name, const QString& unit, const qint32 value, const quint64 msec);
lm's avatar
lm committed
21 22
    void valueChanged(const int uasId, const QString& name, const QString& unit, const quint64 value, const quint64 msec);
    void valueChanged(const int uasId, const QString& name, const QString& unit, const qint64 value, const quint64 msec);
23 24
    void valueChanged(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec);
	
lm's avatar
lm committed
25 26 27 28 29 30 31

public slots:
    /** @brief Receive one message from the protocol and decode it */
    void receiveMessage(LinkInterface* link,mavlink_message_t message);
protected:
    /** @brief Emit the value of one message field */
    void emitFieldValue(mavlink_message_t* msg, int fieldid, quint64 time);
pixhawk's avatar
pixhawk committed
32 33
    /** @brief Shift a timestamp in Unix time if necessary */
    quint64 getUnixTimeFromMs(int systemID, quint64 time);
lm's avatar
lm committed
34 35

    mavlink_message_t receivedMessages[256]; ///< Available / known messages
36 37
    mavlink_message_info_t messageInfo[256]; ///< Message information
    QMap<uint16_t, bool> messageFilter;               ///< Message/field names not to emit
38
    QMap<uint16_t, bool> textMessageFilter;           ///< Message/field names not to emit in text mode
39 40
    int componentID[256];                             ///< Multi component detection
    bool componentMulti[256];                         ///< Multi components detected
pixhawk's avatar
pixhawk committed
41 42 43
    quint64 onboardTimeOffset[256];                   ///< Offset of onboard time from Unix epoch (of the receiving GCS)
    qint64 onboardToGCSUnixTimeOffsetAndDelay[256];   ///< Offset of onboard time and GCS Unix time
    quint64 firstOnboardTime[256];                    ///< First seen onboard time
lm's avatar
lm committed
44 45 46 47

};

#endif // MAVLINKDECODER_H