MAVLinkDecoder.cc 18.6 KB
Newer Older
Don Gagne's avatar
Don Gagne committed
1
#include "QGCMAVLink.h"
lm's avatar
lm committed
2
#include "MAVLinkDecoder.h"
Don Gagne's avatar
Don Gagne committed
3 4

#include <QDebug>
lm's avatar
lm committed
5 6

MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) :
Lorenz Meier's avatar
Lorenz Meier committed
7
    QThread()
lm's avatar
lm committed
8
{
Lorenz Meier's avatar
Lorenz Meier committed
9
    Q_UNUSED(parent);
10 11 12 13
    // 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
14
    memset(receivedMessages, 0, sizeof(mavlink_message_t)*256);
15 16 17 18
    for (unsigned int i = 0; i<255;++i)
    {
        componentID[i] = -1;
        componentMulti[i] = false;
pixhawk's avatar
pixhawk committed
19
        onboardTimeOffset[i] = 0;
20 21
        onboardToGCSUnixTimeOffsetAndDelay[i] = 0;
        firstOnboardTime[i] = 0;
22
    }
lm's avatar
lm committed
23

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

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

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

    start(LowPriority);
}

/**
 * @brief Runs the thread
 *
 **/
void MAVLinkDecoder::run()
{
    exec();
lm's avatar
lm committed
66 67 68 69
}

void MAVLinkDecoder::receiveMessage(LinkInterface* link,mavlink_message_t message)
{
70 71 72 73 74
    if (message.msgid >= cMessageIds) {
        // No support for messag ids above 255
        return;
    }

lm's avatar
lm committed
75 76 77 78
    Q_UNUSED(link);
    memcpy(receivedMessages+message.msgid, &message, sizeof(mavlink_message_t));

    uint8_t msgid = message.msgid;
Don Gagne's avatar
Don Gagne committed
79
    const mavlink_message_info_t* msgInfo = mavlink_get_message_info(&message);
lm's avatar
lm committed
80

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

95
        // 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
96
        uint8_t fieldid = 0;
97 98
        uint8_t* m = (uint8_t*)&((mavlink_message_t*)(receivedMessages+msgid))->payload64[0];

Don Gagne's avatar
Don Gagne committed
99
        if (QString(msgInfo->fields[fieldid].name) == QString("time_boot_ms") && msgInfo->fields[fieldid].type == MAVLINK_TYPE_UINT32_T)
pixhawk's avatar
pixhawk committed
100
        {
Don Gagne's avatar
Don Gagne committed
101
            time = *((quint32*)(m+msgInfo->fields[fieldid].wire_offset));
pixhawk's avatar
pixhawk committed
102
        }
Don Gagne's avatar
Don Gagne committed
103
        else if (QString(msgInfo->fields[fieldid].name).contains("usec") && msgInfo->fields[fieldid].type == MAVLINK_TYPE_UINT64_T)
pixhawk's avatar
pixhawk committed
104
        {
Don Gagne's avatar
Don Gagne committed
105
            time = *((quint64*)(m+msgInfo->fields[fieldid].wire_offset));
106
            time = (time+500)/1000; // Scale to milliseconds, round up/down correctly
pixhawk's avatar
pixhawk committed
107
        }
108
    }
pixhawk's avatar
pixhawk committed
109

110 111
    // Align UAS time to global time
    time = getUnixTimeFromMs(message.sysid, time);
pixhawk's avatar
pixhawk committed
112

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

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

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

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

pixhawk's avatar
pixhawk committed
160 161 162 163 164 165 166 167 168
        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;
    }

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 194 195 196 197

//    // 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
198 199 200
    return ret;
}

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

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

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

298 299
    if (multiComponentSourceDetected)
    {
300
        name = name.prepend(QString("C%1:").arg(msg->compid));
301 302
    }

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

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