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

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

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

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

    start(LowPriority);
}

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

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

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

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

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

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

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

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

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

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

pixhawk's avatar
pixhawk committed
124
quint64 MAVLinkDecoder::getUnixTimeFromMs(int systemID, quint64 time)
125
{
pixhawk's avatar
pixhawk committed
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 152
    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
    {
153
        if (onboardTimeOffset[systemID] == 0 || time < (firstOnboardTime[systemID]-100))
pixhawk's avatar
pixhawk committed
154 155 156 157
        {
            firstOnboardTime[systemID] = time;
            onboardTimeOffset[systemID] = QGC::groundTimeMilliseconds() - time;
        }
158 159 160

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

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

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 198

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

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

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

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

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

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

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