SlugsMAV.cc 6.89 KB
Newer Older
1 2
#include "SlugsMAV.h"

3 4
#include <QDebug>

5 6 7 8 9 10
SlugsMAV::SlugsMAV(MAVLinkProtocol* mavlink, int id) :
        UAS(mavlink, id)//,
        // Place other initializers here
{
}

11 12 13 14 15 16 17 18
/**
 * This function is called by MAVLink once a complete, uncorrupted (CRC check valid)
 * mavlink packet is received.
 *
 * @param link Hardware link the message came from (e.g. /dev/ttyUSB0 or UDP port).
 *             messages can be sent back to the system via this link
 * @param message MAVLink message, as received from the MAVLink protocol stack
 */
19 20
void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
21 22 23
    // Let UAS handle the default message set
    UAS::receiveMessage(link, message);

unknown's avatar
unknown committed
24
    // Handle your special messages mavlink_message_t* msg = &message;
25 26 27 28
    switch (message.msgid)
    {
    case MAVLINK_MSG_ID_HEARTBEAT:
        {
29
            qDebug() << "SLUGS RECEIVED HEARTBEAT";
unknown's avatar
unknown committed
30 31
            break;
        }
32

33
#ifdef MAVLINK_ENABLED_SLUGS_MESSAGES_QGC
34

unknown's avatar
unknown committed
35 36 37 38 39 40
    case MAVLINK_MSG_ID_CPU_LOAD:
        {
            mavlink_cpu_load_t cpu_load;
            quint64 time = getUnixTime(0);
            mavlink_msg_cpu_load_decode(&message,&cpu_load);

41 42 43
                emit valueChanged(uasId, tr("SensorDSC Load"), cpu_load.sensLoad, time);
                emit valueChanged(uasId, tr("ControlDSC Load"), cpu_load.ctrlLoad, time);
                emit valueChanged(uasId, tr("Battery Volt"), cpu_load.batVolt, time);
unknown's avatar
unknown committed
44

45 46 47 48 49
                emit slugsCPULoad(uasId,
                                  cpu_load.sensLoad,
                                  cpu_load.ctrlLoad,
                                  cpu_load.batVolt,
                                  time);
50

unknown's avatar
unknown committed
51 52 53 54 55 56 57
            break;
        }
    case MAVLINK_MSG_ID_AIR_DATA:
        {
            mavlink_air_data_t air_data;
            quint64 time = getUnixTime(0);
            mavlink_msg_air_data_decode(&message,&air_data);
58 59 60
                emit valueChanged(uasId, tr("Dynamic Pressure"), air_data.dynamicPressure,time);
                emit valueChanged(uasId, tr("Static Pressure"),air_data.staticPressure, time);
                emit valueChanged(uasId, tr("Temp"),air_data.temperature,time);
unknown's avatar
unknown committed
61

62 63 64 65 66 67
                emit slugsAirData(uasId,
                                  air_data.dynamicPressure,
                                  air_data.staticPressure,
                                  air_data.temperature,
                                  time);

unknown's avatar
unknown committed
68 69 70 71 72 73 74
            break;
        }
    case MAVLINK_MSG_ID_SENSOR_BIAS:
        {
            mavlink_sensor_bias_t sensor_bias;
            quint64 time = getUnixTime(0);
            mavlink_msg_sensor_bias_decode(&message,&sensor_bias);
75 76 77 78 79 80
                emit valueChanged(uasId,tr("Ax Bias"),sensor_bias.axBias, time);
                emit valueChanged(uasId,tr("Ay Bias"),sensor_bias.ayBias,time);
                emit valueChanged(uasId,tr("Az Bias"),sensor_bias.azBias,time);
                emit valueChanged(uasId,tr("Gx Bias"),sensor_bias.gxBias,time);
                emit valueChanged(uasId,tr("Gy Bias"),sensor_bias.gyBias,time);
                emit valueChanged(uasId,tr("Gz Bias"),sensor_bias.gzBias,time);
unknown's avatar
unknown committed
81

82 83 84 85 86 87 88 89 90 91
                emit slugsSensorBias(uasId,
                                     sensor_bias.axBias,
                                     sensor_bias.ayBias,
                                     sensor_bias.azBias,
                                     sensor_bias.gxBias,
                                     sensor_bias.gyBias,
                                     sensor_bias.gzBias,
                                     time);


unknown's avatar
unknown committed
92 93 94 95 96 97 98
            break;
        }
    case MAVLINK_MSG_ID_DIAGNOSTIC:
        {
            mavlink_diagnostic_t diagnostic;
            quint64 time = getUnixTime(0);
            mavlink_msg_diagnostic_decode(&message,&diagnostic);
99 100 101 102 103 104
                emit valueChanged(uasId,tr("Diag F1"),diagnostic.diagFl1,time);
                emit valueChanged(uasId,tr("Diag F2"),diagnostic.diagFl2,time);
                emit valueChanged(uasId,tr("Diag F3"),diagnostic.diagFl3,time);
                emit valueChanged(uasId,tr("Diag S1"),diagnostic.diagSh1,time);
                emit valueChanged(uasId,tr("Diag S2"),diagnostic.diagSh2,time);
                emit valueChanged(uasId,tr("Diag S3"),diagnostic.diagSh3,time);
unknown's avatar
unknown committed
105

106 107 108 109 110 111 112 113
                emit slugsDiagnostic(uasId,
                                     diagnostic.diagFl1,
                                     diagnostic.diagFl2,
                                     diagnostic.diagFl3,
                                     diagnostic.diagSh1,
                                     diagnostic.diagSh2,
                                     diagnostic.diagSh3);

unknown's avatar
unknown committed
114 115 116 117 118 119 120
            break;
        }
    case MAVLINK_MSG_ID_PILOT_CONSOLE:
        {
            mavlink_pilot_console_t pilot;
            quint64 time = getUnixTime(0);
            mavlink_msg_pilot_console_decode(&message,&pilot);
121 122 123 124 125
                emit valueChanged(uasId,"dt",pilot.dt,time);
                emit valueChanged(uasId,"dla",pilot.dla,time);
                emit valueChanged(uasId,"dra",pilot.dra,time);
                emit valueChanged(uasId,"dr",pilot.dr,time);
                emit valueChanged(uasId,"de",pilot.de,time);
unknown's avatar
unknown committed
126

127 128 129 130 131 132 133 134 135
                emit slugsPilotConsolePWM(uasId,
                                          pilot.dt,
                                          pilot.dla,
                                          pilot.dra,
                                          pilot.dr,
                                          pilot.de,
                                          time);


unknown's avatar
unknown committed
136 137 138 139 140 141 142
            break;
        }
    case MAVLINK_MSG_ID_PWM_COMMANDS:
        {
            mavlink_pwm_commands_t pwm;
            quint64 time = getUnixTime(0);
            mavlink_msg_pwm_commands_decode(&message,&pwm);
143 144 145 146 147 148 149 150 151 152
                emit valueChanged(uasId,"dt_c",pwm.dt_c,time);
                emit valueChanged(uasId,"dla_c",pwm.dla_c,time);
                emit valueChanged(uasId,"dra_c",pwm.dra_c,time);
                emit valueChanged(uasId,"dr_c",pwm.dr_c,time);
                emit valueChanged(uasId,"dle_c",pwm.dle_c,time);
                emit valueChanged(uasId,"dre_c",pwm.dre_c,time);
                emit valueChanged(uasId,"dlf_c",pwm.dlf_c,time);
                emit valueChanged(uasId,"drf_c",pwm.drf_c,time);
                emit valueChanged(uasId,"da1_c",pwm.aux1,time);
                emit valueChanged(uasId,"da2_c",pwm.aux2,time);
unknown's avatar
unknown committed
153

154 155 156 157 158 159 160 161 162 163 164 165 166
                emit slugsPWM(uasId,
                              pwm.dt_c,
                              pwm.dla_c,
                              pwm.dra_c,
                              pwm.dr_c,
                              pwm.dle_c,
                              pwm.dre_c,
                              pwm.dlf_c,
                              pwm.drf_c,
                              pwm.aux1,
                              pwm.aux2,
                              time);

unknown's avatar
unknown committed
167

168 169
            break;
        }
170 171
#endif

172
    default:
173
        qDebug() << "\nSLUGS RECEIVED MESSAGE WITH ID" << message.msgid;
174 175 176
        break;
    }
}