QGCMAVLinkInspector.cc 19.6 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 29 30
	// 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);

	// Initialize the received data for all messages to invalid (0xFF)
31
    memset(receivedMessages, 0xFF, sizeof(mavlink_message_t)*256);
lm's avatar
lm committed
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 46 47 48 49
    // 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();

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

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

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

LM's avatar
LM committed
64 65 66 67 68 69 70 71 72
void QGCMAVLinkInspector::addSystem(UASInterface* uas)
{
    ui->systemComboBox->addItem(uas->getUASName(), uas->getUASID());
}

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);
LM's avatar
LM committed
98

99 100 101 102 103 104 105 106 107 108 109 110
//    // 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
111 112 113 114 115 116 117 118 119 120 121
}

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

    rebuildComponentList();
}

122 123 124 125
/**
 * Reset the view. This entails clearing all data structures and resetting data from already-
 * received messages.
 */
126 127
void QGCMAVLinkInspector::clearView()
{
128
    memset(receivedMessages, 0xFF, sizeof(mavlink_message_t)*256);
129
    onboardMessageInterval.clear();
130 131
	lastMessageUpdate.clear();
	messagesHz.clear();
132 133
    treeWidgetItems.clear();
    ui->treeWidget->clear();
134
    ui->rateTreeWidget->clear();
135 136
}

lm's avatar
lm committed
137 138
void QGCMAVLinkInspector::refreshView()
{
lm's avatar
lm committed
139
    for (int i = 0; i < 256; ++i)//mavlink_message_t msg, receivedMessages)
lm's avatar
lm committed
140
    {
lm's avatar
lm committed
141 142
        mavlink_message_t* msg = receivedMessages+i;
        // Ignore NULL values
143
        if (msg->msgid == 0xFF) continue;
lm's avatar
lm committed
144
        // Update the tree view
145
        QString messageName("%1 (%2 Hz, #%3)");
LM's avatar
LM committed
146 147 148 149
        float msgHz = (1.0f-updateHzLowpass)*messagesHz.value(msg->msgid, 0) + updateHzLowpass*((float)messageCount.value(msg->msgid, 0))/((float)updateInterval/1000.0f);
        messagesHz.insert(msg->msgid, msgHz);
        messageName = messageName.arg(messageInfo[msg->msgid].name).arg(msgHz, 3, 'f', 1).arg(msg->msgid);
        messageCount.insert(msg->msgid, 0);
lm's avatar
lm committed
150
        if (!treeWidgetItems.contains(msg->msgid))
lm's avatar
lm committed
151 152 153 154
        {
            QStringList fields;
            fields << messageName;
            QTreeWidgetItem* widget = new QTreeWidgetItem(fields);
lm's avatar
lm committed
155 156 157 158 159 160 161 162 163
            widget->setFirstColumnSpanned(true);

            for (unsigned int i = 0; i < messageInfo[msg->msgid].num_fields; ++i)
            {
                QTreeWidgetItem* field = new QTreeWidgetItem();
                widget->addChild(field);
            }

            treeWidgetItems.insert(msg->msgid, widget);
lm's avatar
lm committed
164 165 166
            ui->treeWidget->addTopLevelItem(widget);
        }

167
        // Set Hz
lm's avatar
lm committed
168
        QTreeWidgetItem* message = treeWidgetItems.value(msg->msgid);
169 170
        message->setFirstColumnSpanned(true);
        message->setData(0, Qt::DisplayRole, QVariant(messageName));
lm's avatar
lm committed
171 172 173 174 175
        for (unsigned int i = 0; i < messageInfo[msg->msgid].num_fields; ++i)
        {
            updateField(msg->msgid, i, message->child(i));
        }
    }
176 177 178 179 180 181 182 183 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

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

void QGCMAVLinkInspector::receiveMessage(LinkInterface* link,mavlink_message_t message)
{
    Q_UNUSED(link);
LM's avatar
LM committed
220 221
    if (selectedSystemID != 0 && selectedSystemID != message.sysid) return;
    if (selectedComponentID != 0 && selectedComponentID != message.compid) return;
lm's avatar
lm committed
222 223
    // Only overwrite if system filter is set
    memcpy(receivedMessages+message.msgid, &message, sizeof(mavlink_message_t));
224

225 226 227 228 229 230 231 232 233 234 235
    // Add not yet seen systems / components
    if (!systems.contains(message.sysid)) {
        systems.insert(message.sysid, message.sysid);
        ui->systemComboBox->addItem(tr("MAV%1").arg(message.sysid), message.sysid);
    }

    if (!components.contains(message.compid)) {
        components.insert(message.compid, message.compid);
        ui->componentComboBox->addItem(tr("COMP%1").arg(message.compid), message.compid);
    }

236 237 238
    quint64 receiveTime = QGC::groundTimeMilliseconds();
    if (lastMessageUpdate.contains(message.msgid))
    {
LM's avatar
LM committed
239 240
        int count = messageCount.value(message.msgid, 0);
        messageCount.insert(message.msgid, count+1);
241 242 243
    }

    lastMessageUpdate.insert(message.msgid, receiveTime);
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 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291

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

    switch (message.msgid) {
        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
292 293 294 295 296 297
}

QGCMAVLinkInspector::~QGCMAVLinkInspector()
{
    delete ui;
}
lm's avatar
lm committed
298 299 300 301 302 303 304 305 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 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352

void QGCMAVLinkInspector::updateField(int msgid, int fieldid, QTreeWidgetItem* item)
{
    // Add field tree widget item
    item->setData(0, Qt::DisplayRole, QVariant(messageInfo[msgid].fields[fieldid].name));
    uint8_t* m = ((uint8_t*)(receivedMessages+msgid))+8;
    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
353
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374
            {
                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
375
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396
            {
                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
397
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418
            {
                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
419
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440
            {
                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
441
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462
            {
                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
463
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
464
            {
Geoff Fink's avatar
Geoff Fink committed
465
               string += tmp.arg(nums[j]);
lm's avatar
lm committed
466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484
            }
            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
485
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506
            {
                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
507
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
508 509 510 511 512 513 514 515 516 517 518
            {
                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
519
            item->setData(1, Qt::DisplayRole, (quint64) n);
lm's avatar
lm committed
520 521 522 523 524 525 526 527 528
        }
        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
529
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
lm's avatar
lm committed
530 531 532 533 534 535 536 537 538 539 540
            {
                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
541
            item->setData(1, Qt::DisplayRole, (qint64) n);
lm's avatar
lm committed
542 543 544 545
        }
        break;
    }
}