QGCMAVLinkInspector.cc 24.4 KB
Newer Older
lm's avatar
lm committed
1 2
#include <QList>

lm's avatar
lm committed
3
#include "QGCMAVLink.h"
lm's avatar
lm committed
4
#include "QGCMAVLinkInspector.h"
LM's avatar
LM committed
5
#include "UASManager.h"
lm's avatar
lm committed
6 7 8 9
#include "ui_QGCMAVLinkInspector.h"

#include <QDebug>

10 11 12
const float QGCMAVLinkInspector::updateHzLowpass = 0.2f;
const unsigned int QGCMAVLinkInspector::updateInterval = 1000U;

lm's avatar
lm committed
13 14
QGCMAVLinkInspector::QGCMAVLinkInspector(MAVLinkProtocol* protocol, QWidget *parent) :
    QWidget(parent),
15
    _protocol(protocol),
LM's avatar
LM committed
16 17
    selectedSystemID(0),
    selectedComponentID(0),
lm's avatar
lm committed
18 19 20
    ui(new Ui::QGCMAVLinkInspector)
{
    ui->setupUi(this);
lm's avatar
lm committed
21

22
    // Make sure "All" is an option for both the system and components
23 24
    ui->systemComboBox->addItem(tr("All"), 0);
    ui->componentComboBox->addItem(tr("All"), 0);
lm's avatar
lm committed
25

26 27 28
    // Store metadata for all MAVLink messages.
    mavlink_message_info_t msg_infos[256] = MAVLINK_MESSAGE_INFO;
    memcpy(messageInfo, msg_infos, sizeof(mavlink_message_info_t)*256);
29

30
    // Set up the column headers for the message listing
lm's avatar
lm committed
31 32 33 34 35
    QStringList header;
    header << tr("Name");
    header << tr("Value");
    header << tr("Type");
    ui->treeWidget->setHeaderLabels(header);
LM's avatar
LM committed
36

37 38 39 40 41 42 43 44 45 46
    // Set up the column headers for the rate listing
    QStringList rateHeader;
    rateHeader << tr("Name");
    rateHeader << tr("#ID");
    rateHeader << tr("Rate");
    ui->rateTreeWidget->setHeaderLabels(rateHeader);
    connect(ui->rateTreeWidget, SIGNAL(itemChanged(QTreeWidgetItem*,int)),
            this, SLOT(rateTreeItemChanged(QTreeWidgetItem*,int)));
    ui->rateTreeWidget->hide();

47
    // Connect the UI
LM's avatar
LM committed
48 49
    connect(ui->systemComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(selectDropDownMenuSystem(int)));
    connect(ui->componentComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(selectDropDownMenuComponent(int)));
50
    connect(ui->clearButton, SIGNAL(clicked()), this, SLOT(clearView()));
LM's avatar
LM committed
51

52
    // Connect external connections
53
    connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addSystem(UASInterface*)));
54
    connect(protocol, SIGNAL(messageReceived(LinkInterface*,mavlink_message_t)), this, SLOT(receiveMessage(LinkInterface*,mavlink_message_t)));
LM's avatar
LM committed
55

56 57
    // Attach the UI's refresh rate to a timer.
    connect(&updateTimer, SIGNAL(timeout()), this, SLOT(refreshView()));
LM's avatar
LM committed
58
    updateTimer.start(updateInterval);
lm's avatar
lm committed
59 60
}

LM's avatar
LM committed
61 62 63
void QGCMAVLinkInspector::addSystem(UASInterface* uas)
{
    ui->systemComboBox->addItem(uas->getUASName(), uas->getUASID());
64 65 66

    // Add a tree for a new UAS
    addUAStoTree(uas->getUASID());
LM's avatar
LM committed
67 68 69 70 71 72
}

void QGCMAVLinkInspector::selectDropDownMenuSystem(int dropdownid)
{
    selectedSystemID = ui->systemComboBox->itemData(dropdownid).toInt();
    rebuildComponentList();
73 74 75 76 77 78

    if (selectedSystemID != 0 && selectedComponentID != 0) {
        ui->rateTreeWidget->show();
    } else {
        ui->rateTreeWidget->hide();
    }
LM's avatar
LM committed
79 80 81 82 83
}

void QGCMAVLinkInspector::selectDropDownMenuComponent(int dropdownid)
{
    selectedComponentID = ui->componentComboBox->itemData(dropdownid).toInt();
84 85 86 87 88 89

    if (selectedSystemID != 0 && selectedComponentID != 0) {
        ui->rateTreeWidget->show();
    } else {
        ui->rateTreeWidget->hide();
    }
LM's avatar
LM committed
90 91 92 93 94
}

void QGCMAVLinkInspector::rebuildComponentList()
{
    ui->componentComboBox->clear();
95
    components.clear();
LM's avatar
LM committed
96

97
    ui->componentComboBox->addItem(tr("All"), 0);
98 99 100 101 102 103 104 105 106 107 108 109

    // Fill
    UASInterface* uas = UASManager::instance()->getUASForId(selectedSystemID);
    if (uas)
    {
        QMap<int, QString> components = uas->getComponents();
        foreach (int id, components.keys())
        {
            QString name = components.value(id);
            ui->componentComboBox->addItem(name, id);
        }
    }
LM's avatar
LM committed
110 111 112 113 114 115 116 117 118 119 120
}

void QGCMAVLinkInspector::addComponent(int uas, int component, const QString& name)
{
    Q_UNUSED(component);
    Q_UNUSED(name);
    if (uas != selectedSystemID) return;

    rebuildComponentList();
}

121 122 123 124
/**
 * Reset the view. This entails clearing all data structures and resetting data from already-
 * received messages.
 */
125 126
void QGCMAVLinkInspector::clearView()
{
127 128 129 130 131 132 133
    uasTreeWidgetItems.clear();
    uasMsgTreeItems.clear();
    uasMavlinkStorage.clear();
    uasMessageHz.clear();
    uasMessageCount.clear();
    uasLastMessageUpdate.clear();

134
    onboardMessageInterval.clear();
135

136
    ui->treeWidget->clear();
137
    ui->rateTreeWidget->clear();
138 139
}

lm's avatar
lm committed
140 141
void QGCMAVLinkInspector::refreshView()
{
142 143 144
    QMap<int, mavlink_message_t* >::const_iterator ite;
    
    for(ite=uasMavlinkStorage.constBegin(); ite!=uasMavlinkStorage.constEnd();++ite)
lm's avatar
lm committed
145
    {
146
        for (int i = 0; i < 256; ++i)
lm's avatar
lm committed
147
        {
148 149 150 151 152 153 154 155 156 157
            mavlink_message_t* msg = ite.value()+i;
            // Ignore NULL values
            if (msg->msgid == 0xFF) continue;

            // Update the message frenquency

            // Get the previous frequency for low-pass filtering
            float msgHz = 0.0f;
            QMap<int, QMap<int, float>* >::const_iterator iteHz = uasMessageHz.find(msg->sysid);
            QMap<int, float>* uasMsgHz = iteHz.value();
lm's avatar
lm committed
158

159
            while((iteHz != uasMessageHz.end()) && (iteHz.key() == msg->sysid))
lm's avatar
lm committed
160
            {
161 162 163 164 165 166 167
                if(iteHz.value()->contains(msg->msgid))
                {
                    uasMsgHz = iteHz.value();
                    msgHz = iteHz.value()->value(msg->msgid);
                    break;
                }
                ++iteHz;
lm's avatar
lm committed
168 169
            }

170 171 172 173 174 175 176 177 178 179 180 181 182 183
            // Get the number of message received
            float msgCount = 0;
            QMap<int, QMap<int, unsigned int> * >::const_iterator iter = uasMessageCount.find(msg->sysid);
            QMap<int, unsigned int>* uasMsgCount = iter.value();
            while((iter != uasMessageCount.end()) && (iter.key()==msg->sysid))
            {
                if(iter.value()->contains(msg->msgid))
                {
                    msgCount = (float) iter.value()->value(msg->msgid);
                    uasMsgCount = iter.value();
                    break;
                }
                ++iter;
            }
lm's avatar
lm committed
184

185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231
            // Compute the new low-pass filtered frequency and update the message count
            msgHz = (1.0f-updateHzLowpass)* msgHz + updateHzLowpass*msgCount/((float)updateInterval/1000.0f);
            uasMsgHz->insert(msg->msgid,msgHz);
            uasMsgCount->insert(msg->msgid,(unsigned int) 0);

            // Update the tree view
            QString messageName("%1 (%2 Hz, #%3)");
            messageName = messageName.arg(messageInfo[msg->msgid].name).arg(msgHz, 3, 'f', 1).arg(msg->msgid);

            addUAStoTree(msg->sysid);

            // Look for the tree for the UAS sysid
            QMap<int, QTreeWidgetItem*>* msgTreeItems = uasMsgTreeItems.value(msg->sysid);
            if (!msgTreeItems)
            {
                // The UAS tree has not been created yet, no update
                return;
            }

            // Add the message with msgid to the tree if not done yet
            if(!msgTreeItems->contains(msg->msgid))
            {
                QStringList fields;
                fields << messageName;
                QTreeWidgetItem* widget = new QTreeWidgetItem();
                for (unsigned int i = 0; i < messageInfo[msg->msgid].num_fields; ++i)
                {
                    QTreeWidgetItem* field = new QTreeWidgetItem();
                    widget->addChild(field);
                }
                msgTreeItems->insert(msg->msgid,widget);
                QList<int> groupKeys = msgTreeItems->uniqueKeys();
                int insertIndex = groupKeys.indexOf(msg->msgid);
                uasTreeWidgetItems.value(msg->sysid)->insertChild(insertIndex,widget);
            }

            // Update the message
            QTreeWidgetItem* message = msgTreeItems->value(msg->msgid);
            if(message)
            {
                message->setFirstColumnSpanned(true);
                message->setData(0, Qt::DisplayRole, QVariant(messageName));
                for (unsigned int i = 0; i < messageInfo[msg->msgid].num_fields; ++i)
                {
                    updateField(msg->sysid,msg->msgid, i, message->child(i));
                }
            }
lm's avatar
lm committed
232 233
        }
    }
234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272

    if (selectedSystemID == 0 || selectedComponentID == 0)
    {
        return;
    }

    for (int i = 0; i < 256; ++i)//mavlink_message_t msg, receivedMessages)
    {
        const char* msgname = messageInfo[i].name;

        int namelen = strnlen(msgname, 5);

        if (namelen < 3) {
            continue;
        }

        if (!strcmp(msgname, "EMPTY")) {
            continue;
        }

        // Update the tree view
        QString messageName("%1");
        messageName = messageName.arg(msgname);
        if (!rateTreeWidgetItems.contains(i))
        {
            QStringList fields;
            fields << messageName;
            fields << QString("%1").arg(i);
            fields << "OFF / --- Hz";
            QTreeWidgetItem* widget = new QTreeWidgetItem(fields);
            widget->setFlags(widget->flags() | Qt::ItemIsEditable);
            rateTreeWidgetItems.insert(i, widget);
            ui->rateTreeWidget->addTopLevelItem(widget);
        }

        // Set Hz
        //QTreeWidgetItem* message = rateTreeWidgetItems.value(i);
        //message->setData(0, Qt::DisplayRole, QVariant(messageName));
    }
lm's avatar
lm committed
273 274
}

275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301
void QGCMAVLinkInspector::addUAStoTree(int sysId)
{
    if(!uasTreeWidgetItems.contains(sysId))
    {
        // Add the UAS to the main tree after it has been created
        UASInterface* uas = UASManager::instance()->getUASForId(sysId);

        if (uas)
        {
            QStringList idstring;
            if (uas->getUASName() == "")
            {
                idstring << tr("UAS ") + QString::number(uas->getUASID());
            }
            else
            {
                idstring << uas->getUASName();
            }
            QTreeWidgetItem* uasWidget = new QTreeWidgetItem(idstring);
            uasWidget->setFirstColumnSpanned(true);
            uasTreeWidgetItems.insert(sysId,uasWidget);
            ui->treeWidget->addTopLevelItem(uasWidget);
            uasMsgTreeItems.insert(sysId,new QMap<int, QTreeWidgetItem*>());
        }
    }
}

lm's avatar
lm committed
302 303 304
void QGCMAVLinkInspector::receiveMessage(LinkInterface* link,mavlink_message_t message)
{
    Q_UNUSED(link);
305 306 307 308 309 310 311 312 313 314 315

    quint64 receiveTime;

    // Create dynamically an array to store the messages for each UAS
    if(!uasMavlinkStorage.contains(message.sysid))
    {
        mavlink_message_t* msg = new mavlink_message_t[256];

        // Initialize the received data for all messages to invalid (0xFF)
        memset(msg,0xFF, sizeof(mavlink_message_t)*256);
        uasMavlinkStorage.insert(message.sysid,msg);
316 317
    }

318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335
    // Fill the slot with the message received
    memcpy(uasMavlinkStorage.value(message.sysid)+message.msgid,&message,sizeof(mavlink_message_t));

    // Looking if this message has already been received once
    bool msgFound = false;
    QMap<int, QMap<int, quint64>* >::const_iterator ite = uasLastMessageUpdate.find(message.sysid);
    QMap<int, quint64>* lastMsgUpdate = ite.value();
    while((ite != uasLastMessageUpdate.end()) && (ite.key() == message.sysid))
    {   
        if(ite.value()->contains(message.msgid))
        {
            msgFound = true;

            // Point to the found message
            lastMsgUpdate = ite.value();
            break;
        }
        ++ite;
336 337
    }

338 339 340 341
    receiveTime = QGC::groundTimeMilliseconds();

    // If the message doesn't exist, create a map for the frequency, message count and time of reception
    if(!msgFound)
342
    {
343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359
        // Create a map for the message frequency
        QMap<int, float>* messageHz = new QMap<int,float>;
        messageHz->insert(message.msgid,0.0f);
        uasMessageHz.insertMulti(message.sysid,messageHz);

        // Create a map for the message count
        QMap<int, unsigned int>* messagesCount = new QMap<int, unsigned int>;
        messagesCount->insert(message.msgid,0);
        uasMessageCount.insertMulti(message.sysid,messagesCount);

        // Create a map for the time of reception of the message
        QMap<int, quint64>* lastMessage = new QMap<int, quint64>;
        lastMessage->insert(message.msgid,receiveTime);
        uasLastMessageUpdate.insertMulti(message.sysid,lastMessage);

        // Point to the created message
        lastMsgUpdate = lastMessage;
360 361
    }

362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381
    // The message has been found/created
    if ((lastMsgUpdate->contains(message.msgid))&&(uasMessageCount.contains(message.sysid)))
    {
        // Looking for and updating the message count
        unsigned int count = 0;
        QMap<int, QMap<int, unsigned int>* >::const_iterator iter = uasMessageCount.find(message.sysid);
        QMap<int, unsigned int> * uasMsgCount = iter.value();
        while((iter != uasMessageCount.end()) && (iter.key() == message.sysid))
        {
            if(iter.value()->contains(message.msgid))
            {
                uasMsgCount = iter.value();
                count = uasMsgCount->value(message.msgid,0);
                uasMsgCount->insert(message.msgid,count+1);
                break;
            }
            ++iter;
        }
    }
    lastMsgUpdate->insert(message.msgid,receiveTime);
382

383 384
    if (selectedSystemID == 0 || selectedComponentID == 0)
    {
385 386 387
        return;
    }

388 389
    switch (message.msgid)
    {
390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431
        case MAVLINK_MSG_ID_DATA_STREAM:
            {
                mavlink_data_stream_t stream;
                mavlink_msg_data_stream_decode(&message, &stream);
                onboardMessageInterval.insert(stream.stream_id, stream.message_rate);
            }
            break;

    }
}

void QGCMAVLinkInspector::changeStreamInterval(int msgid, int interval) {
    //REQUEST_DATA_STREAM
    if (selectedSystemID == 0 || selectedComponentID == 0) {
        return;
    }

    mavlink_request_data_stream_t stream;
    stream.target_system = selectedSystemID;
    stream.target_component = selectedComponentID;
    stream.req_stream_id = msgid;
    stream.req_message_rate = interval;
    stream.start_stop = (interval > 0);

    mavlink_message_t msg;
    mavlink_msg_request_data_stream_encode(_protocol->getSystemId(), _protocol->getComponentId(), &msg, &stream);

    _protocol->sendMessage(msg);
}

void QGCMAVLinkInspector::rateTreeItemChanged(QTreeWidgetItem* paramItem, int column)
{
    if (paramItem && column > 0) {

        int key = paramItem->data(1, Qt::DisplayRole).toInt();
        QVariant value = paramItem->data(2, Qt::DisplayRole);
        float interval = 1000 / value.toFloat();

        qDebug() << "Stream " << key << "interval" << interval;

        changeStreamInterval(key, interval);
    }
lm's avatar
lm committed
432 433 434 435 436 437
}

QGCMAVLinkInspector::~QGCMAVLinkInspector()
{
    delete ui;
}
lm's avatar
lm committed
438

439
void QGCMAVLinkInspector::updateField(int sysid, int msgid, int fieldid, QTreeWidgetItem* item)
lm's avatar
lm committed
440 441 442
{
    // Add field tree widget item
    item->setData(0, Qt::DisplayRole, QVariant(messageInfo[msgid].fields[fieldid].name));
443
    uint8_t* m = ((uint8_t*)(uasMavlinkStorage.value(sysid)+msgid))+8;
lm's avatar
lm committed
444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492
    switch (messageInfo[msgid].fields[fieldid].type)
    {
    case MAVLINK_TYPE_CHAR:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            char* str = (char*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
            // Enforce null termination
            str[messageInfo[msgid].fields[fieldid].array_length-1] = '\0';
            QString string(str);
            item->setData(2, Qt::DisplayRole, "char");
            item->setData(1, Qt::DisplayRole, string);
        }
        else
        {
            // Single char
            char b = *((char*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
            item->setData(2, Qt::DisplayRole, QString("char[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
            item->setData(1, Qt::DisplayRole, b);
        }
        break;
    case MAVLINK_TYPE_UINT8_T:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            uint8_t* nums = m+messageInfo[msgid].fields[fieldid].wire_offset;
            // Enforce null termination
            QString tmp("%1, ");
            QString string;
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
            {
                string += tmp.arg(nums[j]);
            }
            item->setData(2, Qt::DisplayRole, QString("uint8_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
            item->setData(1, Qt::DisplayRole, string);
        }
        else
        {
            // Single value
            uint8_t u = *(m+messageInfo[msgid].fields[fieldid].wire_offset);
            item->setData(2, Qt::DisplayRole, "uint8_t");
            item->setData(1, Qt::DisplayRole, u);
        }
        break;
    case MAVLINK_TYPE_INT8_T:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            int8_t* nums = (int8_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
            // Enforce null termination
            QString tmp("%1, ");
            QString string;
Geoff Fink's avatar
Geoff Fink committed
493
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514
            {
                string += tmp.arg(nums[j]);
            }
            item->setData(2, Qt::DisplayRole, QString("int8_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
            item->setData(1, Qt::DisplayRole, string);
        }
        else
        {
            // Single value
            int8_t n = *((int8_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
            item->setData(2, Qt::DisplayRole, "int8_t");
            item->setData(1, Qt::DisplayRole, n);
        }
        break;
    case MAVLINK_TYPE_UINT16_T:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            uint16_t* nums = (uint16_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
            // Enforce null termination
            QString tmp("%1, ");
            QString string;
Geoff Fink's avatar
Geoff Fink committed
515
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536
            {
                string += tmp.arg(nums[j]);
            }
            item->setData(2, Qt::DisplayRole, QString("uint16_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
            item->setData(1, Qt::DisplayRole, string);
        }
        else
        {
            // Single value
            uint16_t n = *((uint16_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
            item->setData(2, Qt::DisplayRole, "uint16_t");
            item->setData(1, Qt::DisplayRole, n);
        }
        break;
    case MAVLINK_TYPE_INT16_T:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            int16_t* nums = (int16_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
            // Enforce null termination
            QString tmp("%1, ");
            QString string;
Geoff Fink's avatar
Geoff Fink committed
537
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558
            {
                string += tmp.arg(nums[j]);
            }
            item->setData(2, Qt::DisplayRole, QString("int16_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
            item->setData(1, Qt::DisplayRole, string);
        }
        else
        {
            // Single value
            int16_t n = *((int16_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
            item->setData(2, Qt::DisplayRole, "int16_t");
            item->setData(1, Qt::DisplayRole, n);
        }
        break;
    case MAVLINK_TYPE_UINT32_T:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            uint32_t* nums = (uint32_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
            // Enforce null termination
            QString tmp("%1, ");
            QString string;
Geoff Fink's avatar
Geoff Fink committed
559
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580
            {
                string += tmp.arg(nums[j]);
            }
            item->setData(2, Qt::DisplayRole, QString("uint32_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
            item->setData(1, Qt::DisplayRole, string);
        }
        else
        {
            // Single value
            float n = *((uint32_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
            item->setData(2, Qt::DisplayRole, "uint32_t");
            item->setData(1, Qt::DisplayRole, n);
        }
        break;
    case MAVLINK_TYPE_INT32_T:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            int32_t* nums = (int32_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
            // Enforce null termination
            QString tmp("%1, ");
            QString string;
Geoff Fink's avatar
Geoff Fink committed
581
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602
            {
                string += tmp.arg(nums[j]);
            }
            item->setData(2, Qt::DisplayRole, QString("int32_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
            item->setData(1, Qt::DisplayRole, string);
        }
        else
        {
            // Single value
            int32_t n = *((int32_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
            item->setData(2, Qt::DisplayRole, "int32_t");
            item->setData(1, Qt::DisplayRole, n);
        }
        break;
    case MAVLINK_TYPE_FLOAT:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            float* nums = (float*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
            // Enforce null termination
            QString tmp("%1, ");
            QString string;
Geoff Fink's avatar
Geoff Fink committed
603
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
604
            {
Geoff Fink's avatar
Geoff Fink committed
605
               string += tmp.arg(nums[j]);
lm's avatar
lm committed
606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624
            }
            item->setData(2, Qt::DisplayRole, QString("float[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
            item->setData(1, Qt::DisplayRole, string);
        }
        else
        {
            // Single value
            float f = *((float*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
            item->setData(2, Qt::DisplayRole, "float");
            item->setData(1, Qt::DisplayRole, f);
        }
        break;
    case MAVLINK_TYPE_DOUBLE:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            double* nums = (double*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
            // Enforce null termination
            QString tmp("%1, ");
            QString string;
Geoff Fink's avatar
Geoff Fink committed
625
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646
            {
                string += tmp.arg(nums[j]);
            }
            item->setData(2, Qt::DisplayRole, QString("double[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
            item->setData(1, Qt::DisplayRole, string);
        }
        else
        {
            // Single value
            double f = *((double*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
            item->setData(2, Qt::DisplayRole, "double");
            item->setData(1, Qt::DisplayRole, f);
        }
        break;
    case MAVLINK_TYPE_UINT64_T:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            uint64_t* nums = (uint64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
            // Enforce null termination
            QString tmp("%1, ");
            QString string;
Geoff Fink's avatar
Geoff Fink committed
647
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
648 649 650 651 652 653 654 655 656 657 658
            {
                string += tmp.arg(nums[j]);
            }
            item->setData(2, Qt::DisplayRole, QString("uint64_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
            item->setData(1, Qt::DisplayRole, string);
        }
        else
        {
            // Single value
            uint64_t n = *((uint64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
            item->setData(2, Qt::DisplayRole, "uint64_t");
pixhawk's avatar
pixhawk committed
659
            item->setData(1, Qt::DisplayRole, (quint64) n);
lm's avatar
lm committed
660 661 662 663 664 665 666 667 668
        }
        break;
    case MAVLINK_TYPE_INT64_T:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            int64_t* nums = (int64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
            // Enforce null termination
            QString tmp("%1, ");
            QString string;
Geoff Fink's avatar
Geoff Fink committed
669
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
670 671 672 673 674 675 676 677 678 679 680
            {
                string += tmp.arg(nums[j]);
            }
            item->setData(2, Qt::DisplayRole, QString("int64_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
            item->setData(1, Qt::DisplayRole, string);
        }
        else
        {
            // Single value
            int64_t n = *((int64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
            item->setData(2, Qt::DisplayRole, "int64_t");
pixhawk's avatar
pixhawk committed
681
            item->setData(1, Qt::DisplayRole, (qint64) n);
lm's avatar
lm committed
682 683 684 685
        }
        break;
    }
}