QGCMAVLinkInspector.cc 27.1 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"
5
#include "MultiVehicleManager.h"
6
#include "UAS.h"
7
#include "QGCApplication.h"
8

lm's avatar
lm committed
9 10 11 12
#include "ui_QGCMAVLinkInspector.h"

#include <QDebug>

13 14 15
const float QGCMAVLinkInspector::updateHzLowpass = 0.2f;
const unsigned int QGCMAVLinkInspector::updateInterval = 1000U;

16 17
QGCMAVLinkInspector::QGCMAVLinkInspector(const QString& title, QAction* action, MAVLinkProtocol* protocol, QWidget *parent) :
    QGCDockWidget(title, action, parent),
18
    _protocol(protocol),
LM's avatar
LM committed
19 20
    selectedSystemID(0),
    selectedComponentID(0),
lm's avatar
lm committed
21 22 23
    ui(new Ui::QGCMAVLinkInspector)
{
    ui->setupUi(this);
lm's avatar
lm committed
24

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

29 30 31
    // 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);
32

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

40 41 42 43 44 45
    // Set up the column headers for the rate listing
    QStringList rateHeader;
    rateHeader << tr("Name");
    rateHeader << tr("#ID");
    rateHeader << tr("Rate");
    ui->rateTreeWidget->setHeaderLabels(rateHeader);
46 47
    connect(ui->rateTreeWidget, &QTreeWidget::itemChanged,
            this, &QGCMAVLinkInspector::rateTreeItemChanged);
48 49
    ui->rateTreeWidget->hide();

50
    // Connect the UI
51 52 53 54 55 56
    connect(ui->systemComboBox, static_cast<void (QComboBox::*)(int)>(&QComboBox::currentIndexChanged),
            this, &QGCMAVLinkInspector::selectDropDownMenuSystem);
    connect(ui->componentComboBox, static_cast<void (QComboBox::*)(int)>(&QComboBox::currentIndexChanged),
            this, &QGCMAVLinkInspector::selectDropDownMenuComponent);

    connect(ui->clearButton, &QPushButton::clicked, this, &QGCMAVLinkInspector::clearView);
LM's avatar
LM committed
57

58
    // Connect external connections
59
    connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::vehicleAdded, this, &QGCMAVLinkInspector::_vehicleAdded);
60
    connect(protocol, &MAVLinkProtocol::messageReceived, this, &QGCMAVLinkInspector::receiveMessage);
LM's avatar
LM committed
61

62
    // Attach the UI's refresh rate to a timer.
63
    connect(&updateTimer, &QTimer::timeout, this, &QGCMAVLinkInspector::refreshView);
LM's avatar
LM committed
64
    updateTimer.start(updateInterval);
65 66
    
    loadSettings();
lm's avatar
lm committed
67 68
}

69
void QGCMAVLinkInspector::_vehicleAdded(Vehicle* vehicle)
LM's avatar
LM committed
70
{
71
    ui->systemComboBox->addItem(QString("Vehicle %1").arg(vehicle->id()), vehicle->id());
72 73

    // Add a tree for a new UAS
74
    addUAStoTree(vehicle->id());
LM's avatar
LM committed
75 76 77 78 79 80
}

void QGCMAVLinkInspector::selectDropDownMenuSystem(int dropdownid)
{
    selectedSystemID = ui->systemComboBox->itemData(dropdownid).toInt();
    rebuildComponentList();
81 82 83 84 85 86

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

void QGCMAVLinkInspector::selectDropDownMenuComponent(int dropdownid)
{
    selectedComponentID = ui->componentComboBox->itemData(dropdownid).toInt();
92 93 94 95 96 97

    if (selectedSystemID != 0 && selectedComponentID != 0) {
        ui->rateTreeWidget->show();
    } else {
        ui->rateTreeWidget->hide();
    }
LM's avatar
LM committed
98 99 100 101 102
}

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

105
    ui->componentComboBox->addItem(tr("All"), 0);
106 107

    // Fill
108
    Vehicle* vehicle = qgcApp()->toolbox()->multiVehicleManager()->getVehicleById(selectedSystemID);
109
    if (vehicle)
110
    {
111
        UASInterface* uas = vehicle->uas();
112 113 114 115 116 117 118
        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
119 120 121 122 123 124
}

void QGCMAVLinkInspector::addComponent(int uas, int component, const QString& name)
{
    Q_UNUSED(component);
    Q_UNUSED(name);
125
    
LM's avatar
LM committed
126 127 128 129 130
    if (uas != selectedSystemID) return;

    rebuildComponentList();
}

131 132 133 134
/**
 * Reset the view. This entails clearing all data structures and resetting data from already-
 * received messages.
 */
135 136
void QGCMAVLinkInspector::clearView()
{
137 138 139 140 141 142
    QMap<int, mavlink_message_t* >::iterator ite;
    for(ite=uasMessageStorage.begin(); ite!=uasMessageStorage.end();++ite)
    {
        delete ite.value();
        ite.value() = NULL;
    }
143
    uasMessageStorage.clear();
144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174

    QMap<int, QMap<int, QTreeWidgetItem*>* >::iterator iteMsg;
    for (iteMsg=uasMsgTreeItems.begin(); iteMsg!=uasMsgTreeItems.end();++iteMsg)
    {
        QMap<int, QTreeWidgetItem*>* msgTreeItems = iteMsg.value();

        QList<int> groupKeys = msgTreeItems->uniqueKeys();
        QList<int>::iterator listKeys;
        for (listKeys=groupKeys.begin();listKeys!=groupKeys.end();++listKeys)
        {
            delete msgTreeItems->take(*listKeys);
        }
    }
    uasMsgTreeItems.clear();

    QMap<int, QTreeWidgetItem* >::iterator iteTree;
    for(iteTree=uasTreeWidgetItems.begin(); iteTree!=uasTreeWidgetItems.end();++iteTree)
    {
        delete iteTree.value();
        iteTree.value() = NULL;
    }
    uasTreeWidgetItems.clear();
    
    QMap<int, QMap<int, float>* >::iterator iteHz;
    for (iteHz=uasMessageHz.begin(); iteHz!=uasMessageHz.end();++iteHz)
    {

        iteHz.value()->clear();
        delete iteHz.value();
        iteHz.value() = NULL;
    }
175
    uasMessageHz.clear();
176 177 178 179 180 181 182 183

    QMap<int, QMap<int, unsigned int>* >::iterator iteCount;
    for(iteCount=uasMessageCount.begin(); iteCount!=uasMessageCount.end();++iteCount)
    {
        iteCount.value()->clear();
        delete iteCount.value();
        iteCount.value() = NULL;
    }
184
    uasMessageCount.clear();
185 186 187 188 189 190 191 192

    QMap<int, QMap<int, quint64>* >::iterator iteLast;
    for(iteLast=uasLastMessageUpdate.begin(); iteLast!=uasLastMessageUpdate.end();++iteLast)
    {
        iteLast.value()->clear();
        delete iteLast.value();
        iteLast.value() = NULL;
    }
193 194
    uasLastMessageUpdate.clear();

195
    onboardMessageInterval.clear();
196

197
    ui->treeWidget->clear();
198
    ui->rateTreeWidget->clear();
199

200 201
}

lm's avatar
lm committed
202 203
void QGCMAVLinkInspector::refreshView()
{
204
    QMap<int, mavlink_message_t* >::const_iterator ite;
205

206
    for(ite=uasMessageStorage.constBegin(); ite!=uasMessageStorage.constEnd();++ite)
lm's avatar
lm committed
207
    {
208

209 210 211 212 213
        mavlink_message_t* msg = ite.value();
        // Ignore NULL values
        if (msg->msgid == 0xFF) continue;

        // Update the message frenquency
214

215 216 217 218
        // 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
219

220 221 222
        while((iteHz != uasMessageHz.end()) && (iteHz.key() == msg->sysid))
        {
            if(iteHz.value()->contains(msg->msgid))
lm's avatar
lm committed
223
            {
224 225 226
                uasMsgHz = iteHz.value();
                msgHz = iteHz.value()->value(msg->msgid);
                break;
lm's avatar
lm committed
227
            }
228 229
            ++iteHz;
        }
lm's avatar
lm committed
230

231 232 233 234
        // 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();
235

236 237 238
        while((iter != uasMessageCount.end()) && (iter.key()==msg->sysid))
        {
            if(iter.value()->contains(msg->msgid))
239
            {
240 241 242
                msgCount = (float) iter.value()->value(msg->msgid);
                uasMsgCount = iter.value();
                break;
243
            }
244 245
            ++iter;
        }
lm's avatar
lm committed
246

247 248 249 250
        // 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);
251

252 253 254
        // 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);
255

256
        addUAStoTree(msg->sysid);
257

258 259 260 261 262 263 264
        // 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;
        }
265

266 267 268 269 270 271 272
        // 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)
273
            {
274 275
                QTreeWidgetItem* field = new QTreeWidgetItem();
                widget->addChild(field);
276
            }
277 278 279 280 281
            msgTreeItems->insert(msg->msgid,widget);
            QList<int> groupKeys = msgTreeItems->uniqueKeys();
            int insertIndex = groupKeys.indexOf(msg->msgid);
            uasTreeWidgetItems.value(msg->sysid)->insertChild(insertIndex,widget);
        }
282

283 284 285 286 287 288 289
        // 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)
290
            {
291
                updateField(msg->sysid,msg->msgid, i, message->child(i));
292
            }
lm's avatar
lm committed
293 294
        }
    }
295 296 297 298 299 300 301 302 303 304

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

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

Don Gagne's avatar
Don Gagne committed
305
        size_t namelen = strnlen(msgname, 5);
306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333

        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
334 335
}

336 337 338 339 340
void QGCMAVLinkInspector::addUAStoTree(int sysId)
{
    if(!uasTreeWidgetItems.contains(sysId))
    {
        // Add the UAS to the main tree after it has been created
341
        Vehicle* vehicle = qgcApp()->toolbox()->multiVehicleManager()->getVehicleById(sysId);
342
        if (vehicle)
343
        {
344
            UASInterface* uas = vehicle->uas();
345
            QStringList idstring;
346
            idstring << QString("Vehicle %1").arg(uas->getUASID());
347 348 349 350 351 352 353 354 355
            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
356 357 358
void QGCMAVLinkInspector::receiveMessage(LinkInterface* link,mavlink_message_t message)
{
    Q_UNUSED(link);
359 360

    quint64 receiveTime;
361 362 363 364
    
    if (selectedSystemID != 0 && selectedSystemID != message.sysid) return;
    if (selectedComponentID != 0 && selectedComponentID != message.compid) return;

365
    // Create dynamically an array to store the messages for each UAS
366
    if (!uasMessageStorage.contains(message.sysid))
367
    {
368 369 370
        mavlink_message_t* msg = new mavlink_message_t;
        *msg = message;
        uasMessageStorage.insertMulti(message.sysid,msg);
371 372
    }

373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395
    bool msgFound = false;
    QMap<int, mavlink_message_t* >::const_iterator iteMsg = uasMessageStorage.find(message.sysid);
    mavlink_message_t* uasMessage = iteMsg.value();
    while((iteMsg != uasMessageStorage.end()) && (iteMsg.key() == message.sysid))
    {
        if (iteMsg.value()->msgid == message.msgid)
        {
            msgFound = true;
            uasMessage = iteMsg.value();
            break;
        }
        ++iteMsg;
    }
    if (!msgFound)
    {
        mavlink_message_t* msgIdMessage = new mavlink_message_t;
        *msgIdMessage = message;
        uasMessageStorage.insertMulti(message.sysid,msgIdMessage);
    }
    else
    {
        *uasMessage = message;
    }
396 397

    // Looking if this message has already been received once
398
    msgFound = false;
399 400 401 402 403 404 405 406 407 408 409 410 411
    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;
412 413
    }

414 415 416 417
    receiveTime = QGC::groundTimeMilliseconds();

    // If the message doesn't exist, create a map for the frequency, message count and time of reception
    if(!msgFound)
418
    {
419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435
        // 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;
436
    }
437
    else
438
    {
439 440
        // The message has been found/created
        if ((lastMsgUpdate->contains(message.msgid))&&(uasMessageCount.contains(message.sysid)))
441
        {
442 443 444 445 446
            // 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))
447
            {
448 449 450 451 452 453 454 455
                if(iter.value()->contains(message.msgid))
                {
                    uasMsgCount = iter.value();
                    count = uasMsgCount->value(message.msgid,0);
                    uasMsgCount->insert(message.msgid,count+1);
                    break;
                }
                ++iter;
456 457
            }
        }
458
        lastMsgUpdate->insert(message.msgid,receiveTime);
459
    }
460

461 462
    if (selectedSystemID == 0 || selectedComponentID == 0)
    {
463 464 465
        return;
    }

466 467
    switch (message.msgid)
    {
468 469 470 471 472 473 474 475 476 477 478
        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;

    }
}

479 480
void QGCMAVLinkInspector::changeStreamInterval(int msgid, int interval)
{
481 482 483 484 485 486 487 488 489 490 491 492 493 494 495
    //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);

Don Gagne's avatar
Don Gagne committed
496 497
#if 0
    // FIXME: Is this really used?
498
    _protocol->sendMessage(msg);
Don Gagne's avatar
Don Gagne committed
499
#endif
500 501 502 503 504 505 506 507 508 509 510 511 512 513
}

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
514 515 516 517
}

QGCMAVLinkInspector::~QGCMAVLinkInspector()
{
518
    clearView();
lm's avatar
lm committed
519 520
    delete ui;
}
lm's avatar
lm committed
521

522
void QGCMAVLinkInspector::updateField(int sysid, int msgid, int fieldid, QTreeWidgetItem* item)
lm's avatar
lm committed
523 524 525
{
    // Add field tree widget item
    item->setData(0, Qt::DisplayRole, QVariant(messageInfo[msgid].fields[fieldid].name));
526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544
    
    bool msgFound = false;
    QMap<int, mavlink_message_t* >::const_iterator iteMsg = uasMessageStorage.find(sysid);
    mavlink_message_t* uasMessage = iteMsg.value();
    while((iteMsg != uasMessageStorage.end()) && (iteMsg.key() == sysid))
    {
        if (iteMsg.value()->msgid == msgid)
        {
            msgFound = true;
            uasMessage = iteMsg.value();
            break;
        }
        ++iteMsg;
    }

    if (!msgFound)
    {
        return;
    }
545

546 547 548
    uint8_t* m = ((uint8_t*)uasMessage)+8;


lm's avatar
lm committed
549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597
    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
598
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619
            {
                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
620
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641
            {
                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
642
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663
            {
                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
664
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685
            {
                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
686
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707
            {
                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
708
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
709
            {
Geoff Fink's avatar
Geoff Fink committed
710
               string += tmp.arg(nums[j]);
lm's avatar
lm committed
711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729
            }
            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
730
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751
            {
                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
752
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
753 754 755 756 757 758 759 760 761 762 763
            {
                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
764
            item->setData(1, Qt::DisplayRole, (quint64) n);
lm's avatar
lm committed
765 766 767 768 769 770 771 772 773
        }
        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
774
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
775 776 777 778 779 780 781 782 783 784 785
            {
                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
786
            item->setData(1, Qt::DisplayRole, (qint64) n);
lm's avatar
lm committed
787 788 789 790
        }
        break;
    }
}