SlugsMAV.h 3.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
#include <QTimer>
30

31
#define SLUGS_UPDATE_RATE   100   // in ms
32 33
class SlugsMAV : public UAS
{
34
    Q_OBJECT
unknown's avatar
unknown committed
35
    Q_INTERFACES(UASInterface)
36 37 38 39
public:
    SlugsMAV(MAVLinkProtocol* mavlink, int id = 0);

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

43 44 45 46
    void emitSignals (void);



47
signals:
48

49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107
    void slugsRawImu(int uasId, const mavlink_raw_imu_t& rawData);

#ifdef MAVLINK_ENABLED_SLUGS

    void slugsCPULoad(int systemId, const mavlink_cpu_load_t& cpuLoad);
    void slugsAirData(int systemId, const mavlink_air_data_t& airData);
    void slugsSensorBias(int systemId, const mavlink_sensor_bias_t& sensorBias);
    void slugsDiagnostic(int systemId, const mavlink_diagnostic_t& diagnostic);
    void slugsPilotConsolePWM(int systemId, const mavlink_pilot_console_t& pilotConsole);
    void slugsPWM(int systemId, const mavlink_pwm_commands_t& pwmCommands);
    void slugsNavegation(int systemId, const mavlink_slugs_navigation_t& slugsNavigation);
    void slugsDataLog(int systemId, const mavlink_data_log_t& dataLog);
    void slugsFilteredData(int systemId, const mavlink_filtered_data_t& filteredData);
    void slugsGPSDateTime(int systemId, const mavlink_gps_date_time_t& gpsDateTime);
    void slugsActionAck(int systemId, const mavlink_action_ack_t& actionAck);

    void slugsBootMsg(int uasId, mavlink_boot_t& boot);
    void slugsAttitude(int uasId, mavlink_attitude_t& attitude);

#endif

protected:

   typedef struct _mavlink_pid_values_t {
         float P[11];
         float I[11];
         float D[11];
     }mavlink_pid_values_t;

   unsigned char updateRoundRobin;
   QTimer* widgetTimer;


   mavlink_raw_imu_t 			mlRawImuData;

#ifdef MAVLINK_ENABLED_SLUGS
   mavlink_gps_raw_t			mlGpsData;
   mavlink_attitude_t           mlAttitude;
   mavlink_cpu_load_t 			mlCpuLoadData;
   mavlink_air_data_t 			mlAirData;
   mavlink_sensor_bias_t 		mlSensorBiasData;
   mavlink_diagnostic_t 		mlDiagnosticData;
   mavlink_pilot_console_t 		mlPilotConsoleData;
   mavlink_filtered_data_t 		mlFilteredData;
   mavlink_boot_t 				mlBoot;
   mavlink_gps_date_time_t 		mlGpsDateTime;
   mavlink_mid_lvl_cmds_t 		mlMidLevelCommands;
   mavlink_set_mode_t 			mlApMode;
   mavlink_pwm_commands_t		mlPwmCommands;
   mavlink_pid_values_t			mlPidValues;
   mavlink_pid_t				mlSinglePid;

   mavlink_slugs_navigation_t	mlNavigation;
   mavlink_data_log_t			mlDataLog;
   mavlink_ctrl_srfc_pt_t		mlPassthrough;
   mavlink_action_ack_t			mlActionAck;

   mavlink_slugs_action_t		mlAction;

108 109

   // Standart messages MAVLINK used by SLUGS
110 111 112 113
private:


   void emitGpsSignals (void);
114

115
   int uasId;
116

117
#endif // if SLUGS
118

119 120 121
};

#endif // SLUGSMAV_H