PxQuadMAV.h 824 Bytes
Newer Older
1 2 3 4 5 6 7
#ifndef PXQUADMAV_H
#define PXQUADMAV_H

#include "UAS.h"

class PxQuadMAV : public UAS
{
8
    Q_OBJECT
9
    Q_INTERFACES(UASInterface)
10 11
public:
    PxQuadMAV(MAVLinkProtocol* mavlink, int id);
12 13 14
public slots:
    /** @brief Receive a MAVLink message from this MAV */
    void receiveMessage(LinkInterface* link, mavlink_message_t message);
15 16
    /** @brief Send a command to an onboard process */
    void sendProcessCommand(int watchdogId, int processId, unsigned int command);
17
signals:
pixhawk's avatar
pixhawk committed
18
    void watchdogReceived(int systemId, int watchdogId, unsigned int processCount);
19 20
    void processReceived(int systemId, int watchdogId, int processId, QString name, QString arguments, int timeout);
    void processChanged(int systemId, int watchdogId, int processId, int state, bool muted, int crashed, int pid);
21 22 23
};

#endif // PXQUADMAV_H