SlugsMAV.h 4.7 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23
/*=====================================================================

QGroundControl Open Source Ground Control Station

(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>

This file is part of the QGROUNDCONTROL project

    QGROUNDCONTROL is free software: you can redistribute it and/or modify
    it under the terms of the GNU General Public License as published by
    the Free Software Foundation, either version 3 of the License, or
    (at your option) any later version.

    QGROUNDCONTROL is distributed in the hope that it will be useful,
    but WITHOUT ANY WARRANTY; without even the implied warranty of
    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
    GNU General Public License for more details.

    You should have received a copy of the GNU General Public License
    along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.

======================================================================*/

24 25 26 27
#ifndef SLUGSMAV_H
#define SLUGSMAV_H

#include "UAS.h"
28
#include "mavlink.h"
29 30 31

class SlugsMAV : public UAS
{
32
    Q_OBJECT
unknown's avatar
unknown committed
33
    Q_INTERFACES(UASInterface)
34 35 36 37
public:
    SlugsMAV(MAVLinkProtocol* mavlink, int id = 0);

public slots:
38
    /** @brief Receive a MAVLink message from this MAV */
39
    void receiveMessage(LinkInterface* link, mavlink_message_t message);
40 41 42

signals:
    // ESPECIAL SLUGS MESSAGE
43
    void slugsCPULoad(int systemId,
44 45 46 47 48
                      uint8_t sensLoad,
                      uint8_t ctrlLoad,
                      uint8_t batVolt,
                      quint64 time);

49
    void slugsAirData(int systemId,
50 51 52 53 54
                      float dinamicPressure,
                      float staticPresure,
                      uint16_t temperature,
                      quint64 time);

55
    void slugsSensorBias(int systemId,
56 57 58 59 60 61 62 63
                         double axBias,
                         double ayBias,
                         double azBias,
                         double gxBias,
                         double gyBias,
                         double gzBias,
                         quint64 time);

64
    void slugsDiagnostic(int systemId,
65 66 67 68 69 70 71 72
                         double diagFl1,
                         double diagFl2,
                         double diagFl3,
                         int16_t diagSh1,
                         int16_t diagSh2,
                         int16_t diagSh3,
                         quint64 time);

73
    void slugsPilotConsolePWM(int systemId,
74 75 76 77 78 79 80
                              uint16_t dt,
                              uint16_t dla,
                              uint16_t dra,
                              uint16_t dr,
                              uint16_t de,
                              quint64 time);

81
    void slugsPWM(int systemId,
82 83 84 85 86 87 88 89 90 91 92 93
                  uint16_t dt_c,
                  uint16_t dla_c,
                  uint16_t dra_c,
                  uint16_t dr_c,
                  uint16_t dle_c,
                  uint16_t dre_c,
                  uint16_t dlf_c,
                  uint16_t drf_c,
                  uint16_t da1_c,
                  uint16_t da2_c,
                  quint64 time);

94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127
    void slugsNavegation(int systemId,
                          double u_m,
                          double phi_c,
                          double theta_c,
                          double psiDot_c,
                          double ay_body,
                          double totalDist,
                          double dist2Go,
                          uint8_t fromWP,
                          uint8_t toWP,
                          quint64 time);

   void slugsDataLog(int systemId,
                 double logfl_1,
                 double logfl_2,
                 double logfl_3,
                 double logfl_4,
                 double logfl_5,
                 double logfl_6,
                 quint64 time);


   void slugsFilteredData(int systemId,
                          double filaX,
                          double filaY,
                          double filaZ,
                          double filgX,
                          double filgY,
                          double filgZ,
                          double filmX,
                          double filmY,
                          double filmZ,
                          quint64 time);

128
   void slugsGPSDateTime(int systemId,
129 130 131 132 133 134 135 136 137
                         uint8_t gpsyear,
                         uint8_t gpsmonth,
                         uint8_t gpsday,
                         uint8_t gpshour,
                         uint8_t gpsmin,
                         uint8_t gpssec,
                         uint8_t gpsvisSat,
                         quint64 time);

138 139 140 141
   void slugsActionAck(int systemId,
                       uint8_t action,
                       uint8_t result);

142 143 144



145 146 147
};

#endif // SLUGSMAV_H