MAVLinkDecoder.cc 18.7 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);
Nate Weibley's avatar
Nate Weibley committed
41
    messageFilter.insert(MAVLINK_MSG_ID_LOG_DATA, false);
Lorenz Meier's avatar
Lorenz Meier committed
42
    #ifdef MAVLINK_MSG_ID_ENCAPSULATED_DATA
43
    messageFilter.insert(MAVLINK_MSG_ID_ENCAPSULATED_DATA, false);
Lorenz Meier's avatar
Lorenz Meier committed
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);
Lorenz Meier's avatar
Lorenz Meier committed
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
}

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

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

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

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

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

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

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

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

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

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

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

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

171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199

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

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

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

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

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

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

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