Skip to content
QGCMAVLinkInspector.h 2.53 KiB
Newer Older
#pragma once
lm's avatar
lm committed

#include <QMap>
#include <QTimer>

#include "QGCDockWidget.h"
lm's avatar
lm committed
#include "MAVLinkProtocol.h"
#include "Vehicle.h"
lm's avatar
lm committed

namespace Ui {
    class QGCMAVLinkInspector;
}

class QTreeWidgetItem;
LM's avatar
LM committed
class UASInterface;
lm's avatar
lm committed

class QGCMAVLinkInspector : public QGCDockWidget
lm's avatar
lm committed
{
    Q_OBJECT

public:
    explicit QGCMAVLinkInspector(const QString& title, QAction* action, MAVLinkProtocol* protocol, QWidget *parent = 0);
lm's avatar
lm committed
    ~QGCMAVLinkInspector();

public slots:
    void receiveMessage(LinkInterface* link,mavlink_message_t message);
    /** @brief Clear all messages */
    void clearView();
    /** @brief Update view */
lm's avatar
lm committed
    void refreshView();
    /** @brief Add component to the list */
LM's avatar
LM committed
    void addComponent(int uas, int component, const QString& name);
    /** @Brief Select a system through the drop down menu */
    void selectDropDownMenuSystem(int dropdownid);
    /** @Brief Select a component through the drop down menu */
    void selectDropDownMenuComponent(int dropdownid);
lm's avatar
lm committed

protected:
    MAVLinkProtocol *_protocol;     ///< MAVLink instance
LM's avatar
LM committed
    int selectedSystemID;          ///< Currently selected system
    int selectedComponentID;       ///< Currently selected component
    QMap<int, int> components; ///< Already observed components
lm's avatar
lm committed
    QTimer updateTimer; ///< Only update at 1 Hz to not overload the GUI
lm's avatar
lm committed

    QMap<int, QTreeWidgetItem* > uasTreeWidgetItems; ///< Tree of available uas with their widget
    QMap<int, QMap<int, QTreeWidgetItem*>* > uasMsgTreeItems; ///< Stores the widget of the received message for each UAS

    QMap<int, mavlink_message_t* > uasMessageStorage; ///< Stores the messages for every UAS

    QMap<int, QMap<int, float>* > uasMessageHz; ///< Stores the frequency of each message of each UAS
    QMap<int, QMap<int, unsigned int>* > uasMessageCount; ///< Stores the message count of each message of each UAS

    QMap<int, QMap<int, quint64>* > uasLastMessageUpdate; ///< Stores the time of the last message for each message of each UAS

Don Gagne's avatar
Don Gagne committed
    void updateField(mavlink_message_t* msg, const mavlink_message_info_t* msgInfo, int fieldid, QTreeWidgetItem* item);
LM's avatar
LM committed
    void rebuildComponentList();
Don Gagne's avatar
 
Don Gagne committed
    void addVehicleToTree(int vehicleId);
    void removeVehicleFromTree(int vehicleId);
lm's avatar
lm committed

    static const unsigned int updateInterval; ///< The update interval of the refresh function
    static const float updateHzLowpass; ///< The low-pass filter value for the frequency of each message
    
private slots:
Don Gagne's avatar
 
Don Gagne committed
    void _vehicleAdded  (Vehicle* vehicle);
    void _vehicleRemoved(Vehicle* vehicle);
LM's avatar
LM committed

lm's avatar
lm committed
private:
    Ui::QGCMAVLinkInspector *ui;
};