MAVLinkInspectorController.cc 33.3 KB
Newer Older
1 2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8 9 10 11 12
 *
 * 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*)

Gus Grubba's avatar
Gus Grubba committed
21 22
#define UPDATE_FREQUENCY (1000 / 15)    // 15Hz

23
//-----------------------------------------------------------------------------
24
QGCMAVLinkMessageField::QGCMAVLinkMessageField(QGCMAVLinkMessage *parent, QString name, QString type)
25 26 27
    : QObject(parent)
    , _type(type)
    , _name(name)
28
    , _msg(parent)
29 30
{
    qCDebug(MAVLinkInspectorLog) << "Field:" << name << type;
Gus Grubba's avatar
Gus Grubba committed
31 32
}

33 34
//-----------------------------------------------------------------------------
void
35
QGCMAVLinkMessageField::addSeries(MAVLinkChartController* chart, QAbstractSeries* series)
Gus Grubba's avatar
Gus Grubba committed
36
{
37
    if(!_pSeries) {
38
        _chart = chart;
39 40 41
        _pSeries = series;
        emit seriesChanged();
        _dataIndex = 0;
Gus Grubba's avatar
Gus Grubba committed
42
        _msg->updateFieldSelection();
Gus Grubba's avatar
Gus Grubba committed
43 44 45 46 47
    }
}

//-----------------------------------------------------------------------------
void
48
QGCMAVLinkMessageField::delSeries()
Gus Grubba's avatar
Gus Grubba committed
49
{
50 51 52 53 54
    if(_pSeries) {
        _values.clear();
        QLineSeries* lineSeries = static_cast<QLineSeries*>(_pSeries);
        lineSeries->replace(_values);
        _pSeries = nullptr;
55
        _chart   = nullptr;
56
        emit seriesChanged();
Gus Grubba's avatar
Gus Grubba committed
57
        _msg->updateFieldSelection();
Gus Grubba's avatar
Gus Grubba committed
58
    }
59 60
}

61 62 63 64
//-----------------------------------------------------------------------------
QString
QGCMAVLinkMessageField::label()
{
65
    //-- Label is message name + field name
66 67 68
    return QString(_msg->name() + ": " + _name);
}

69
//-----------------------------------------------------------------------------
70 71 72 73 74 75 76 77 78
void
QGCMAVLinkMessageField::setSelectable(bool sel)
{
    if(_selectable != sel) {
        _selectable = sel;
        emit selectableChanged();
    }
}

79 80 81 82 83 84 85 86 87
//-----------------------------------------------------------------------------
int
QGCMAVLinkMessageField::chartIndex()
{
    if(_chart)
        return _chart->chartIndex();
    return 0;
}

88 89 90 91 92 93 94 95
//-----------------------------------------------------------------------------
void
QGCMAVLinkMessageField::updateValue(QString newValue, qreal v)
{
    if(_value != newValue) {
        _value = newValue;
        emit valueChanged();
    }
96
    if(_pSeries && _chart) {
97 98 99
        int count = _values.count();
        //-- Arbitrary limit of 1 minute of data at 50Hz for now
        if(count < (50 * 60)) {
Gus Grubba's avatar
Gus Grubba committed
100
            QPointF p(QGC::bootTimeMilliseconds(), v);
101
            _values.append(p);
102 103
        } else {
            if(_dataIndex >= count) _dataIndex = 0;
Gus Grubba's avatar
Gus Grubba committed
104
            _values[_dataIndex].setX(QGC::bootTimeMilliseconds());
105
            _values[_dataIndex].setY(v);
106 107
            _dataIndex++;
        }
Gus Grubba's avatar
Gus Grubba committed
108
        //-- Auto Range
109
        if(_chart->rangeYIndex() == 0) {
Gus Grubba's avatar
Gus Grubba committed
110 111 112
            qreal vmin  = std::numeric_limits<qreal>::max();
            qreal vmax  = std::numeric_limits<qreal>::min();
            for(int i = 0; i < _values.count(); i++) {
113
                qreal v = _values[i].y();
Gus Grubba's avatar
Gus Grubba committed
114 115 116
                if(vmax < v) vmax = v;
                if(vmin > v) vmin = v;
            }
117
            bool changed = false;
Gus Grubba's avatar
Gus Grubba committed
118 119
            if(std::abs(_rangeMin - vmin) > 0.000001) {
                _rangeMin = vmin;
120
                changed = true;
Gus Grubba's avatar
Gus Grubba committed
121 122 123
            }
            if(std::abs(_rangeMax - vmax) > 0.000001) {
                _rangeMax = vmax;
124 125 126
                changed = true;
            }
            if(changed) {
127
                _chart->updateYRange();
Gus Grubba's avatar
Gus Grubba committed
128
            }
129 130 131 132 133 134
        }
    }
}

//-----------------------------------------------------------------------------
void
Gus Grubba's avatar
Gus Grubba committed
135
QGCMAVLinkMessageField::updateSeries()
136 137 138
{
    int count = _values.count();
    if (count > 1) {
Gus Grubba's avatar
Gus Grubba committed
139 140 141 142 143 144 145 146
        QList<QPointF> s;
        s.reserve(count);
        int idx = _dataIndex;
        for(int i = 0; i < count; i++, idx++) {
            if(idx >= count) idx = 0;
            QPointF p(_values[idx]);
            s.append(p);
        }
147
        QLineSeries* lineSeries = static_cast<QLineSeries*>(_pSeries);
Gus Grubba's avatar
Gus Grubba committed
148
        lineSeries->replace(s);
149 150 151 152
    }
}

//-----------------------------------------------------------------------------
153
QGCMAVLinkMessage::QGCMAVLinkMessage(QObject *parent, mavlink_message_t* message)
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
    : QObject(parent)
{
    _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);
    }
182
    update(message);
183 184
}

185 186 187 188 189 190
//-----------------------------------------------------------------------------
QGCMAVLinkMessage::~QGCMAVLinkMessage()
{
    _fields.clearAndDeleteContents();
}

191 192
//-----------------------------------------------------------------------------
void
Gus Grubba's avatar
Gus Grubba committed
193
QGCMAVLinkMessage::updateFieldSelection()
194 195 196 197 198 199 200 201 202 203 204
{
    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;
            }
        }
    }
Gus Grubba's avatar
Gus Grubba committed
205 206 207
    if(sel != _fieldSelected) {
        _fieldSelected = sel;
        emit fieldSelectedChanged();
208 209 210
    }
}

Gus Grubba's avatar
Gus Grubba committed
211 212 213 214 215 216 217 218 219 220
//-----------------------------------------------------------------------------
void
QGCMAVLinkMessage::updateFreq()
{
    quint64 msgCount = _count - _lastCount;
    _messageHz = (0.2 * _messageHz) + (0.8 * msgCount);
    _lastCount = _count;
    emit freqChanged();
}

221 222 223 224 225
//-----------------------------------------------------------------------------
void
QGCMAVLinkMessage::update(mavlink_message_t* message)
{
    _count++;
226

227
    _message = *message;
228 229 230 231 232 233 234 235 236 237 238 239 240
    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) {
241 242 243
            const unsigned int offset = msgInfo->fields[i].wire_offset;
            const unsigned int array_length = msgInfo->fields[i].array_length;
            static const unsigned int array_buffer_length = (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_CHECKSUM_BYTES + 7);
244 245
            switch (msgInfo->fields[i].type) {
            case MAVLINK_TYPE_CHAR:
246
                f->setSelectable(false);
247 248
                if (array_length > 0) {
                    char* str = reinterpret_cast<char*>(m + offset);
249
                    // Enforce null termination
250
                    str[array_length - 1] = '\0';
251
                    QString v(str);
252
                    f->updateValue(v, 0);
253 254
                } else {
                    // Single char
255
                    char b = *(reinterpret_cast<char*>(m + offset));
256
                    QString v(b);
257
                    f->updateValue(v, 0);
258 259 260
                }
                break;
            case MAVLINK_TYPE_UINT8_T:
261 262
                if (array_length > 0) {
                    uint8_t* nums = m + offset;
263 264
                    QString tmp("%1, ");
                    QString string;
265
                    for (unsigned int j = 0; j < array_length - 1; ++j) {
266 267
                        string += tmp.arg(nums[j]);
                    }
268
                    string += QString::number(nums[array_length - 1]);
269
                    f->updateValue(string, static_cast<qreal>(nums[0]));
270 271
                } else {
                    // Single value
272
                    uint8_t u = *(m + offset);
273
                    f->updateValue(QString::number(u), static_cast<qreal>(u));
274 275 276
                }
                break;
            case MAVLINK_TYPE_INT8_T:
277 278
                if (array_length > 0) {
                    int8_t* nums = reinterpret_cast<int8_t*>(m + offset);
279 280
                    QString tmp("%1, ");
                    QString string;
281
                    for (unsigned int j = 0; j < array_length - 1; ++j) {
282 283
                        string += tmp.arg(nums[j]);
                    }
284
                    string += QString::number(nums[array_length - 1]);
285
                    f->updateValue(string, static_cast<qreal>(nums[0]));
286 287
                } else {
                    // Single value
288
                    int8_t n = *(reinterpret_cast<int8_t*>(m + offset));
289
                    f->updateValue(QString::number(n), static_cast<qreal>(n));
290 291 292
                }
                break;
            case MAVLINK_TYPE_UINT16_T:
293 294 295
                if (array_length > 0) {
                    uint16_t nums[array_buffer_length / sizeof(uint16_t)];
                    memcpy(nums, m + offset,  sizeof(uint16_t) * array_length);
296 297
                    QString tmp("%1, ");
                    QString string;
298
                    for (unsigned int j = 0; j < array_length - 1; ++j) {
299 300
                        string += tmp.arg(nums[j]);
                    }
301
                    string += QString::number(nums[array_length - 1]);
302
                    f->updateValue(string, static_cast<qreal>(nums[0]));
303 304
                } else {
                    // Single value
305 306
                    uint16_t n;
                    memcpy(&n, m + offset, sizeof(uint16_t));
307
                    f->updateValue(QString::number(n), static_cast<qreal>(n));
308 309 310
                }
                break;
            case MAVLINK_TYPE_INT16_T:
311 312 313
                if (array_length > 0) {
                    int16_t nums[array_buffer_length / sizeof(int16_t)];
                    memcpy(nums, m + offset,  sizeof(int16_t) * array_length);
314 315
                    QString tmp("%1, ");
                    QString string;
316
                    for (unsigned int j = 0; j < array_length - 1; ++j) {
317 318
                        string += tmp.arg(nums[j]);
                    }
319
                    string += QString::number(nums[array_length - 1]);
320
                    f->updateValue(string, static_cast<qreal>(nums[0]));
321 322
                } else {
                    // Single value
323 324
                    int16_t n;
                    memcpy(&n, m + offset, sizeof(int16_t));
325
                    f->updateValue(QString::number(n), static_cast<qreal>(n));
326 327 328
                }
                break;
            case MAVLINK_TYPE_UINT32_T:
329 330 331
                if (array_length > 0) {
                    uint32_t nums[array_buffer_length / sizeof(uint32_t)];
                    memcpy(nums, m + offset,  sizeof(uint32_t) * array_length);
332 333
                    QString tmp("%1, ");
                    QString string;
334
                    for (unsigned int j = 0; j < array_length - 1; ++j) {
335 336
                        string += tmp.arg(nums[j]);
                    }
337
                    string += QString::number(nums[array_length - 1]);
338
                    f->updateValue(string, static_cast<qreal>(nums[0]));
339 340
                } else {
                    // Single value
341 342
                    uint32_t n;
                    memcpy(&n, m + offset, sizeof(uint32_t));
Gus Grubba's avatar
Gus Grubba committed
343 344 345
                    //-- Special case
                    if(_message.msgid == MAVLINK_MSG_ID_SYSTEM_TIME) {
                        QDateTime d = QDateTime::fromMSecsSinceEpoch(static_cast<qint64>(n),Qt::UTC,0);
346
                        f->updateValue(d.toString("HH:mm:ss"), static_cast<qreal>(n));
Gus Grubba's avatar
Gus Grubba committed
347
                    } else {
348
                        f->updateValue(QString::number(n), static_cast<qreal>(n));
Gus Grubba's avatar
Gus Grubba committed
349
                    }
350 351 352
                }
                break;
            case MAVLINK_TYPE_INT32_T:
353 354 355
                if (array_length > 0) {
                    int32_t nums[array_buffer_length / sizeof(int32_t)];
                    memcpy(nums, m + offset,  sizeof(int32_t) * array_length);
356 357
                    QString tmp("%1, ");
                    QString string;
358
                    for (unsigned int j = 0; j < array_length - 1; ++j) {
359 360
                        string += tmp.arg(nums[j]);
                    }
361
                    string += QString::number(nums[array_length - 1]);
362
                    f->updateValue(string, static_cast<qreal>(nums[0]));
363 364
                } else {
                    // Single value
365 366
                    int32_t n;
                    memcpy(&n, m + offset, sizeof(int32_t));
367
                    f->updateValue(QString::number(n), static_cast<qreal>(n));
368 369 370
                }
                break;
            case MAVLINK_TYPE_FLOAT:
371 372 373
                if (array_length > 0) {
                    float nums[array_buffer_length / sizeof(float)];
                    memcpy(nums, m + offset,  sizeof(float) * array_length);
374 375
                    QString tmp("%1, ");
                    QString string;
376
                    for (unsigned int j = 0; j < array_length - 1; ++j) {
377 378
                       string += tmp.arg(static_cast<double>(nums[j]));
                    }
379
                    string += QString::number(static_cast<double>(nums[array_length - 1]));
380
                    f->updateValue(string, static_cast<qreal>(nums[0]));
381 382
                } else {
                    // Single value
383 384
                    float fv;
                    memcpy(&fv, m + offset, sizeof(float));
385
                    f->updateValue(QString::number(static_cast<double>(fv)), static_cast<qreal>(fv));
386 387 388
                }
                break;
            case MAVLINK_TYPE_DOUBLE:
389 390 391
                if (array_length > 0) {
                    double nums[array_buffer_length / sizeof(double)];
                    memcpy(nums, m + offset,  sizeof(double) * array_length);
392 393
                    QString tmp("%1, ");
                    QString string;
394
                    for (unsigned int j = 0; j < array_length - 1; ++j) {
395 396
                        string += tmp.arg(nums[j]);
                    }
397
                    string += QString::number(static_cast<double>(nums[array_length - 1]));
398
                    f->updateValue(string, static_cast<qreal>(nums[0]));
399 400
                } else {
                    // Single value
401 402
                    double d;
                    memcpy(&d, m + offset, sizeof(double));
403
                    f->updateValue(QString::number(d), static_cast<qreal>(d));
404 405 406
                }
                break;
            case MAVLINK_TYPE_UINT64_T:
407 408 409
                if (array_length > 0) {
                    uint64_t nums[array_buffer_length / sizeof(uint64_t)];
                    memcpy(nums, m + offset,  sizeof(uint64_t) * array_length);
410 411
                    QString tmp("%1, ");
                    QString string;
412
                    for (unsigned int j = 0; j < array_length - 1; ++j) {
413 414
                        string += tmp.arg(nums[j]);
                    }
415
                    string += QString::number(nums[array_length - 1]);
416
                    f->updateValue(string, static_cast<qreal>(nums[0]));
417 418
                } else {
                    // Single value
419 420
                    uint64_t n;
                    memcpy(&n, m + offset, sizeof(uint64_t));
Gus Grubba's avatar
Gus Grubba committed
421 422 423
                    //-- Special case
                    if(_message.msgid == MAVLINK_MSG_ID_SYSTEM_TIME) {
                        QDateTime d = QDateTime::fromMSecsSinceEpoch(n/1000,Qt::UTC,0);
424
                        f->updateValue(d.toString("yyyy MM dd HH:mm:ss"), static_cast<qreal>(n));
Gus Grubba's avatar
Gus Grubba committed
425
                    } else {
426
                        f->updateValue(QString::number(n), static_cast<qreal>(n));
Gus Grubba's avatar
Gus Grubba committed
427
                    }
428 429 430
                }
                break;
            case MAVLINK_TYPE_INT64_T:
431 432 433
                if (array_length > 0) {
                    int64_t nums[array_buffer_length / sizeof(int64_t)];
                    memcpy(nums, m + offset,  sizeof(int64_t) * array_length);
434 435
                    QString tmp("%1, ");
                    QString string;
436
                    for (unsigned int j = 0; j < array_length - 1; ++j) {
437 438
                        string += tmp.arg(nums[j]);
                    }
439
                    string += QString::number(nums[array_length - 1]);
440
                    f->updateValue(string, static_cast<qreal>(nums[0]));
441 442
                } else {
                    // Single value
443 444
                    int64_t n;
                    memcpy(&n, m + offset, sizeof(int64_t));
445
                    f->updateValue(QString::number(n), static_cast<qreal>(n));
446 447 448 449 450 451 452 453 454
                }
                break;
            }
        }
    }
    emit messageChanged();
}

//-----------------------------------------------------------------------------
455
QGCMAVLinkSystem::QGCMAVLinkSystem(QObject* parent, quint8 id)
456 457 458 459 460 461
    : QObject(parent)
    , _id(id)
{
    qCDebug(MAVLinkInspectorLog) << "New Vehicle:" << id;
}

462
//-----------------------------------------------------------------------------
463
QGCMAVLinkSystem::~QGCMAVLinkSystem()
464 465 466 467
{
    _messages.clearAndDeleteContents();
}

468 469
//-----------------------------------------------------------------------------
QGCMAVLinkMessage*
470
QGCMAVLinkSystem::findMessage(uint32_t id, uint8_t cid)
471 472 473 474
{
    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
475
            if(m->id() == id && m->cid() == cid) {
476 477 478 479 480 481 482
                return m;
            }
        }
    }
    return nullptr;
}

Gus Grubba's avatar
Gus Grubba committed
483 484
//-----------------------------------------------------------------------------
int
485
QGCMAVLinkSystem::findMessage(QGCMAVLinkMessage* message)
Gus Grubba's avatar
Gus Grubba committed
486 487 488 489 490 491 492 493 494 495
{
    for(int i = 0; i < _messages.count(); i++) {
        QGCMAVLinkMessage* m = qobject_cast<QGCMAVLinkMessage*>(_messages.get(i));
        if(m && m == message) {
            return i;
        }
    }
    return -1;
}

496 497
//-----------------------------------------------------------------------------
void
498
QGCMAVLinkSystem::_resetSelection()
499 500 501 502 503 504 505 506 507 508
{
    for(int i = 0; i < _messages.count(); i++) {
        QGCMAVLinkMessage* m = qobject_cast<QGCMAVLinkMessage*>(_messages.get(i));
        if(m && m->selected()) {
            m->setSelected(false);
            emit m->selectedChanged();
        }
    }
}

Gus Grubba's avatar
Gus Grubba committed
509 510
//-----------------------------------------------------------------------------
void
511
QGCMAVLinkSystem::setSelected(int sel)
Gus Grubba's avatar
Gus Grubba committed
512 513 514 515
{
    if(sel < _messages.count()) {
        _selected = sel;
        emit selectedChanged();
516 517 518 519 520 521
        _resetSelection();
        QGCMAVLinkMessage* m = qobject_cast<QGCMAVLinkMessage*>(_messages.get(sel));
        if(m && !m->selected()) {
            m->setSelected(true);
            emit m->selectedChanged();
        }
Gus Grubba's avatar
Gus Grubba committed
522 523 524
    }
}

Gus Grubba's avatar
Gus Grubba committed
525 526 527 528 529 530 531
//-----------------------------------------------------------------------------
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;
532 533
    if(aa->name() == bb->name()) return aa->name() < bb->name();
    return aa->name() < bb->name();
Gus Grubba's avatar
Gus Grubba committed
534 535
}

536 537
//-----------------------------------------------------------------------------
void
538
QGCMAVLinkSystem::append(QGCMAVLinkMessage* message)
539
{
Gus Grubba's avatar
Gus Grubba committed
540 541 542 543
    //-- Save selected message
    QGCMAVLinkMessage* selectedMsg = nullptr;
    if(_messages.count()) {
        selectedMsg = qobject_cast<QGCMAVLinkMessage*>(_messages.get(_selected));
544 545 546
    } else {
        //-- First message
        message->setSelected(true);
Gus Grubba's avatar
Gus Grubba committed
547
    }
548
    _messages.append(message);
Gus Grubba's avatar
Gus Grubba committed
549 550 551 552 553 554 555 556 557
    //-- 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();
            }
        }
558
        _checkCompID(message);
Gus Grubba's avatar
Gus Grubba committed
559
    }
560
    emit messagesChanged();
Gus Grubba's avatar
Gus Grubba committed
561 562 563 564 565 566 567 568
    //-- Remember selected message
    if(selectedMsg) {
        int idx = findMessage(selectedMsg);
        if(idx >= 0) {
            _selected = idx;
            emit selectedChanged();
        }
    }
569 570
}

571 572
//-----------------------------------------------------------------------------
void
573
QGCMAVLinkSystem::_checkCompID(QGCMAVLinkMessage* message)
574 575
{
    if(_compIDsStr.isEmpty()) {
576
        _compIDsStr << tr("Comp All");
577 578 579 580
    }
    if(!_compIDs.contains(static_cast<int>(message->cid()))) {
        int cid = static_cast<int>(message->cid());
        _compIDs.append(cid);
581
        _compIDsStr << tr("Comp %1").arg(cid);
582 583 584 585
        emit compIDsChanged();
    }
}

Gus Grubba's avatar
Gus Grubba committed
586
//-----------------------------------------------------------------------------
587
MAVLinkChartController::MAVLinkChartController(MAVLinkInspectorController *parent, int index)
Gus Grubba's avatar
Gus Grubba committed
588
    : QObject(parent)
589
    , _index(index)
590
    , _controller(parent)
Gus Grubba's avatar
Gus Grubba committed
591
{
592 593
    connect(&_updateSeriesTimer, &QTimer::timeout, this, &MAVLinkChartController::_refreshSeries);
    updateXRange();
Gus Grubba's avatar
Gus Grubba committed
594 595
}

596
//-----------------------------------------------------------------------------
597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627
void
MAVLinkChartController::setRangeYIndex(quint32 r)
{
    if(r < static_cast<quint32>(_controller->rangeSt().count())) {
        _rangeYIndex = r;
        qreal range = _controller->rangeSt()[static_cast<int>(r)]->range;
        emit rangeYIndexChanged();
        //-- If not Auto, use defined range
        if(_rangeYIndex > 0) {
            _rangeYMin = -range;
            emit rangeYMinChanged();
            _rangeYMax = range;
            emit rangeYMaxChanged();
        }
    }
}

//-----------------------------------------------------------------------------
void
MAVLinkChartController::setRangeXIndex(quint32 t)
{
    _rangeXIndex = t;
    emit rangeXIndexChanged();
    updateXRange();
}

//-----------------------------------------------------------------------------
void
MAVLinkChartController::updateXRange()
{
    if(_rangeXIndex < static_cast<quint32>(_controller->timeScaleSt().count())) {
Gus Grubba's avatar
Gus Grubba committed
628
        qint64 t = static_cast<qint64>(QGC::bootTimeMilliseconds());
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 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696
        _rangeXMax = QDateTime::fromMSecsSinceEpoch(t);
        _rangeXMin = QDateTime::fromMSecsSinceEpoch(t - _controller->timeScaleSt()[static_cast<int>(_rangeXIndex)]->timeScale);
        emit rangeXMinChanged();
        emit rangeXMaxChanged();
    }
}

//-----------------------------------------------------------------------------
void
MAVLinkChartController::updateYRange()
{
    if(_chartFields.count()) {
        qreal vmin  = std::numeric_limits<qreal>::max();
        qreal vmax  = std::numeric_limits<qreal>::min();
        for(int i = 0; i < _chartFields.count(); i++) {
            QObject* object = qvariant_cast<QObject*>(_chartFields.at(i));
            QGCMAVLinkMessageField* pField = qobject_cast<QGCMAVLinkMessageField*>(object);
            if(pField) {
                if(vmax < pField->rangeMax()) vmax = pField->rangeMax();
                if(vmin > pField->rangeMin()) vmin = pField->rangeMin();
            }
        }
        if(std::abs(_rangeYMin - vmin) > 0.000001) {
            _rangeYMin = vmin;
            emit rangeYMinChanged();
        }
        if(std::abs(_rangeYMax - vmax) > 0.000001) {
            _rangeYMax = vmax;
            emit rangeYMaxChanged();
        }
    }
}

//-----------------------------------------------------------------------------
void
MAVLinkChartController::_refreshSeries()
{
    updateXRange();
    for(int i = 0; i < _chartFields.count(); i++) {
        QObject* object = qvariant_cast<QObject*>(_chartFields.at(i));
        QGCMAVLinkMessageField* pField = qobject_cast<QGCMAVLinkMessageField*>(object);
        if(pField) {
            pField->updateSeries();
        }
    }
}

//-----------------------------------------------------------------------------
void
MAVLinkChartController::addSeries(QGCMAVLinkMessageField* field, QAbstractSeries* series)
{
    if(field && series) {
        QVariant f = QVariant::fromValue(field);
        for(int i = 0; i < _chartFields.count(); i++) {
            if(_chartFields.at(i) == f) {
                return;
            }
        }
        _chartFields.append(f);
        field->addSeries(this, series);
        emit chartFieldsChanged();
        _updateSeriesTimer.start(UPDATE_FREQUENCY);
    }
}

//-----------------------------------------------------------------------------
void
MAVLinkChartController::delSeries(QGCMAVLinkMessageField* field)
697
{
698 699 700 701 702 703 704 705 706 707 708 709 710 711 712
    if(field) {
        field->delSeries();
        QVariant f = QVariant::fromValue(field);
        for(int i = 0; i < _chartFields.count(); i++) {
            if(_chartFields.at(i) == f) {
                _chartFields.removeAt(i);
                emit chartFieldsChanged();
                if(_chartFields.count() == 0) {
                    updateXRange();
                    _updateSeriesTimer.stop();
                }
                return;
            }
        }
    }
713 714
}

715 716 717 718 719 720 721 722
//-----------------------------------------------------------------------------
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
723 724
    connect(&_updateFrequencyTimer, &QTimer::timeout, this, &MAVLinkInspectorController::_refreshFrequency);
    _updateFrequencyTimer.start(1000);
Gus Grubba's avatar
Gus Grubba committed
725 726
    MultiVehicleManager *manager = qgcApp()->toolbox()->multiVehicleManager();
    connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &MAVLinkInspectorController::_setActiveVehicle);
Gus Grubba's avatar
Gus Grubba committed
727 728 729 730 731
    _timeScaleSt.append(new TimeScale_st(this, tr("5 Sec"),   5 * 1000));
    _timeScaleSt.append(new TimeScale_st(this, tr("10 Sec"), 10 * 1000));
    _timeScaleSt.append(new TimeScale_st(this, tr("30 Sec"), 30 * 1000));
    _timeScaleSt.append(new TimeScale_st(this, tr("60 Sec"), 60 * 1000));
    emit timeScalesChanged();
732 733 734 735 736 737 738 739 740 741 742
    _rangeSt.append(new Range_st(this, tr("Auto"),    0));
    _rangeSt.append(new Range_st(this, tr("10,000"),  10000));
    _rangeSt.append(new Range_st(this, tr("1,000"),   1000));
    _rangeSt.append(new Range_st(this, tr("100"),     100));
    _rangeSt.append(new Range_st(this, tr("10"),      10));
    _rangeSt.append(new Range_st(this, tr("1"),       1));
    _rangeSt.append(new Range_st(this, tr("0.1"),     0.1));
    _rangeSt.append(new Range_st(this, tr("0.01"),    0.01));
    _rangeSt.append(new Range_st(this, tr("0.001"),   0.001));
    _rangeSt.append(new Range_st(this, tr("0.0001"),  0.0001));
    emit rangeListChanged();
743 744 745 746 747
}

//-----------------------------------------------------------------------------
MAVLinkInspectorController::~MAVLinkInspectorController()
{
748
    _charts.clearAndDeleteContents();
749
    _systems.clearAndDeleteContents();
750 751
}

Gus Grubba's avatar
Gus Grubba committed
752 753 754 755 756 757 758 759 760 761 762 763
//----------------------------------------------------------------------------------------
QStringList
MAVLinkInspectorController::timeScales()
{
    if(!_timeScales.count()) {
        for(int i = 0; i < _timeScaleSt.count(); i++) {
            _timeScales << _timeScaleSt[i]->label;
        }
    }
    return _timeScales;
}

764 765 766 767 768 769 770 771 772 773 774 775
//----------------------------------------------------------------------------------------
QStringList
MAVLinkInspectorController::rangeList()
{
    if(!_rangeList.count()) {
        for(int i = 0; i < _rangeSt.count(); i++) {
            _rangeList << _rangeSt[i]->label;
        }
    }
    return _rangeList;
}

Gus Grubba's avatar
Gus Grubba committed
776 777 778 779 780
//----------------------------------------------------------------------------------------
void
MAVLinkInspectorController::_setActiveVehicle(Vehicle* vehicle)
{
    if(vehicle) {
781
        QGCMAVLinkSystem* v = _findVehicle(static_cast<uint8_t>(vehicle->id()));
Gus Grubba's avatar
Gus Grubba committed
782
        if(v) {
783
            _activeSystem = v;
Gus Grubba's avatar
Gus Grubba committed
784
        } else {
785
            _activeSystem = nullptr;
Gus Grubba's avatar
Gus Grubba committed
786 787
        }
    } else {
788
        _activeSystem = nullptr;
Gus Grubba's avatar
Gus Grubba committed
789
    }
790
    emit activeSystemChanged();
Gus Grubba's avatar
Gus Grubba committed
791 792
}

793
//-----------------------------------------------------------------------------
794
QGCMAVLinkSystem*
795 796
MAVLinkInspectorController::_findVehicle(uint8_t id)
{
797 798
    for(int i = 0; i < _systems.count(); i++) {
        QGCMAVLinkSystem* v = qobject_cast<QGCMAVLinkSystem*>(_systems.get(i));
799 800 801 802 803 804 805 806 807
        if(v) {
            if(v->id() == id) {
                return v;
            }
        }
    }
    return nullptr;
}

Gus Grubba's avatar
Gus Grubba committed
808 809 810 811
//-----------------------------------------------------------------------------
void
MAVLinkInspectorController::_refreshFrequency()
{
812 813
    for(int i = 0; i < _systems.count(); i++) {
        QGCMAVLinkSystem* v = qobject_cast<QGCMAVLinkSystem*>(_systems.get(i));
Gus Grubba's avatar
Gus Grubba committed
814 815 816 817 818 819 820 821 822 823 824
        if(v) {
            for(int i = 0; i < v->messages()->count(); i++) {
                QGCMAVLinkMessage* m = qobject_cast<QGCMAVLinkMessage*>(v->messages()->get(i));
                if(m) {
                    m->updateFreq();
                }
            }
        }
    }
}

825 826 827 828
//-----------------------------------------------------------------------------
void
MAVLinkInspectorController::_vehicleAdded(Vehicle* vehicle)
{
829
    QGCMAVLinkSystem* v = _findVehicle(static_cast<uint8_t>(vehicle->id()));
830
    if(v) {
831
        v->messages()->clearAndDeleteContents();
832 833
        emit v->messagesChanged();
    } else {
834 835 836
        v = new QGCMAVLinkSystem(this, static_cast<uint8_t>(vehicle->id()));
        _systems.append(v);
        _systemNames.append(tr("System %1").arg(vehicle->id()));
837
    }
838
    emit systemsChanged();
839 840 841 842 843 844
}

//-----------------------------------------------------------------------------
void
MAVLinkInspectorController::_vehicleRemoved(Vehicle* vehicle)
{
845
    QGCMAVLinkSystem* v = _findVehicle(static_cast<uint8_t>(vehicle->id()));
846 847
    if(v) {
        v->deleteLater();
848 849 850 851
        _systems.removeOne(v);
        QString vs = tr("System %1").arg(vehicle->id());
        _systemNames.removeOne(vs);
        emit systemsChanged();
852 853 854 855 856
    }
}

//-----------------------------------------------------------------------------
void
857
MAVLinkInspectorController::_receiveMessage(LinkInterface*, mavlink_message_t message)
858
{
859
    QGCMAVLinkMessage* m = nullptr;
860
    QGCMAVLinkSystem* v = _findVehicle(message.sysid);
861
    if(!v) {
862 863 864 865 866 867 868
        v = new QGCMAVLinkSystem(this, message.sysid);
        _systems.append(v);
        _systemNames.append(tr("System %1").arg(message.sysid));
        emit systemsChanged();
        if(!_activeSystem) {
            _activeSystem = v;
            emit activeSystemChanged();
Gus Grubba's avatar
Gus Grubba committed
869
        }
870
    } else {
Gus Grubba's avatar
Gus Grubba committed
871
        m = v->findMessage(message.msgid, message.compid);
872
    }
873 874 875
    if(!m) {
        m = new QGCMAVLinkMessage(this, &message);
        v->append(m);
876
    } else {
877
        m->update(&message);
878 879 880 881
    }
}

//-----------------------------------------------------------------------------
882 883
MAVLinkChartController*
MAVLinkInspectorController::createChart()
884
{
885
    MAVLinkChartController* pChart = new MAVLinkChartController(this, _charts.count());
886 887 888 889
    QQmlEngine::setObjectOwnership(pChart, QQmlEngine::CppOwnership);
    _charts.append(pChart);
    emit chartsChanged();
    return pChart;
890 891
}

892 893
//-----------------------------------------------------------------------------
void
894
MAVLinkInspectorController::deleteChart(MAVLinkChartController* chart)
895
{
896 897 898
    if(chart) {
        for(int i = 0; i < _charts.count(); i++) {
            MAVLinkChartController* c = qobject_cast<MAVLinkChartController*>(_charts.get(i));
Gus Grubba's avatar
Gus Grubba committed
899
            if(c && c == chart) {
900
                _charts.removeOne(c);
Gus Grubba's avatar
Gus Grubba committed
901
                delete c;
902
                break;
903 904
            }
        }
905
        emit chartsChanged();
906 907 908 909
    }
}

//-----------------------------------------------------------------------------
910 911 912 913
MAVLinkInspectorController::TimeScale_st::TimeScale_st(QObject* parent, const QString& l, uint32_t t)
    : QObject(parent)
    , label(l)
    , timeScale(t)
914 915 916 917
{
}

//-----------------------------------------------------------------------------
918 919 920 921
MAVLinkInspectorController::Range_st::Range_st(QObject* parent, const QString& l, qreal r)
    : QObject(parent)
    , label(l)
    , range(r)
922
{
Gus Grubba's avatar
Gus Grubba committed
923 924
}

925 926 927 928 929 930 931 932 933
void MAVLinkInspectorController::setActiveSystem(int systemId)
{
    QGCMAVLinkSystem* v = _findVehicle(systemId);
    if (v != _activeSystem) {
        _activeSystem = v;
        emit activeSystemChanged();
    }
}