QGCMAVLinkMessageSender.cc 19.6 KB
Newer Older
Lorenz Meier's avatar
Lorenz Meier committed
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20
#include "QGCMAVLinkMessageSender.h"
#include "ui_QGCMAVLinkMessageSender.h"
#include "MAVLinkProtocol.h"

QGCMAVLinkMessageSender::QGCMAVLinkMessageSender(MAVLinkProtocol* mavlink, QWidget *parent) :
    QWidget(parent),
    protocol(mavlink),
    ui(new Ui::QGCMAVLinkMessageSender)
{
    ui->setupUi(this);
    mavlink_message_info_t msg[256] = MAVLINK_MESSAGE_INFO;
    memcpy(messageInfo, msg, sizeof(mavlink_message_info_t)*256);

    QStringList header;
    header << tr("Name");
    header << tr("Value");
    header << tr("Type");
    ui->treeWidget->setHeaderLabels(header);
    createTreeView();
    connect(&refreshTimer, SIGNAL(timeout()), this, SLOT(refresh()));
21 22 23
    //refreshTimer.start(1000); // Refresh at 1 Hz interval

    connect(ui->sendButton, SIGNAL(pressed()), this, SLOT(sendMessage()));
Lorenz Meier's avatar
Lorenz Meier committed
24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39
}

void QGCMAVLinkMessageSender::refresh()
{
    // Send messages
    foreach (unsigned int i, managementItems.keys())
    {
        if (!sendTimers.contains(i))
        {
            //sendTimers.insert(i, new QTimer())
        }
    }

    // ui->treeWidget->topLevelItem(0)->children();
}

40 41
bool QGCMAVLinkMessageSender::sendMessage()
{
42
    return sendMessage(ui->messageIdSpinBox->value());
43 44
}

Lorenz Meier's avatar
Lorenz Meier committed
45 46
bool QGCMAVLinkMessageSender::sendMessage(unsigned int msgid)
{
47 48
    QString msgname(messageInfo[msgid].name);
    if (msgid == 0 || msgid > 255 || messageInfo[msgid].name == NULL || msgname.compare(QString("EMPTY")))
49 50 51
    {
        return false;
    }
Lorenz Meier's avatar
Lorenz Meier committed
52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83
    bool result = true;

    if (treeWidgetItems.contains(msgid))
    {
        // Fill message fields

        mavlink_message_t msg;
        QList<QTreeWidgetItem*> fields;// = treeWidgetItems.value(msgid)->;

        for (unsigned int i = 0; i < messageInfo[msgid].num_fields; ++i)
        {
            QTreeWidgetItem* field = fields.at(i);
            int fieldid = i;
            uint8_t* m = ((uint8_t*)(&msg))+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);
                    // Copy data
                    QString string = field->data(1, Qt::DisplayRole).toString();
                    // Copy string size
                    int len = qMin((unsigned int)string.length(), messageInfo[msgid].fields[fieldid].array_length);
                    memcpy(str, string.toStdString().c_str(), len);
                    // Enforce null termination
                    str[len-1] = '\0';
                }
                else
                {
                    // Single char
                    char* b = ((char*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
84
                    *b = field->data(1, Qt::DisplayRole).toChar().toLatin1();
Lorenz Meier's avatar
Lorenz Meier committed
85 86 87 88 89 90 91 92
                }
                break;
            case MAVLINK_TYPE_UINT8_T:
                if (messageInfo[msgid].fields[fieldid].array_length > 0)
                {
                    uint8_t* nums = m+messageInfo[msgid].fields[fieldid].wire_offset;
                    for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
                    {
93
                        if ((unsigned int)(field->data(1, Qt::DisplayRole).toString().split(" ").size()) > j)
Lorenz Meier's avatar
Lorenz Meier committed
94 95 96 97 98 99 100 101 102
                        {
                            nums[j] = field->data(1, Qt::DisplayRole).toString().split(" ").at(j).toInt();
                        }
                    }
                }
                else
                {
                    // Single value
                    uint8_t* u = (m+messageInfo[msgid].fields[fieldid].wire_offset);
103
                    *u = field->data(1, Qt::DisplayRole).toChar().toLatin1();
Lorenz Meier's avatar
Lorenz Meier committed
104 105
                }
                break;
106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121
            case MAVLINK_TYPE_INT8_T:
                if (messageInfo[msgid].fields[fieldid].array_length > 0)
                {
                    int8_t* nums = reinterpret_cast<int8_t*>((m+messageInfo[msgid].fields[fieldid].wire_offset));
                    for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
                    {
                        if ((unsigned int)(field->data(1, Qt::DisplayRole).toString().split(" ").size()) > j)
                        {
                            nums[j] = field->data(1, Qt::DisplayRole).toString().split(" ").at(j).toInt();
                        }
                    }
                }
                else
                {
                    // Single value
                    int8_t* u = reinterpret_cast<int8_t*>(m+messageInfo[msgid].fields[fieldid].wire_offset);
122
                    *u = field->data(1, Qt::DisplayRole).toChar().toLatin1();
123 124
                }
                break;
125
            case MAVLINK_TYPE_INT16_T:
126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144
            case MAVLINK_TYPE_UINT16_T:
                if (messageInfo[msgid].fields[fieldid].array_length > 0)
                {
                    uint16_t* nums = reinterpret_cast<uint16_t*>(m+messageInfo[msgid].fields[fieldid].wire_offset);
                    for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
                    {
                        if ((unsigned int)(field->data(1, Qt::DisplayRole).toString().split(" ").size()) > j)
                        {
                            nums[j] = field->data(1, Qt::DisplayRole).toString().split(" ").at(j).toUInt();
                        }
                    }
                }
                else
                {
                    // Single value
                    uint16_t* u = reinterpret_cast<uint16_t*>(m+messageInfo[msgid].fields[fieldid].wire_offset);
                    *u = field->data(1, Qt::DisplayRole).toUInt();
                }
                break;
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 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 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222
            case MAVLINK_TYPE_INT32_T:
            case MAVLINK_TYPE_UINT32_T:
                if (messageInfo[msgid].fields[fieldid].array_length > 0)
                {
                    int32_t* nums = reinterpret_cast<int32_t*>(m+messageInfo[msgid].fields[fieldid].wire_offset);
                    for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
                    {
                        if ((unsigned int)(field->data(1, Qt::DisplayRole).toString().split(" ").size()) > j)
                        {
                            nums[j] = field->data(1, Qt::DisplayRole).toString().split(" ").at(j).toUInt();
                        }
                    }
                }
                else
                {
                    // Single value
                    int32_t* u = reinterpret_cast<int32_t*>(m+messageInfo[msgid].fields[fieldid].wire_offset);
                    *u = field->data(1, Qt::DisplayRole).toUInt();
                }
                break;
            case MAVLINK_TYPE_INT64_T:
            case MAVLINK_TYPE_UINT64_T:
                if (messageInfo[msgid].fields[fieldid].array_length > 0)
                {
                    int64_t* nums = reinterpret_cast<int64_t*>(m+messageInfo[msgid].fields[fieldid].wire_offset);
                    for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
                    {
                        if ((unsigned int)(field->data(1, Qt::DisplayRole).toString().split(" ").size()) > j)
                        {
                            nums[j] = field->data(1, Qt::DisplayRole).toString().split(" ").at(j).toULongLong();
                        }
                    }
                }
                else
                {
                    // Single value
                    int64_t* u = reinterpret_cast<int64_t*>(m+messageInfo[msgid].fields[fieldid].wire_offset);
                    *u = field->data(1, Qt::DisplayRole).toULongLong();
                }
                break;
            case MAVLINK_TYPE_FLOAT:
                if (messageInfo[msgid].fields[fieldid].array_length > 0)
                {
                    float* nums = reinterpret_cast<float*>(m+messageInfo[msgid].fields[fieldid].wire_offset);
                    for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
                    {
                        if ((unsigned int)(field->data(1, Qt::DisplayRole).toString().split(" ").size()) > j)
                        {
                            nums[j] = field->data(1, Qt::DisplayRole).toString().split(" ").at(j).toFloat();
                        }
                    }
                }
                else
                {
                    // Single value
                    float* u = reinterpret_cast<float*>(m+messageInfo[msgid].fields[fieldid].wire_offset);
                    *u = field->data(1, Qt::DisplayRole).toFloat();
                }
                break;
            case MAVLINK_TYPE_DOUBLE:
                if (messageInfo[msgid].fields[fieldid].array_length > 0)
                {
                    double* nums = reinterpret_cast<double*>(m+messageInfo[msgid].fields[fieldid].wire_offset);
                    for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
                    {
                        if ((unsigned int)(field->data(1, Qt::DisplayRole).toString().split(" ").size()) > j)
                        {
                            nums[j] = field->data(1, Qt::DisplayRole).toString().split(" ").at(j).toDouble();
                        }
                    }
                }
                else
                {
                    // Single value
                    double* u = reinterpret_cast<double*>(m+messageInfo[msgid].fields[fieldid].wire_offset);
                    *u = field->data(1, Qt::DisplayRole).toDouble();
                }
                break;
Lorenz Meier's avatar
Lorenz Meier committed
223 224
            }
        }
225 226 227

        // Send message
        protocol->sendMessage(msg);
Lorenz Meier's avatar
Lorenz Meier committed
228 229 230 231 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 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 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 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 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 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 432 433 434 435 436 437 438 439 440 441 442 443 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 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510
    }
    else
    {
        result = false;
    }

    return result;
}

QGCMAVLinkMessageSender::~QGCMAVLinkMessageSender()
{
    delete ui;
}

void QGCMAVLinkMessageSender::createTreeView()
{
    for (int i = 0; i < 256; ++i)//mavlink_message_t msg, receivedMessages)
    {
        // Update the tree view
        QString messageName("%1 (%2 Hz, #%3)");
        float msgHz = messagesHz.value(i, 0);

        // Ignore non-existent messages
        if (QString(messageInfo[i].name) == "EMPTY") continue;

        messageName = messageName.arg(messageInfo[i].name).arg(msgHz, 3, 'f', 1).arg(i);
        if (!treeWidgetItems.contains(i))
        {
            QStringList fields;
            fields << messageName;
            QTreeWidgetItem* widget = new QTreeWidgetItem(fields);
            widget->setFirstColumnSpanned(true);

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

            treeWidgetItems.insert(i, widget);
            ui->treeWidget->addTopLevelItem(widget);


            QTreeWidgetItem* message = widget;//treeWidgetItems.value(msg->msgid);
            message->setFirstColumnSpanned(true);
            message->setData(0, Qt::DisplayRole, QVariant(messageName));
            for (unsigned int j = 0; j < messageInfo[i].num_fields; ++j)
            {
                createField(i, j, message->child(j));
            }
            // Add management fields, such as update rate and send button
            //            QTreeWidgetItem* management = new QTreeWidgetItem();
            //            widget->addChild(management);
            //            management->setData(0, Qt::DisplayRole, "Rate:");
            //            management->setData(1, Qt::DisplayRole, 0);
            //            management->setData(2, Qt::DisplayRole, "Hz");
            //            managementItems.insert(i, management);
        }
    }
}

void QGCMAVLinkMessageSender::createField(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)
        {
            item->setData(2, Qt::DisplayRole, "char");
            item->setData(1, Qt::DisplayRole, "");
        }
        else
        {
            // Single char
            item->setData(2, Qt::DisplayRole, QString("char[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
            item->setData(1, Qt::DisplayRole, "");
        }
        break;
    case MAVLINK_TYPE_UINT8_T:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            // Enforce null termination
            QString tmp("%1, ");
            QString string;
            for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
            {
                string += tmp.arg(0);
            }
            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
            item->setData(2, Qt::DisplayRole, "uint8_t");
            item->setData(1, Qt::DisplayRole, 0);
        }
        break;
    case MAVLINK_TYPE_INT8_T:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            // Enforce null termination
            QString tmp("%1, ");
            QString string;
            for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
            {
                string += tmp.arg(0);
            }
            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
            item->setData(2, Qt::DisplayRole, "int8_t");
            item->setData(1, Qt::DisplayRole, 0);
        }
        break;
    case MAVLINK_TYPE_UINT16_T:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            // Enforce null termination
            QString tmp("%1, ");
            QString string;
            for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
            {
                string += tmp.arg(0);
            }
            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
            item->setData(2, Qt::DisplayRole, "uint16_t");
            item->setData(1, Qt::DisplayRole, 0);
        }
        break;
    case MAVLINK_TYPE_INT16_T:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            // Enforce null termination
            QString tmp("%1, ");
            QString string;
            for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
            {
                string += tmp.arg(0);
            }
            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
            item->setData(2, Qt::DisplayRole, "int16_t");
            item->setData(1, Qt::DisplayRole, 0);
        }
        break;
    case MAVLINK_TYPE_UINT32_T:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            // Enforce null termination
            QString tmp("%1, ");
            QString string;
            for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
            {
                string += tmp.arg(0);
            }
            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
            item->setData(2, Qt::DisplayRole, "uint32_t");
            item->setData(1, Qt::DisplayRole, 0);
        }
        break;
    case MAVLINK_TYPE_INT32_T:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            // Enforce null termination
            QString tmp("%1, ");
            QString string;
            for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
            {
                string += tmp.arg(0);
            }
            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
            item->setData(2, Qt::DisplayRole, "int32_t");
            item->setData(1, Qt::DisplayRole, 0);
        }
        break;
    case MAVLINK_TYPE_FLOAT:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            // Enforce null termination
            QString tmp("%1, ");
            QString string;
            for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
            {
                string += tmp.arg(0.0f);
            }
            item->setData(2, Qt::DisplayRole, QString("float[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
            item->setData(1, Qt::DisplayRole, string);
        }
        else
        {
            // Single value
            item->setData(2, Qt::DisplayRole, "float");
            item->setData(1, Qt::DisplayRole, 0.0f);
        }
        break;
    case MAVLINK_TYPE_DOUBLE:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            // Enforce null termination
            QString tmp("%1, ");
            QString string;
            for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
            {
                string += tmp.arg(0);
            }
            item->setData(2, Qt::DisplayRole, QString("double[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
            item->setData(1, Qt::DisplayRole, string);
        }
        else
        {
            // Single value
            item->setData(2, Qt::DisplayRole, "double");
            item->setData(1, Qt::DisplayRole, 0.0);
        }
        break;
    case MAVLINK_TYPE_UINT64_T:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            // Enforce null termination
            QString tmp("%1, ");
            QString string;
            for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
            {
                string += tmp.arg(0);
            }
            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
            item->setData(2, Qt::DisplayRole, "uint64_t");
            item->setData(1, Qt::DisplayRole, (quint64) 0);
        }
        break;
    case MAVLINK_TYPE_INT64_T:
        if (messageInfo[msgid].fields[fieldid].array_length > 0)
        {
            // Enforce null termination
            QString tmp("%1, ");
            QString string;
            for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
            {
                string += tmp.arg(0);
            }
            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
            item->setData(2, Qt::DisplayRole, "int64_t");
            item->setData(1, Qt::DisplayRole, (qint64) 0);
        }
        break;
    }
}