MAVLinkDecoder.cc 18.7 KB
Newer Older
lm's avatar
lm committed
1 2 3 4 5 6 7 8 9
#include "MAVLinkDecoder.h"
#include "UASManager.h"

MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) :
    QObject(parent)
{
    mavlink_message_info_t msg[256] = MAVLINK_MESSAGE_INFO;
    memcpy(messageInfo, msg, sizeof(mavlink_message_info_t)*256);
    memset(receivedMessages, 0, sizeof(mavlink_message_t)*256);
10 11 12 13
    for (unsigned int i = 0; i<255;++i)
    {
        componentID[i] = -1;
        componentMulti[i] = false;
pixhawk's avatar
pixhawk committed
14
        onboardTimeOffset[i] = 0;
15 16
        onboardToGCSUnixTimeOffsetAndDelay[i] = 0;
        firstOnboardTime[i] = 0;
17
    }
lm's avatar
lm committed
18

19
    // Fill filter
20 21 22
    // Allow system status
//    messageFilter.insert(MAVLINK_MSG_ID_HEARTBEAT, false);
//    messageFilter.insert(MAVLINK_MSG_ID_SYS_STATUS, false);
23
    messageFilter.insert(MAVLINK_MSG_ID_STATUSTEXT, false);
24
    messageFilter.insert(MAVLINK_MSG_ID_COMMAND_LONG, false);
25 26 27 28 29 30
    messageFilter.insert(MAVLINK_MSG_ID_COMMAND_ACK, false);
    messageFilter.insert(MAVLINK_MSG_ID_PARAM_SET, false);
    messageFilter.insert(MAVLINK_MSG_ID_PARAM_VALUE, false);
    messageFilter.insert(MAVLINK_MSG_ID_MISSION_ITEM, false);
    messageFilter.insert(MAVLINK_MSG_ID_MISSION_COUNT, false);
    messageFilter.insert(MAVLINK_MSG_ID_MISSION_ACK, false);
31
    messageFilter.insert(MAVLINK_MSG_ID_DATA_STREAM, false);
32
    messageFilter.insert(MAVLINK_MSG_ID_GPS_STATUS, false);
33
    messageFilter.insert(MAVLINK_MSG_ID_RC_CHANNELS_RAW, false);
34
    #ifdef MAVLINK_MSG_ID_ENCAPSULATED_DATA
35
    messageFilter.insert(MAVLINK_MSG_ID_ENCAPSULATED_DATA, false);
36 37
    #endif
    #ifdef MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE
38
    messageFilter.insert(MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, false);
39
    #endif
40
    messageFilter.insert(MAVLINK_MSG_ID_EXTENDED_MESSAGE, false);
41

42 43 44 45
    textMessageFilter.insert(MAVLINK_MSG_ID_DEBUG, false);
    textMessageFilter.insert(MAVLINK_MSG_ID_DEBUG_VECT, false);
    textMessageFilter.insert(MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, false);
    textMessageFilter.insert(MAVLINK_MSG_ID_NAMED_VALUE_INT, false);
46
//    textMessageFilter.insert(MAVLINK_MSG_ID_HIGHRES_IMU, false);
47

lm's avatar
lm committed
48 49 50 51 52 53 54 55 56 57
    connect(protocol, SIGNAL(messageReceived(LinkInterface*,mavlink_message_t)), this, SLOT(receiveMessage(LinkInterface*,mavlink_message_t)));
}

void MAVLinkDecoder::receiveMessage(LinkInterface* link,mavlink_message_t message)
{
    Q_UNUSED(link);
    memcpy(receivedMessages+message.msgid, &message, sizeof(mavlink_message_t));

    uint8_t msgid = message.msgid;

58 59 60 61
    // Store an arrival time for this message. This value ends up being calculated later.
    quint64 time = 0;
    
    // The SYSTEM_TIME message is special, in that it's handled here for synchronizing the QGC time with the remote time.
62
    if (message.msgid == MAVLINK_MSG_ID_SYSTEM_TIME)
lm's avatar
lm committed
63
    {
pixhawk's avatar
pixhawk committed
64 65
        mavlink_system_time_t timebase;
        mavlink_msg_system_time_decode(&message, &timebase);
66 67
        onboardTimeOffset[message.sysid] = (timebase.time_unix_usec+500)/1000 - timebase.time_boot_ms;
        onboardToGCSUnixTimeOffsetAndDelay[message.sysid] = static_cast<qint64>(QGC::groundTimeMilliseconds() - (timebase.time_unix_usec+500)/1000);
lm's avatar
lm committed
68 69 70 71
    }
    else
    {

72
        // See if first value is a time value and if it is, use that as the arrival time for this data.
pixhawk's avatar
pixhawk committed
73 74 75 76 77 78 79 80 81
        uint8_t fieldid = 0;
        uint8_t* m = ((uint8_t*)(receivedMessages+msgid))+8;
        if (QString(messageInfo[msgid].fields[fieldid].name) == QString("time_boot_ms") && messageInfo[msgid].fields[fieldid].type == MAVLINK_TYPE_UINT32_T)
        {
            time = *((quint32*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
        }
        else if (QString(messageInfo[msgid].fields[fieldid].name).contains("usec") && messageInfo[msgid].fields[fieldid].type == MAVLINK_TYPE_UINT64_T)
        {
            time = *((quint64*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
82
            time = (time+500)/1000; // Scale to milliseconds, round up/down correctly
pixhawk's avatar
pixhawk committed
83
        }
84
    }
pixhawk's avatar
pixhawk committed
85

86 87
    // Align UAS time to global time
    time = getUnixTimeFromMs(message.sysid, time);
pixhawk's avatar
pixhawk committed
88

89 90 91 92
    // Send out all field values for this message
    for (int i = 0; i < messageInfo[msgid].num_fields; ++i)
    {
        emitFieldValue(&message, i, time);
lm's avatar
lm committed
93 94 95 96 97 98
    }

    // Send out combined math expressions
    // FIXME XXX TODO
}

pixhawk's avatar
pixhawk committed
99
quint64 MAVLinkDecoder::getUnixTimeFromMs(int systemID, quint64 time)
100
{
pixhawk's avatar
pixhawk committed
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
    quint64 ret = 0;
    if (time == 0)
    {
        ret = QGC::groundTimeMilliseconds() - onboardToGCSUnixTimeOffsetAndDelay[systemID];
    }
    // Check if time is smaller than 40 years,
    // assuming no system without Unix timestamp
    // runs longer than 40 years continuously without
    // reboot. In worst case this will add/subtract the
    // communication delay between GCS and MAV,
    // it will never alter the timestamp in a safety
    // critical way.
    //
    // Calculation:
    // 40 years
    // 365 days
    // 24 hours
    // 60 minutes
    // 60 seconds
    // 1000 milliseconds
    // 1000 microseconds
#ifndef _MSC_VER
    else if (time < 1261440000000LLU)
#else
    else if (time < 1261440000000)
#endif
    {
128
        if (onboardTimeOffset[systemID] == 0 || time < (firstOnboardTime[systemID]-100))
pixhawk's avatar
pixhawk committed
129 130 131 132
        {
            firstOnboardTime[systemID] = time;
            onboardTimeOffset[systemID] = QGC::groundTimeMilliseconds() - time;
        }
133 134 135

        if (time > firstOnboardTime[systemID]) firstOnboardTime[systemID] = time;

pixhawk's avatar
pixhawk committed
136 137 138 139 140 141 142 143 144
        ret = time + onboardTimeOffset[systemID];
    }
    else
    {
        // Time is not zero and larger than 40 years -> has to be
        // a Unix epoch timestamp. Do nothing.
        ret = time;
    }

145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173

//    // Check if the offset estimation likely went wrong
//    // and we're talking to a new instance / the system
//    // has rebooted. Only reset if this is consistent.
//    if (!isNull && lastNonNullTime > ret)
//    {
//        onboardTimeOffsetInvalidCount++;
//    }
//    else if (!isNull && lastNonNullTime < ret)
//    {
//        onboardTimeOffsetInvalidCount = 0;
//    }

//    // Reset onboard time offset estimation, since it seems to be really off
//    if (onboardTimeOffsetInvalidCount > 20)
//    {
//        onboardTimeOffset = 0;
//        onboardTimeOffsetInvalidCount = 0;
//        lastNonNullTime = 0;
//        qDebug() << "RESETTET ONBOARD TIME OFFSET";
//    }

//    // If we're progressing in time, set it
//    // else wait for the reboot detection to
//    // catch the timestamp wrap / reset
//    if (!isNull && (lastNonNullTime < ret)) {
//        lastNonNullTime = ret;
//    }

pixhawk's avatar
pixhawk committed
174 175 176
    return ret;
}

lm's avatar
lm committed
177 178
void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64 time)
{
179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196
    bool multiComponentSourceDetected = false;

    // Store component ID
    if (componentID[msg->msgid] == -1)
    {
        componentID[msg->msgid] = msg->compid;
    }
    else
    {
        // Got this message already
        if (componentID[msg->msgid] != msg->compid)
        {
            componentMulti[msg->msgid] = true;
        }
    }

    if (componentMulti[msg->msgid] == true) multiComponentSourceDetected = true;

lm's avatar
lm committed
197 198
    // Add field tree widget item
    uint8_t msgid = msg->msgid;
199
    if (messageFilter.contains(msgid)) return;
lm's avatar
lm committed
200 201 202 203 204
    QString fieldName(messageInfo[msgid].fields[fieldid].name);
    QString fieldType;
    uint8_t* m = ((uint8_t*)(receivedMessages+msgid))+8;
    QString name("%1.%2");
    QString unit("");
pixhawk's avatar
pixhawk committed
205 206 207 208 209 210

    // Debug vector messages
    if (msgid == MAVLINK_MSG_ID_DEBUG_VECT)
    {
        mavlink_debug_vect_t debug;
        mavlink_msg_debug_vect_decode(msg, &debug);
211 212 213
        char buf[11];
        strncpy(buf, debug.name, 10);
        buf[10] = '\0';
214
        name = QString("%1.%2").arg(buf).arg(fieldName);
215
        time = getUnixTimeFromMs(msg->sysid, (debug.time_usec+500)/1000); // Scale to milliseconds, round up/down correctly
pixhawk's avatar
pixhawk committed
216
    }
217 218 219 220 221
    else if (msgid == MAVLINK_MSG_ID_DEBUG)
    {
        mavlink_debug_t debug;
        mavlink_msg_debug_decode(msg, &debug);
        name = name.arg(QString("debug")).arg(debug.ind);
222
        time = getUnixTimeFromMs(msg->sysid, debug.time_boot_ms);
223 224 225 226 227
    }
    else if (msgid == MAVLINK_MSG_ID_NAMED_VALUE_FLOAT)
    {
        mavlink_named_value_float_t debug;
        mavlink_msg_named_value_float_decode(msg, &debug);
228 229 230 231
        char buf[11];
        strncpy(buf, debug.name, 10);
        buf[10] = '\0';
        name = QString(buf);
232
        time = getUnixTimeFromMs(msg->sysid, debug.time_boot_ms);
233 234 235 236 237
    }
    else if (msgid == MAVLINK_MSG_ID_NAMED_VALUE_INT)
    {
        mavlink_named_value_int_t debug;
        mavlink_msg_named_value_int_decode(msg, &debug);
238 239 240 241
        char buf[11];
        strncpy(buf, debug.name, 10);
        buf[10] = '\0';
        name = QString(buf);
242
        time = getUnixTimeFromMs(msg->sysid, debug.time_boot_ms);
243
    }
244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263
    else if (msgid == MAVLINK_MSG_ID_RC_CHANNELS_RAW)
    {
        // XXX this is really ugly, but we do not know a better way to do this
        mavlink_rc_channels_raw_t raw;
        mavlink_msg_rc_channels_raw_decode(msg, &raw);
        name = name.arg(messageInfo[msgid].name).arg(fieldName);
        name.prepend(QString("port%1_").arg(raw.port));
    }
    else if (msgid == MAVLINK_MSG_ID_RC_CHANNELS_SCALED)
    {
        // XXX this is really ugly, but we do not know a better way to do this
        mavlink_rc_channels_scaled_t scaled;
        mavlink_msg_rc_channels_scaled_decode(msg, &scaled);
        name = name.arg(messageInfo[msgid].name).arg(fieldName);
        name.prepend(QString("port%1_").arg(scaled.port));
    }
    else if (msgid == MAVLINK_MSG_ID_SERVO_OUTPUT_RAW)
    {
        // XXX this is really ugly, but we do not know a better way to do this
        mavlink_servo_output_raw_t servo;
264
        mavlink_msg_servo_output_raw_decode(msg, &servo);
265 266 267
        name = name.arg(messageInfo[msgid].name).arg(fieldName);
        name.prepend(QString("port%1_").arg(servo.port));
    }
pixhawk's avatar
pixhawk committed
268 269
    else
    {
270
        name = name.arg(messageInfo[msgid].name).arg(fieldName);
pixhawk's avatar
pixhawk committed
271 272
    }

273 274
    if (multiComponentSourceDetected)
    {
275
        name = name.prepend(QString("C%1:").arg(msg->compid));
276 277
    }

278
    name = name.prepend(QString("M%1:").arg(msg->sysid));
279

lm's avatar
lm committed
280 281 282 283 284 285 286 287 288
    switch (messageInfo[msgid].fields[fieldid].type)
    {
    case MAVLINK_TYPE_CHAR:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            char* str = (char*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
            // Enforce null termination
            str[messageInfo[msgid].fields[fieldid].array_length-1] = '\0';
            QString string(name + ": " + str);
289
            if (!textMessageFilter.contains(msgid)) emit textMessageReceived(msg->sysid, msg->compid, 0, string);
lm's avatar
lm committed
290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321
        }
        else
        {
            // Single char
            char b = *((char*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
            unit = QString("char[%1]").arg(messageInfo[msgid].fields[fieldid].array_length);
            emit valueChanged(msg->sysid, name, unit, b, time);
        }
        break;
    case MAVLINK_TYPE_UINT8_T:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            uint8_t* nums = m+messageInfo[msgid].fields[fieldid].wire_offset;
            fieldType = QString("uint8_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length);
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
            {
                emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time);
            }
        }
        else
        {
            // Single value
            uint8_t u = *(m+messageInfo[msgid].fields[fieldid].wire_offset);
            fieldType = "uint8_t";
            emit valueChanged(msg->sysid, name, fieldType, u, time);
        }
        break;
    case MAVLINK_TYPE_INT8_T:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            int8_t* nums = (int8_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
            fieldType = QString("int8_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length);
322
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339
            {
                emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time);
            }
        }
        else
        {
            // Single value
            int8_t n = *((int8_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
            fieldType = "int8_t";
            emit valueChanged(msg->sysid, name, fieldType, n, time);
        }
        break;
    case MAVLINK_TYPE_UINT16_T:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            uint16_t* nums = (uint16_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
            fieldType = QString("uint16_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length);
340
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357
            {
                emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time);
            }
        }
        else
        {
            // Single value
            uint16_t n = *((uint16_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
            fieldType = "uint16_t";
            emit valueChanged(msg->sysid, name, fieldType, n, time);
        }
        break;
    case MAVLINK_TYPE_INT16_T:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            int16_t* nums = (int16_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
            fieldType = QString("int16_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length);
358
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375
            {
                emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time);
            }
        }
        else
        {
            // Single value
            int16_t n = *((int16_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
            fieldType = "int16_t";
            emit valueChanged(msg->sysid, name, fieldType, n, time);
        }
        break;
    case MAVLINK_TYPE_UINT32_T:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            uint32_t* nums = (uint32_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
            fieldType = QString("uint32_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length);
376
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
377 378 379 380 381 382 383
            {
                emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time);
            }
        }
        else
        {
            // Single value
384
            uint32_t n = *((uint32_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
lm's avatar
lm committed
385 386 387 388 389 390 391 392 393
            fieldType = "uint32_t";
            emit valueChanged(msg->sysid, name, fieldType, n, time);
        }
        break;
    case MAVLINK_TYPE_INT32_T:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            int32_t* nums = (int32_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
            fieldType = QString("int32_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length);
394
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411
            {
                emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time);
            }
        }
        else
        {
            // Single value
            int32_t n = *((int32_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
            fieldType = "int32_t";
            emit valueChanged(msg->sysid, name, fieldType, n, time);
        }
        break;
    case MAVLINK_TYPE_FLOAT:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            float* nums = (float*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
            fieldType = QString("float[%1]").arg(messageInfo[msgid].fields[fieldid].array_length);
412
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
413
            {
414
                emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, (float)(nums[j]), time);
lm's avatar
lm committed
415 416 417 418 419 420 421 422 423 424 425 426 427 428 429
            }
        }
        else
        {
            // Single value
            float f = *((float*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
            fieldType = "float";
            emit valueChanged(msg->sysid, name, fieldType, f, time);
        }
        break;
    case MAVLINK_TYPE_DOUBLE:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            double* nums = (double*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
            fieldType = QString("double[%1]").arg(messageInfo[msgid].fields[fieldid].array_length);
430
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447
            {
                emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time);
            }
        }
        else
        {
            // Single value
            double f = *((double*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
            fieldType = "double";
            emit valueChanged(msg->sysid, name, fieldType, f, time);
        }
        break;
    case MAVLINK_TYPE_UINT64_T:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            uint64_t* nums = (uint64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
            fieldType = QString("uint64_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length);
448
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
449
            {
pixhawk's avatar
pixhawk committed
450
                emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, (quint64) nums[j], time);
lm's avatar
lm committed
451 452 453 454 455 456 457
            }
        }
        else
        {
            // Single value
            uint64_t n = *((uint64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
            fieldType = "uint64_t";
pixhawk's avatar
pixhawk committed
458
            emit valueChanged(msg->sysid, name, fieldType, (quint64) n, time);
lm's avatar
lm committed
459 460 461 462 463 464 465
        }
        break;
    case MAVLINK_TYPE_INT64_T:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            int64_t* nums = (int64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
            fieldType = QString("int64_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length);
466
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
467
            {
pixhawk's avatar
pixhawk committed
468
                emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, (qint64) nums[j], time);
lm's avatar
lm committed
469 470 471 472 473 474 475
            }
        }
        else
        {
            // Single value
            int64_t n = *((int64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
            fieldType = "int64_t";
pixhawk's avatar
pixhawk committed
476
            emit valueChanged(msg->sysid, name, fieldType, (qint64) n, time);
lm's avatar
lm committed
477 478
        }
        break;
479 480
    default:
        qDebug() << "WARNING: UNKNOWN MAVLINK TYPE";
lm's avatar
lm committed
481 482
    }
}