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

3 4
#include <QDebug>

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

10 11
}

12 13 14 15 16 17 18 19
/**
 * 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
 */
20 21
void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
22 23 24
    // Let UAS handle the default message set
    UAS::receiveMessage(link, message);

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

tecnosapiens's avatar
tecnosapiens committed
34
#ifdef MAVLINK_ENABLED_SLUGS
35

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

42 43 44
                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
45

46 47 48 49 50
                emit slugsCPULoad(uasId,
                                  cpu_load.sensLoad,
                                  cpu_load.ctrlLoad,
                                  cpu_load.batVolt,
                                  0);
51
//qDebug()<<"--------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_CPU_LOAD 170";
unknown's avatar
unknown committed
52 53
            break;
        }
54
    case MAVLINK_MSG_ID_AIR_DATA://171
unknown's avatar
unknown committed
55 56 57 58
        {
            mavlink_air_data_t air_data;
            quint64 time = getUnixTime(0);
            mavlink_msg_air_data_decode(&message,&air_data);
59 60 61
                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
62

63 64 65 66 67
                emit slugsAirData(uasId,
                                  air_data.dynamicPressure,
                                  air_data.staticPressure,
                                  air_data.temperature,
                                  time);
68
//qDebug()<<"--------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_AIR_DATA 171";
unknown's avatar
unknown committed
69 70
            break;
        }
71
    case MAVLINK_MSG_ID_SENSOR_BIAS://172
unknown's avatar
unknown committed
72 73 74 75
        {
            mavlink_sensor_bias_t sensor_bias;
            quint64 time = getUnixTime(0);
            mavlink_msg_sensor_bias_decode(&message,&sensor_bias);
76 77 78 79 80 81
                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
82

83
                emit slugsSensorBias(uasId,
84 85 86 87 88 89
                                     sensor_bias.axBias,
                                     sensor_bias.ayBias,
                                     sensor_bias.azBias,
                                     sensor_bias.gxBias,
                                     sensor_bias.gyBias,
                                     sensor_bias.gzBias,
tecnosapiens's avatar
tecnosapiens committed
90
                                     0);
91
          //     qDebug()<<"------------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_SENSOR_BIAS 172";
92 93


unknown's avatar
unknown committed
94 95
            break;
        }
96
    case MAVLINK_MSG_ID_DIAGNOSTIC://173
unknown's avatar
unknown committed
97 98 99 100
        {
            mavlink_diagnostic_t diagnostic;
            quint64 time = getUnixTime(0);
            mavlink_msg_diagnostic_decode(&message,&diagnostic);
101 102 103 104 105 106
                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
107

108 109 110 111 112 113 114 115
                emit slugsDiagnostic(uasId,
                                     diagnostic.diagFl1,
                                     diagnostic.diagFl2,
                                     diagnostic.diagFl3,
                                     diagnostic.diagSh1,
                                     diagnostic.diagSh2,
                                     diagnostic.diagSh3,
                                     0);
116
//qDebug()<<"------->>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_DIAGNOSTIC 173";
unknown's avatar
unknown committed
117 118
            break;
        }
119
    case MAVLINK_MSG_ID_PILOT_CONSOLE://174
unknown's avatar
unknown committed
120 121 122 123
        {
            mavlink_pilot_console_t pilot;
            quint64 time = getUnixTime(0);
            mavlink_msg_pilot_console_decode(&message,&pilot);
124 125 126 127 128
                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
129

130 131 132 133 134 135 136
                emit slugsPilotConsolePWM(uasId,
                                          pilot.dt,
                                          pilot.dla,
                                          pilot.dra,
                                          pilot.dr,
                                          pilot.de,
                                          0);
137
             //   qDebug()<<"---------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_PILOT_CONSOLE 174";
138 139


unknown's avatar
unknown committed
140 141
            break;
        }
142
    case MAVLINK_MSG_ID_PWM_COMMANDS://175
unknown's avatar
unknown committed
143 144 145 146
        {
            mavlink_pwm_commands_t pwm;
            quint64 time = getUnixTime(0);
            mavlink_msg_pwm_commands_decode(&message,&pwm);
147 148 149 150 151 152 153 154 155 156
                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
157

158 159 160 161 162 163 164 165 166 167 168 169
                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,
                              0);
170
//qDebug()<<"----------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_PWM_COMMANDS 175";
171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200

            break;
        }
    case MAVLINK_MSG_ID_SLUGS_NAVIGATION://176
        {
            mavlink_slugs_navigation_t nav;
            quint64 time = getUnixTime(0);
            mavlink_msg_slugs_navigation_decode(&message,&nav);
                emit valueChanged(uasId,"u_m",nav.u_m,time);
                emit valueChanged(uasId,"phi_c",nav.phi_c,time);
                emit valueChanged(uasId,"theta_c",nav.theta_c,time);
                emit valueChanged(uasId,"psiDot_c",nav.psiDot_c,time);
                emit valueChanged(uasId,"ay_body",nav.ay_body,time);
                emit valueChanged(uasId,"totalDist",nav.totalDist,time);
                emit valueChanged(uasId,"dist2Go",nav.dist2Go,time);
                emit valueChanged(uasId,"fromWP",nav.fromWP,time);
                emit valueChanged(uasId,"toWP",nav.toWP,time);

                emit slugsNavegation(uasId,
                                     nav.u_m,
                                     nav.phi_c,
                                     nav.theta_c,
                                     nav.psiDot_c,
                                     nav.ay_body,
                                     nav.totalDist,
                                     nav.dist2Go,
                                     nav.fromWP,
                                     nav.toWP,
                                     time);

201
           // qDebug()<<"-------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_SLUGS_NAVIGATION 176";
202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225

            break;
        }
    case MAVLINK_MSG_ID_DATA_LOG://177
        {
            mavlink_data_log_t dataLog;
            quint64 time = getUnixTime(0);
            mavlink_msg_data_log_decode(&message,&dataLog);
                emit valueChanged(uasId,"fl_1",dataLog.fl_1,time);
                emit valueChanged(uasId,"fl_2",dataLog.fl_2,time);
                emit valueChanged(uasId,"fl_3",dataLog.fl_3,time);
                emit valueChanged(uasId,"fl_4",dataLog.fl_4,time);
                emit valueChanged(uasId,"fl_5",dataLog.fl_5,time);
                emit valueChanged(uasId,"fl_6",dataLog.fl_6,time);

                emit slugsDataLog(uasId,
                                  dataLog.fl_1,
                                  dataLog.fl_2,
                                  dataLog.fl_3,
                                  dataLog.fl_4,
                                  dataLog.fl_5,
                                  dataLog.fl_6,
                                  time);

226
             //   qDebug()<<"-------->>>>>>>>>>>>>>> EMITIENDO LOG DATA 177";
227

228

unknown's avatar
unknown committed
229

230 231
            break;
        }
tecnosapiens's avatar
tecnosapiens committed
232

233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262
    case MAVLINK_MSG_ID_FILTERED_DATA://178
        {

            mavlink_filtered_data_t fil;
            quint64 time = getUnixTime(0);
            mavlink_msg_filtered_data_decode(&message,&fil);
                emit valueChanged(uasId,"aX",fil.aX,time);
                emit valueChanged(uasId,"aY",fil.aY,time);
                emit valueChanged(uasId,"aZ",fil.aZ,time);
                emit valueChanged(uasId,"gX",fil.gX,time);
                emit valueChanged(uasId,"gY",fil.gY,time);
                emit valueChanged(uasId,"gZ",fil.gZ,time);
                emit valueChanged(uasId,"mX",fil.mX,time);
                emit valueChanged(uasId,"mY",fil.mY,time);
                emit valueChanged(uasId,"mZ",fil.mZ,time);

                emit slugsFilteredData(uasId,
                                       fil.aX,
                                       fil.aY,
                                       fil.aZ,
                                       fil.gX,
                                       fil.gY,
                                       fil.gZ,
                                       fil.mX,
                                       fil.mY,
                                       fil.mZ,
                                       time);



263
              //  qDebug()<<"-------->>>>>>>>>>>>>>> EMITIENDO filtering data 178";
264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294



            break;
        }
    case MAVLINK_MSG_ID_GPS_DATE_TIME://179
        {
            mavlink_gps_date_time_t gps;
            quint64 time = getUnixTime(0);
            mavlink_msg_gps_date_time_decode(&message,&gps);
                emit valueChanged(uasId,"year",gps.year,time);
                emit valueChanged(uasId,"month",gps.month,time);
                emit valueChanged(uasId,"day",gps.day,time);
                emit valueChanged(uasId,"hour",gps.hour,time);
                emit valueChanged(uasId,"min",gps.min,time);
                emit valueChanged(uasId,"sec",gps.sec,time);
                emit valueChanged(uasId,"visSat",gps.visSat,time);


                emit slugsGPSDateTime(uasId,
                                       gps.year,
                                       gps.month,
                                       gps.day,
                                       gps.hour,
                                       gps.min,
                                       gps.sec,
                                       gps.visSat,
                                       time);



295
              //  qDebug()<<"-------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_GPS_DATE_TIME 179";
296 297 298 299 300



            break;
        }
301 302
    case MAVLINK_MSG_ID_ACTION_ACK:
        {
tecnosapiens's avatar
tecnosapiens committed
303
            qDebug()<<"-------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_ACTION_ACK";
304 305 306 307 308
            mavlink_action_ack_t ack;

            mavlink_msg_action_ack_decode(&message,&ack);
            emit slugsActionAck(uasId,ack.action,ack.result);
        }
309 310
//    case MAVLINK_MSG_ID_MID_LVL_CMDS://180
//        {
311 312


313
//             //   qDebug()<<"------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_MID_LVL_CMDS 180";
314 315 316



317 318 319 320
//            break;
//        }
//    case MAVLINK_MSG_ID_CTRL_SRFC_PT://181
//        {
321 322


323
//               // qDebug()<<"--------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_CTRL_SRFC_PT 181";
324 325 326



327 328 329 330
//            break;
//        }
//    case MAVLINK_MSG_ID_PID://182
//        {
331 332


333
//               // qDebug()<<"-------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_PID 182";
334 335 336



337 338 339 340
//            break;
//        }
//    case MAVLINK_MSG_ID_SLUGS_ACTION://183
//        {
341 342


343
//               // qDebug()<<"-------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_SLUGS_ACTION 183";
344 345 346



347 348
//            break;
//        }
349 350
#endif

351
    default:
352
        //qDebug() << "\nSLUGS RECEIVED MESSAGE WITH ID" << message.msgid;
353 354 355
        break;
    }
}