MAVLinkDecoder.cc 18.5 KB
Newer Older
Don Gagne's avatar
Don Gagne committed
1 2 3
#define MAVLINK_USE_MESSAGE_INFO
#include <stddef.h>         // Hack workaround for Mav 2.0 header problem with respect to offsetof usage
#include "QGCMAVLink.h"
lm's avatar
lm committed
4
#include "MAVLinkDecoder.h"
Don Gagne's avatar
Don Gagne committed
5 6

#include <QDebug>
lm's avatar
lm committed
7 8

MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) :
Lorenz Meier's avatar
Lorenz Meier committed
9
    QThread()
lm's avatar
lm committed
10
{
Lorenz Meier's avatar
Lorenz Meier committed
11
    Q_UNUSED(parent);
12 13 14 15
    // We're doing it wrong - because the Qt folks got the API wrong:
    // http://blog.qt.digia.com/blog/2010/06/17/youre-doing-it-wrong/
    moveToThread(this);

lm's avatar
lm committed
16
    memset(receivedMessages, 0, sizeof(mavlink_message_t)*256);
17 18 19 20
    for (unsigned int i = 0; i<255;++i)
    {
        componentID[i] = -1;
        componentMulti[i] = false;
pixhawk's avatar
pixhawk committed
21
        onboardTimeOffset[i] = 0;
22 23
        onboardToGCSUnixTimeOffsetAndDelay[i] = 0;
        firstOnboardTime[i] = 0;
24
    }
lm's avatar
lm committed
25

26
    // Fill filter
27 28 29
    // Allow system status
//    messageFilter.insert(MAVLINK_MSG_ID_HEARTBEAT, false);
//    messageFilter.insert(MAVLINK_MSG_ID_SYS_STATUS, false);
30
    messageFilter.insert(MAVLINK_MSG_ID_STATUSTEXT, false);
31
    messageFilter.insert(MAVLINK_MSG_ID_COMMAND_LONG, false);
32 33 34 35 36 37
    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);
38
    messageFilter.insert(MAVLINK_MSG_ID_DATA_STREAM, false);
39
    messageFilter.insert(MAVLINK_MSG_ID_GPS_STATUS, false);
40
    messageFilter.insert(MAVLINK_MSG_ID_RC_CHANNELS_RAW, false);
41
    messageFilter.insert(MAVLINK_MSG_ID_LOG_DATA, false);
42
    #ifdef MAVLINK_MSG_ID_ENCAPSULATED_DATA
43
    messageFilter.insert(MAVLINK_MSG_ID_ENCAPSULATED_DATA, false);
44 45
    #endif
    #ifdef MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE
46
    messageFilter.insert(MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, false);
47
    #endif
48
    messageFilter.insert(MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, false);
49

50 51 52 53
    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);
54
//    textMessageFilter.insert(MAVLINK_MSG_ID_HIGHRES_IMU, false);
55

56
    connect(protocol, &MAVLinkProtocol::messageReceived, this, &MAVLinkDecoder::receiveMessage);
57 58 59 60 61 62 63 64 65 66 67

    start(LowPriority);
}

/**
 * @brief Runs the thread
 *
 **/
void MAVLinkDecoder::run()
{
    exec();
lm's avatar
lm committed
68 69 70 71 72 73 74 75
}

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;
Don Gagne's avatar
Don Gagne committed
76
    const mavlink_message_info_t* msgInfo = mavlink_get_message_info(&message);
lm's avatar
lm committed
77

78 79 80 81
    // 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.
82
    if (message.msgid == MAVLINK_MSG_ID_SYSTEM_TIME)
lm's avatar
lm committed
83
    {
pixhawk's avatar
pixhawk committed
84 85
        mavlink_system_time_t timebase;
        mavlink_msg_system_time_decode(&message, &timebase);
86 87
        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
88 89 90 91
    }
    else
    {

92
        // 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
93 94
        uint8_t fieldid = 0;
        uint8_t* m = ((uint8_t*)(receivedMessages+msgid))+8;
Don Gagne's avatar
Don Gagne committed
95
        if (QString(msgInfo->fields[fieldid].name) == QString("time_boot_ms") && msgInfo->fields[fieldid].type == MAVLINK_TYPE_UINT32_T)
pixhawk's avatar
pixhawk committed
96
        {
Don Gagne's avatar
Don Gagne committed
97
            time = *((quint32*)(m+msgInfo->fields[fieldid].wire_offset));
pixhawk's avatar
pixhawk committed
98
        }
Don Gagne's avatar
Don Gagne committed
99
        else if (QString(msgInfo->fields[fieldid].name).contains("usec") && msgInfo->fields[fieldid].type == MAVLINK_TYPE_UINT64_T)
pixhawk's avatar
pixhawk committed
100
        {
Don Gagne's avatar
Don Gagne committed
101
            time = *((quint64*)(m+msgInfo->fields[fieldid].wire_offset));
102
            time = (time+500)/1000; // Scale to milliseconds, round up/down correctly
pixhawk's avatar
pixhawk committed
103
        }
104
    }
pixhawk's avatar
pixhawk committed
105

106 107
    // Align UAS time to global time
    time = getUnixTimeFromMs(message.sysid, time);
pixhawk's avatar
pixhawk committed
108

109
    // Send out all field values for this message
Don Gagne's avatar
Don Gagne committed
110
    for (unsigned int i = 0; i < msgInfo->num_fields; ++i)
111 112
    {
        emitFieldValue(&message, i, time);
lm's avatar
lm committed
113 114 115 116 117 118
    }

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

pixhawk's avatar
pixhawk committed
119
quint64 MAVLinkDecoder::getUnixTimeFromMs(int systemID, quint64 time)
120
{
pixhawk's avatar
pixhawk committed
121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147
    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
    {
148
        if (onboardTimeOffset[systemID] == 0 || time < (firstOnboardTime[systemID]-100))
pixhawk's avatar
pixhawk committed
149 150 151 152
        {
            firstOnboardTime[systemID] = time;
            onboardTimeOffset[systemID] = QGC::groundTimeMilliseconds() - time;
        }
153 154 155

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

pixhawk's avatar
pixhawk committed
156 157 158 159 160 161 162 163 164
        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;
    }

165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193

//    // 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
194 195 196
    return ret;
}

lm's avatar
lm committed
197 198
void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64 time)
{
199
    bool multiComponentSourceDetected = false;
Don Gagne's avatar
Don Gagne committed
200
    const mavlink_message_info_t* msgInfo = mavlink_get_message_info(msg);
201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217

    // 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
218 219
    // Add field tree widget item
    uint8_t msgid = msg->msgid;
220
    if (messageFilter.contains(msgid)) return;
Don Gagne's avatar
Don Gagne committed
221
    QString fieldName(msgInfo->fields[fieldid].name);
lm's avatar
lm committed
222 223 224 225
    QString fieldType;
    uint8_t* m = ((uint8_t*)(receivedMessages+msgid))+8;
    QString name("%1.%2");
    QString unit("");
pixhawk's avatar
pixhawk committed
226 227 228 229 230 231

    // Debug vector messages
    if (msgid == MAVLINK_MSG_ID_DEBUG_VECT)
    {
        mavlink_debug_vect_t debug;
        mavlink_msg_debug_vect_decode(msg, &debug);
232 233 234
        char buf[11];
        strncpy(buf, debug.name, 10);
        buf[10] = '\0';
235
        name = QString("%1.%2").arg(buf).arg(fieldName);
236
        time = getUnixTimeFromMs(msg->sysid, (debug.time_usec+500)/1000); // Scale to milliseconds, round up/down correctly
pixhawk's avatar
pixhawk committed
237
    }
238 239 240 241 242
    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);
243
        time = getUnixTimeFromMs(msg->sysid, debug.time_boot_ms);
244 245 246 247 248
    }
    else if (msgid == MAVLINK_MSG_ID_NAMED_VALUE_FLOAT)
    {
        mavlink_named_value_float_t debug;
        mavlink_msg_named_value_float_decode(msg, &debug);
249 250 251 252
        char buf[11];
        strncpy(buf, debug.name, 10);
        buf[10] = '\0';
        name = QString(buf);
253
        time = getUnixTimeFromMs(msg->sysid, debug.time_boot_ms);
254 255 256 257 258
    }
    else if (msgid == MAVLINK_MSG_ID_NAMED_VALUE_INT)
    {
        mavlink_named_value_int_t debug;
        mavlink_msg_named_value_int_decode(msg, &debug);
259 260 261 262
        char buf[11];
        strncpy(buf, debug.name, 10);
        buf[10] = '\0';
        name = QString(buf);
263
        time = getUnixTimeFromMs(msg->sysid, debug.time_boot_ms);
264
    }
265 266 267 268 269
    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);
Don Gagne's avatar
Don Gagne committed
270
        name = name.arg(msgInfo->name).arg(fieldName);
271 272 273 274 275 276 277
        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);
Don Gagne's avatar
Don Gagne committed
278
        name = name.arg(msgInfo->name).arg(fieldName);
279 280 281 282 283 284
        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;
285
        mavlink_msg_servo_output_raw_decode(msg, &servo);
Don Gagne's avatar
Don Gagne committed
286
        name = name.arg(msgInfo->name).arg(fieldName);
287 288
        name.prepend(QString("port%1_").arg(servo.port));
    }
pixhawk's avatar
pixhawk committed
289 290
    else
    {
Don Gagne's avatar
Don Gagne committed
291
        name = name.arg(msgInfo->name).arg(fieldName);
pixhawk's avatar
pixhawk committed
292 293
    }

294 295
    if (multiComponentSourceDetected)
    {
296
        name = name.prepend(QString("C%1:").arg(msg->compid));
297 298
    }

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

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