MAVLinkInspectorController.cc 26.4 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

#include "MAVLinkInspectorController.h"
#include "QGCApplication.h"
#include "MultiVehicleManager.h"
13
#include <QtCharts/QLineSeries>
14

15 16
QGC_LOGGING_CATEGORY(MAVLinkInspectorLog, "MAVLinkInspectorLog")

17 18 19 20
QT_CHARTS_USE_NAMESPACE

Q_DECLARE_METATYPE(QAbstractSeries*)

21
//-----------------------------------------------------------------------------
22
QGCMAVLinkMessageField::QGCMAVLinkMessageField(QGCMAVLinkMessage *parent, QString name, QString type)
23 24 25
    : QObject(parent)
    , _type(type)
    , _name(name)
26
    , _msg(parent)
27 28 29 30
{
    qCDebug(MAVLinkInspectorLog) << "Field:" << name << type;
}

31 32 33 34 35 36 37
//-----------------------------------------------------------------------------
QString
QGCMAVLinkMessageField::label()
{
    return QString(_msg->name() + ": " + _name);
}

38
//-----------------------------------------------------------------------------
39 40 41 42 43 44 45 46 47 48 49 50 51 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 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129
void
QGCMAVLinkMessageField::setSelectable(bool sel)
{
    if(_selectable != sel) {
        _selectable = sel;
        emit selectableChanged();
    }
}

//-----------------------------------------------------------------------------
void
QGCMAVLinkMessageField::setSelected(bool sel)
{
    if(_selected != sel) {
        _selected = sel;
        emit selectedChanged();
        _values.clear();
        _times.clear();
        _rangeMin  = 0;
        _rangeMax  = 0;
        _dataIndex = 0;
        emit rangeMinChanged();
        emit rangeMaxChanged();
        if(_selected) {
            _msg->msgCtl()->addChartField(this);
        } else {
            _msg->msgCtl()->delChartField(this);
        }
        _msg->select();
    }
}

//-----------------------------------------------------------------------------
void
QGCMAVLinkMessageField::updateValue(QString newValue, qreal v)
{
    if(_value != newValue) {
        _value = newValue;
        emit valueChanged();
    }
    if(_selected) {
        int count = _values.count();
        //-- Arbitrary limit of 1 minute of data at 50Hz for now
        if(count < (50 * 60)) {
            _values.append(v);
            _times.append(QGC::groundTimeMilliseconds());
        } else {
            if(_dataIndex >= count) _dataIndex = 0;
            _values[_dataIndex] = v;
            _times[_dataIndex]  = QGC::groundTimeMilliseconds();
            _dataIndex++;
        }
        qreal vmin  = std::numeric_limits<qreal>::max();
        qreal vmax  = std::numeric_limits<qreal>::min();
        for(int i = 0; i < _values.count(); i++) {
            qreal v = _values[i];
            if(vmax < v) vmax = v;
            if(vmin > v) vmin = v;
        }
        if(std::abs(_rangeMin - vmin) > 0.000001) {
            _rangeMin = vmin;
            emit rangeMinChanged();
        }
        if(std::abs(_rangeMax - vmax) > 0.000001) {
            _rangeMax = vmax;
            emit rangeMaxChanged();
        }
        _msg->msgCtl()->updateXRange();
        _updateSeries();
    }
}

//-----------------------------------------------------------------------------
void
QGCMAVLinkMessageField::_updateSeries()
{
    int count = _values.count();
    if (count > 1) {
        _series.clear();
        int idx = _dataIndex;
        for(int i = 0; i < count; i++, idx++) {
            if(idx >= count) idx = 0;
            QPointF p(_times[idx], _values[idx]);
            _series.append(p);
        }
        emit seriesChanged();
    }
}

//-----------------------------------------------------------------------------
QGCMAVLinkMessage::QGCMAVLinkMessage(MAVLinkInspectorController *parent, mavlink_message_t* message)
130
    : QObject(parent)
131
    , _msgCtl(parent)
132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160
{
    _message = *message;
    const mavlink_message_info_t* msgInfo = mavlink_get_message_info(message);
    if (!msgInfo) {
        qWarning() << QStringLiteral("QGCMAVLinkMessage NULL msgInfo msgid(%1)").arg(message->msgid);
        return;
    }
    _name = QString(msgInfo->name);
    qCDebug(MAVLinkInspectorLog) << "New Message:" << _name;
    for (unsigned int i = 0; i < msgInfo->num_fields; ++i) {
        QString type = QString("?");
        switch (msgInfo->fields[i].type) {
            case MAVLINK_TYPE_CHAR:     type = QString("char");     break;
            case MAVLINK_TYPE_UINT8_T:  type = QString("uint8_t");  break;
            case MAVLINK_TYPE_INT8_T:   type = QString("int8_t");   break;
            case MAVLINK_TYPE_UINT16_T: type = QString("uint16_t"); break;
            case MAVLINK_TYPE_INT16_T:  type = QString("int16_t");  break;
            case MAVLINK_TYPE_UINT32_T: type = QString("uint32_t"); break;
            case MAVLINK_TYPE_INT32_T:  type = QString("int32_t");  break;
            case MAVLINK_TYPE_FLOAT:    type = QString("float");    break;
            case MAVLINK_TYPE_DOUBLE:   type = QString("double");   break;
            case MAVLINK_TYPE_UINT64_T: type = QString("uint64_t"); break;
            case MAVLINK_TYPE_INT64_T:  type = QString("int64_t");  break;
        }
        QGCMAVLinkMessageField* f = new QGCMAVLinkMessageField(this, msgInfo->fields[i].name, type);
        _fields.append(f);
    }
}

161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180
//-----------------------------------------------------------------------------
void
QGCMAVLinkMessage::select()
{
    bool sel = false;
    for (int i = 0; i < _fields.count(); ++i) {
        QGCMAVLinkMessageField* f = qobject_cast<QGCMAVLinkMessageField*>(_fields.get(i));
        if(f) {
            if(f->selected()) {
                sel = true;
                break;
            }
        }
    }
    if(sel != _selected) {
        _selected = sel;
        emit selectedChanged();
    }
}

Gus Grubba's avatar
Gus Grubba committed
181 182 183 184 185 186 187 188 189 190
//-----------------------------------------------------------------------------
void
QGCMAVLinkMessage::updateFreq()
{
    quint64 msgCount = _count - _lastCount;
    _messageHz = (0.2 * _messageHz) + (0.8 * msgCount);
    _lastCount = _count;
    emit freqChanged();
}

191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211
//-----------------------------------------------------------------------------
void
QGCMAVLinkMessage::update(mavlink_message_t* message)
{
    _message = *message;
    _count++;
    const mavlink_message_info_t* msgInfo = mavlink_get_message_info(message);
    if (!msgInfo) {
        qWarning() << QStringLiteral("QGCMAVLinkMessage::update NULL msgInfo msgid(%1)").arg(message->msgid);
        return;
    }
    if(_fields.count() != static_cast<int>(msgInfo->num_fields)) {
        qWarning() << QStringLiteral("QGCMAVLinkMessage::update msgInfo field count mismatch msgid(%1)").arg(message->msgid);
        return;
    }
    uint8_t* m = reinterpret_cast<uint8_t*>(&message->payload64[0]);
    for (unsigned int i = 0; i < msgInfo->num_fields; ++i) {
        QGCMAVLinkMessageField* f = qobject_cast<QGCMAVLinkMessageField*>(_fields.get(static_cast<int>(i)));
        if(f) {
            switch (msgInfo->fields[i].type) {
            case MAVLINK_TYPE_CHAR:
212
                f->setSelectable(false);
213 214 215 216 217
                if (msgInfo->fields[i].array_length > 0) {
                    char* str = reinterpret_cast<char*>(m+ msgInfo->fields[i].wire_offset);
                    // Enforce null termination
                    str[msgInfo->fields[i].array_length - 1] = '\0';
                    QString v(str);
218
                    f->updateValue(v, 0);
219 220 221 222
                } else {
                    // Single char
                    char b = *(reinterpret_cast<char*>(m + msgInfo->fields[i].wire_offset));
                    QString v(b);
223
                    f->updateValue(v, 0);
224 225 226 227 228 229 230 231
                }
                break;
            case MAVLINK_TYPE_UINT8_T:
                if (msgInfo->fields[i].array_length > 0) {
                    uint8_t* nums = m+msgInfo->fields[i].wire_offset;
                    // Enforce null termination
                    QString tmp("%1, ");
                    QString string;
232
                    for (unsigned int j = 0; j < msgInfo->fields[i].array_length - 1; ++j) {
233 234
                        string += tmp.arg(nums[j]);
                    }
235 236
                    string += QString::number(nums[msgInfo->fields[i].array_length - 1]);
                    f->updateValue(string, static_cast<qreal>(nums[0]));
237 238 239
                } else {
                    // Single value
                    uint8_t u = *(m+msgInfo->fields[i].wire_offset);
240
                    f->updateValue(QString::number(u), static_cast<qreal>(u));
241 242 243 244 245 246 247 248
                }
                break;
            case MAVLINK_TYPE_INT8_T:
                if (msgInfo->fields[i].array_length > 0) {
                    int8_t* nums = reinterpret_cast<int8_t*>(m + msgInfo->fields[i].wire_offset);
                    // Enforce null termination
                    QString tmp("%1, ");
                    QString string;
249
                    for (unsigned int j = 0; j < msgInfo->fields[i].array_length - 1; ++j) {
250 251
                        string += tmp.arg(nums[j]);
                    }
252 253
                    string += QString::number(nums[msgInfo->fields[i].array_length - 1]);
                    f->updateValue(string, static_cast<qreal>(nums[0]));
254 255 256
                } else {
                    // Single value
                    int8_t n = *(reinterpret_cast<int8_t*>(m+msgInfo->fields[i].wire_offset));
257
                    f->updateValue(QString::number(n), static_cast<qreal>(n));
258 259 260 261 262 263 264 265
                }
                break;
            case MAVLINK_TYPE_UINT16_T:
                if (msgInfo->fields[i].array_length > 0) {
                    uint16_t* nums = reinterpret_cast<uint16_t*>(m + msgInfo->fields[i].wire_offset);
                    // Enforce null termination
                    QString tmp("%1, ");
                    QString string;
266
                    for (unsigned int j = 0; j < msgInfo->fields[i].array_length - 1; ++j) {
267 268
                        string += tmp.arg(nums[j]);
                    }
269 270
                    string += QString::number(nums[msgInfo->fields[i].array_length - 1]);
                    f->updateValue(string, static_cast<qreal>(nums[0]));
271 272 273
                } else {
                    // Single value
                    uint16_t n = *(reinterpret_cast<uint16_t*>(m + msgInfo->fields[i].wire_offset));
274
                    f->updateValue(QString::number(n), static_cast<qreal>(n));
275 276 277 278 279 280 281 282
                }
                break;
            case MAVLINK_TYPE_INT16_T:
                if (msgInfo->fields[i].array_length > 0) {
                    int16_t* nums = reinterpret_cast<int16_t*>(m + msgInfo->fields[i].wire_offset);
                    // Enforce null termination
                    QString tmp("%1, ");
                    QString string;
283
                    for (unsigned int j = 0; j < msgInfo->fields[i].array_length - 1; ++j) {
284 285
                        string += tmp.arg(nums[j]);
                    }
286 287
                    string += QString::number(nums[msgInfo->fields[i].array_length - 1]);
                    f->updateValue(string, static_cast<qreal>(nums[0]));
288 289 290
                } else {
                    // Single value
                    int16_t n = *(reinterpret_cast<int16_t*>(m + msgInfo->fields[i].wire_offset));
291
                    f->updateValue(QString::number(n), static_cast<qreal>(n));
292 293 294 295 296 297 298 299
                }
                break;
            case MAVLINK_TYPE_UINT32_T:
                if (msgInfo->fields[i].array_length > 0) {
                    uint32_t* nums = reinterpret_cast<uint32_t*>(m + msgInfo->fields[i].wire_offset);
                    // Enforce null termination
                    QString tmp("%1, ");
                    QString string;
300
                    for (unsigned int j = 0; j < msgInfo->fields[i].array_length - 1; ++j) {
301 302
                        string += tmp.arg(nums[j]);
                    }
303 304
                    string += QString::number(nums[msgInfo->fields[i].array_length - 1]);
                    f->updateValue(string, static_cast<qreal>(nums[0]));
305 306 307
                } else {
                    // Single value
                    uint32_t n = *(reinterpret_cast<uint32_t*>(m + msgInfo->fields[i].wire_offset));
Gus Grubba's avatar
Gus Grubba committed
308 309 310
                    //-- Special case
                    if(_message.msgid == MAVLINK_MSG_ID_SYSTEM_TIME) {
                        QDateTime d = QDateTime::fromMSecsSinceEpoch(static_cast<qint64>(n),Qt::UTC,0);
311
                        f->updateValue(d.toString("HH:mm:ss"), static_cast<qreal>(n));
Gus Grubba's avatar
Gus Grubba committed
312
                    } else {
313
                        f->updateValue(QString::number(n), static_cast<qreal>(n));
Gus Grubba's avatar
Gus Grubba committed
314
                    }
315 316 317 318 319 320 321 322
                }
                break;
            case MAVLINK_TYPE_INT32_T:
                if (msgInfo->fields[i].array_length > 0) {
                    int32_t* nums = reinterpret_cast<int32_t*>(m + msgInfo->fields[i].wire_offset);
                    // Enforce null termination
                    QString tmp("%1, ");
                    QString string;
323
                    for (unsigned int j = 0; j < msgInfo->fields[i].array_length - 1; ++j) {
324 325
                        string += tmp.arg(nums[j]);
                    }
326 327
                    string += QString::number(nums[msgInfo->fields[i].array_length - 1]);
                    f->updateValue(string, static_cast<qreal>(nums[0]));
328 329 330
                } else {
                    // Single value
                    int32_t n = *(reinterpret_cast<int32_t*>(m + msgInfo->fields[i].wire_offset));
331
                    f->updateValue(QString::number(n), static_cast<qreal>(n));
332 333 334 335 336 337 338 339
                }
                break;
            case MAVLINK_TYPE_FLOAT:
                if (msgInfo->fields[i].array_length > 0) {
                    float* nums = reinterpret_cast<float*>(m + msgInfo->fields[i].wire_offset);
                    // Enforce null termination
                    QString tmp("%1, ");
                    QString string;
340
                    for (unsigned int j = 0; j < msgInfo->fields[i].array_length - 1; ++j) {
341 342
                       string += tmp.arg(static_cast<double>(nums[j]));
                    }
343 344
                    string += QString::number(static_cast<double>(nums[msgInfo->fields[i].array_length - 1]));
                    f->updateValue(string, static_cast<qreal>(nums[0]));
345 346 347
                } else {
                    // Single value
                    float fv = *(reinterpret_cast<float*>(m + msgInfo->fields[i].wire_offset));
348
                    f->updateValue(QString::number(static_cast<double>(fv)), static_cast<qreal>(fv));
349 350 351 352 353 354 355 356
                }
                break;
            case MAVLINK_TYPE_DOUBLE:
                if (msgInfo->fields[i].array_length > 0) {
                    double* nums = reinterpret_cast<double*>(m + msgInfo->fields[i].wire_offset);
                    // Enforce null termination
                    QString tmp("%1, ");
                    QString string;
357
                    for (unsigned int j = 0; j < msgInfo->fields[i].array_length - 1; ++j) {
358 359
                        string += tmp.arg(nums[j]);
                    }
360 361
                    string += QString::number(static_cast<double>(nums[msgInfo->fields[i].array_length - 1]));
                    f->updateValue(string, static_cast<qreal>(nums[0]));
362 363 364
                } else {
                    // Single value
                    double d = *(reinterpret_cast<double*>(m + msgInfo->fields[i].wire_offset));
365
                    f->updateValue(QString::number(d), static_cast<qreal>(d));
366 367 368 369 370 371 372 373
                }
                break;
            case MAVLINK_TYPE_UINT64_T:
                if (msgInfo->fields[i].array_length > 0) {
                    uint64_t* nums = reinterpret_cast<uint64_t*>(m + msgInfo->fields[i].wire_offset);
                    // Enforce null termination
                    QString tmp("%1, ");
                    QString string;
374
                    for (unsigned int j = 0; j < msgInfo->fields[i].array_length - 1; ++j) {
375 376
                        string += tmp.arg(nums[j]);
                    }
377 378
                    string += QString::number(nums[msgInfo->fields[i].array_length - 1]);
                    f->updateValue(string, static_cast<qreal>(nums[0]));
379 380 381
                } else {
                    // Single value
                    uint64_t n = *(reinterpret_cast<uint64_t*>(m + msgInfo->fields[i].wire_offset));
Gus Grubba's avatar
Gus Grubba committed
382 383 384
                    //-- Special case
                    if(_message.msgid == MAVLINK_MSG_ID_SYSTEM_TIME) {
                        QDateTime d = QDateTime::fromMSecsSinceEpoch(n/1000,Qt::UTC,0);
385
                        f->updateValue(d.toString("yyyy MM dd HH:mm:ss"), static_cast<qreal>(n));
Gus Grubba's avatar
Gus Grubba committed
386
                    } else {
387
                        f->updateValue(QString::number(n), static_cast<qreal>(n));
Gus Grubba's avatar
Gus Grubba committed
388
                    }
389 390 391 392 393 394 395 396
                }
                break;
            case MAVLINK_TYPE_INT64_T:
                if (msgInfo->fields[i].array_length > 0) {
                    int64_t* nums = reinterpret_cast<int64_t*>(m + msgInfo->fields[i].wire_offset);
                    // Enforce null termination
                    QString tmp("%1, ");
                    QString string;
397
                    for (unsigned int j = 0; j < msgInfo->fields[i].array_length - 1; ++j) {
398 399
                        string += tmp.arg(nums[j]);
                    }
400 401
                    string += QString::number(nums[msgInfo->fields[i].array_length - 1]);
                    f->updateValue(string, static_cast<qreal>(nums[0]));
402 403 404
                } else {
                    // Single value
                    int64_t n = *(reinterpret_cast<int64_t*>(m + msgInfo->fields[i].wire_offset));
405
                    f->updateValue(QString::number(n), static_cast<qreal>(n));
406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423
                }
                break;
            }
        }
    }
    emit messageChanged();
}

//-----------------------------------------------------------------------------
QGCMAVLinkVehicle::QGCMAVLinkVehicle(QObject* parent, quint8 id)
    : QObject(parent)
    , _id(id)
{
    qCDebug(MAVLinkInspectorLog) << "New Vehicle:" << id;
}

//-----------------------------------------------------------------------------
QGCMAVLinkMessage*
Gus Grubba's avatar
Gus Grubba committed
424
QGCMAVLinkVehicle::findMessage(uint32_t id, uint8_t cid)
425 426 427 428
{
    for(int i = 0; i < _messages.count(); i++) {
        QGCMAVLinkMessage* m = qobject_cast<QGCMAVLinkMessage*>(_messages.get(i));
        if(m) {
Gus Grubba's avatar
Gus Grubba committed
429
            if(m->id() == id && m->cid() == cid) {
430 431 432 433 434 435 436
                return m;
            }
        }
    }
    return nullptr;
}

Gus Grubba's avatar
Gus Grubba committed
437 438 439 440 441 442 443 444 445 446 447
//-----------------------------------------------------------------------------
static bool
messages_sort(QObject* a, QObject* b)
{
    QGCMAVLinkMessage* aa = qobject_cast<QGCMAVLinkMessage*>(a);
    QGCMAVLinkMessage* bb = qobject_cast<QGCMAVLinkMessage*>(b);
    if(!aa || !bb) return false;
    if(aa->id() == bb->id()) return aa->cid() < bb->cid();
    return aa->id() < bb->id();
}

448 449 450 451 452
//-----------------------------------------------------------------------------
void
QGCMAVLinkVehicle::append(QGCMAVLinkMessage* message)
{
    _messages.append(message);
Gus Grubba's avatar
Gus Grubba committed
453 454 455 456 457 458 459 460 461
    //-- Sort messages by id and then cid
    if(_messages.count() > 0) {
        std::sort(_messages.objectList()->begin(), _messages.objectList()->end(), messages_sort);
        for(int i = 0; i < _messages.count(); i++) {
            QGCMAVLinkMessage* m = qobject_cast<QGCMAVLinkMessage*>(_messages.get(i));
            if(m) {
                emit m->indexChanged();
            }
        }
462
        _checkCompID(message);
Gus Grubba's avatar
Gus Grubba committed
463
    }
464 465 466
    emit messagesChanged();
}

467 468 469 470 471 472 473 474 475 476 477 478 479 480 481
//-----------------------------------------------------------------------------
void
QGCMAVLinkVehicle::_checkCompID(QGCMAVLinkMessage* message)
{
    if(_compIDsStr.isEmpty()) {
        _compIDsStr << tr("All");
    }
    if(!_compIDs.contains(static_cast<int>(message->cid()))) {
        int cid = static_cast<int>(message->cid());
        _compIDs.append(cid);
        _compIDsStr << QString::number(cid);
        emit compIDsChanged();
    }
}

482 483 484 485 486 487 488 489
//-----------------------------------------------------------------------------
MAVLinkInspectorController::MAVLinkInspectorController()
{
    MultiVehicleManager* multiVehicleManager = qgcApp()->toolbox()->multiVehicleManager();
    connect(multiVehicleManager, &MultiVehicleManager::vehicleAdded,   this, &MAVLinkInspectorController::_vehicleAdded);
    connect(multiVehicleManager, &MultiVehicleManager::vehicleRemoved, this, &MAVLinkInspectorController::_vehicleRemoved);
    MAVLinkProtocol* mavlinkProtocol = qgcApp()->toolbox()->mavlinkProtocol();
    connect(mavlinkProtocol, &MAVLinkProtocol::messageReceived, this, &MAVLinkInspectorController::_receiveMessage);
Gus Grubba's avatar
Gus Grubba committed
490 491 492 493
    connect(&_updateTimer, &QTimer::timeout, this, &MAVLinkInspectorController::_refreshFrequency);
    _updateTimer.start(1000);
    MultiVehicleManager *manager = qgcApp()->toolbox()->multiVehicleManager();
    connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &MAVLinkInspectorController::_setActiveVehicle);
494 495
    _rangeXMax = QDateTime::fromMSecsSinceEpoch(0);
    _rangeXMin = QDateTime::fromMSecsSinceEpoch(std::numeric_limits<qint64>::max());
496 497 498
    _timeScales << tr("5 Sec");
    _timeScales << tr("10 Sec");
    _timeScales << tr("30 Sec");
499
    _timeScales << tr("60 Sec");
500 501 502 503 504 505 506 507
}

//-----------------------------------------------------------------------------
MAVLinkInspectorController::~MAVLinkInspectorController()
{
    _reset();
}

Gus Grubba's avatar
Gus Grubba committed
508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525

//----------------------------------------------------------------------------------------
void
MAVLinkInspectorController::_setActiveVehicle(Vehicle* vehicle)
{
    if(vehicle) {
        QGCMAVLinkVehicle* v = _findVehicle(static_cast<uint8_t>(vehicle->id()));
        if(v) {
            _activeVehicle = v;
        } else {
            _activeVehicle = nullptr;
        }
    } else {
        _activeVehicle = nullptr;
    }
    emit activeVehiclesChanged();
}

526 527 528 529 530 531 532 533 534 535 536 537 538 539 540
//-----------------------------------------------------------------------------
QGCMAVLinkVehicle*
MAVLinkInspectorController::_findVehicle(uint8_t id)
{
    for(int i = 0; i < _vehicles.count(); i++) {
        QGCMAVLinkVehicle* v = qobject_cast<QGCMAVLinkVehicle*>(_vehicles.get(i));
        if(v) {
            if(v->id() == id) {
                return v;
            }
        }
    }
    return nullptr;
}

Gus Grubba's avatar
Gus Grubba committed
541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557
//-----------------------------------------------------------------------------
void
MAVLinkInspectorController::_refreshFrequency()
{
    for(int i = 0; i < _vehicles.count(); i++) {
        QGCMAVLinkVehicle* v = qobject_cast<QGCMAVLinkVehicle*>(_vehicles.get(i));
        if(v) {
            for(int i = 0; i < v->messages()->count(); i++) {
                QGCMAVLinkMessage* m = qobject_cast<QGCMAVLinkMessage*>(v->messages()->get(i));
                if(m) {
                    m->updateFreq();
                }
            }
        }
    }
}

558 559 560 561
//-----------------------------------------------------------------------------
void
MAVLinkInspectorController::_vehicleAdded(Vehicle* vehicle)
{
562 563
    QGCMAVLinkVehicle* v = _findVehicle(static_cast<uint8_t>(vehicle->id()));
    if(v) {
564
        v->messages()->clearAndDeleteContents();
565 566 567 568
        emit v->messagesChanged();
    } else {
        v = new QGCMAVLinkVehicle(this, static_cast<uint8_t>(vehicle->id()));
        _vehicles.append(v);
569
        _vehicleNames.append(tr("Vehicle %1").arg(vehicle->id()));
570 571
    }
    emit vehiclesChanged();
572 573 574 575 576 577
}

//-----------------------------------------------------------------------------
void
MAVLinkInspectorController::_vehicleRemoved(Vehicle* vehicle)
{
578 579 580 581
    QGCMAVLinkVehicle* v = _findVehicle(static_cast<uint8_t>(vehicle->id()));
    if(v) {
        v->deleteLater();
        _vehicles.removeOne(v);
582
        QString vs = tr("Vehicle %1").arg(vehicle->id());
583 584
        _vehicleNames.removeOne(vs);
        emit vehiclesChanged();
585 586 587 588 589
    }
}

//-----------------------------------------------------------------------------
void
590
MAVLinkInspectorController::_receiveMessage(LinkInterface*, mavlink_message_t message)
591
{
592 593 594 595 596
    QGCMAVLinkMessage* m = nullptr;
    QGCMAVLinkVehicle* v = _findVehicle(message.sysid);
    if(!v) {
        v = new QGCMAVLinkVehicle(this, message.sysid);
        _vehicles.append(v);
597
        _vehicleNames.append(tr("Vehicle %1").arg(message.sysid));
598
        emit vehiclesChanged();
Gus Grubba's avatar
Gus Grubba committed
599 600 601 602
        if(!_activeVehicle) {
            _activeVehicle = v;
            emit activeVehiclesChanged();
        }
603
    } else {
Gus Grubba's avatar
Gus Grubba committed
604
        m = v->findMessage(message.msgid, message.compid);
605
    }
606 607 608
    if(!m) {
        m = new QGCMAVLinkMessage(this, &message);
        v->append(m);
609
    } else {
610
        m->update(&message);
611 612 613 614 615 616 617 618
    }
}

//-----------------------------------------------------------------------------
void
MAVLinkInspectorController::_reset()
{
}
619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662

//-----------------------------------------------------------------------------
void
MAVLinkInspectorController::addChartField(QGCMAVLinkMessageField* field)
{
    QVariant f = QVariant::fromValue(field);
    for(int i = 0; i < _chartFields.count(); i++) {
        if(_chartFields.at(i) == f) {
            return;
        }
    }
    _chartFields.append(f);
    emit chartFieldCountChanged();
}

//-----------------------------------------------------------------------------
void
MAVLinkInspectorController::delChartField(QGCMAVLinkMessageField* field)
{
    QVariant f = QVariant::fromValue(field);
    for(int i = 0; i < _chartFields.count(); i++) {
        if(_chartFields.at(i) == f) {
            _chartFields.removeAt(i);
            emit chartFieldCountChanged();
            if(_chartFields.count() == 0) {
                _rangeXMax = QDateTime::fromMSecsSinceEpoch(0);
                _rangeXMin = QDateTime::fromMSecsSinceEpoch(std::numeric_limits<qint64>::max());
            }
            return;
        }
    }
}

//-----------------------------------------------------------------------------
void
MAVLinkInspectorController::updateSeries(int index, QAbstractSeries* series)
{
    if(index < _chartFields.count() && series) {
        QGCMAVLinkMessageField* f = qvariant_cast<QGCMAVLinkMessageField*>(_chartFields.at(index));
        QLineSeries* lineSeries = static_cast<QLineSeries*>(series);
        lineSeries->replace(f->series());
    }
}

663 664 665 666 667 668 669 670 671
//-----------------------------------------------------------------------------
void
MAVLinkInspectorController::setTimeScale(quint32 t)
{
    _timeScale = t;
    emit timeScaleChanged();
    updateXRange();
}

672 673 674 675
//-----------------------------------------------------------------------------
void
MAVLinkInspectorController::updateXRange()
{
676 677 678 679 680 681
    int ts = 5 * 1000;
    switch(_timeScale) {
        case 1: ts = 10 * 1000; break;
        case 2: ts = 30 * 1000; break;
        case 3: ts = 60 * 1000; break;
    }
682 683
    qint64 t = static_cast<qint64>(QGC::groundTimeMilliseconds());
    _rangeXMax = QDateTime::fromMSecsSinceEpoch(t);
684
    _rangeXMin = QDateTime::fromMSecsSinceEpoch(t - ts);
685 686 687
    emit rangeMinXChanged();
    emit rangeMaxXChanged();
}