MAVLinkInspectorController.cc 33.4 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
    : QObject(parent)
{
    _message = *message;
    const mavlink_message_info_t* msgInfo = mavlink_get_message_info(message);
    if (!msgInfo) {
DonLakeFlyer's avatar
DonLakeFlyer committed
159
        qCWarning(MAVLinkInspectorLog) << QStringLiteral("QGCMAVLinkMessage NULL msgInfo msgid(%1)").arg(message->msgid);
160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183
        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);
    }
}

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

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

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

DonLakeFlyer's avatar
DonLakeFlyer committed
220 221 222 223 224 225 226 227 228
void QGCMAVLinkMessage::setSelected(bool sel)
{
    if (_selected != sel) {
        _selected = sel;
        _updateFields();
        emit selectedChanged();
    }
}

229 230 231 232 233
//-----------------------------------------------------------------------------
void
QGCMAVLinkMessage::update(mavlink_message_t* message)
{
    _count++;
234
    _message = *message;
DonLakeFlyer's avatar
DonLakeFlyer committed
235 236 237 238 239 240 241 242 243 244 245

    if (_selected) {
        // Don't update field info unless selected to reduce perf hit of message processing
        _updateFields();
    }
    emit countChanged();
}

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

//-----------------------------------------------------------------------------
471
QGCMAVLinkSystem::QGCMAVLinkSystem(QObject* parent, quint8 id)
472 473 474 475 476 477
    : QObject(parent)
    , _id(id)
{
    qCDebug(MAVLinkInspectorLog) << "New Vehicle:" << id;
}

478
//-----------------------------------------------------------------------------
479
QGCMAVLinkSystem::~QGCMAVLinkSystem()
480 481 482 483
{
    _messages.clearAndDeleteContents();
}

484 485
//-----------------------------------------------------------------------------
QGCMAVLinkMessage*
486
QGCMAVLinkSystem::findMessage(uint32_t id, uint8_t cid)
487 488 489 490
{
    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
491
            if(m->id() == id && m->cid() == cid) {
492 493 494 495 496 497 498
                return m;
            }
        }
    }
    return nullptr;
}

Gus Grubba's avatar
Gus Grubba committed
499 500
//-----------------------------------------------------------------------------
int
501
QGCMAVLinkSystem::findMessage(QGCMAVLinkMessage* message)
Gus Grubba's avatar
Gus Grubba committed
502 503 504 505 506 507 508 509 510 511
{
    for(int i = 0; i < _messages.count(); i++) {
        QGCMAVLinkMessage* m = qobject_cast<QGCMAVLinkMessage*>(_messages.get(i));
        if(m && m == message) {
            return i;
        }
    }
    return -1;
}

512 513
//-----------------------------------------------------------------------------
void
514
QGCMAVLinkSystem::_resetSelection()
515 516 517 518 519 520 521 522 523 524
{
    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
525 526
//-----------------------------------------------------------------------------
void
527
QGCMAVLinkSystem::setSelected(int sel)
Gus Grubba's avatar
Gus Grubba committed
528 529 530 531
{
    if(sel < _messages.count()) {
        _selected = sel;
        emit selectedChanged();
532 533 534 535 536 537
        _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
538 539 540
    }
}

Gus Grubba's avatar
Gus Grubba committed
541 542 543 544 545 546 547
//-----------------------------------------------------------------------------
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;
548 549
    if(aa->name() == bb->name()) return aa->name() < bb->name();
    return aa->name() < bb->name();
Gus Grubba's avatar
Gus Grubba committed
550 551
}

552 553
//-----------------------------------------------------------------------------
void
554
QGCMAVLinkSystem::append(QGCMAVLinkMessage* message)
555
{
Gus Grubba's avatar
Gus Grubba committed
556 557 558 559
    //-- Save selected message
    QGCMAVLinkMessage* selectedMsg = nullptr;
    if(_messages.count()) {
        selectedMsg = qobject_cast<QGCMAVLinkMessage*>(_messages.get(_selected));
560 561 562
    } else {
        //-- First message
        message->setSelected(true);
Gus Grubba's avatar
Gus Grubba committed
563
    }
564
    _messages.append(message);
Gus Grubba's avatar
Gus Grubba committed
565
    //-- Sort messages by id and then cid
DonLakeFlyer's avatar
DonLakeFlyer committed
566 567
    if (_messages.count() > 0) {
        _messages.beginReset();
Gus Grubba's avatar
Gus Grubba committed
568
        std::sort(_messages.objectList()->begin(), _messages.objectList()->end(), messages_sort);
DonLakeFlyer's avatar
DonLakeFlyer committed
569
        _messages.endReset();
570
        _checkCompID(message);
Gus Grubba's avatar
Gus Grubba committed
571
    }
Gus Grubba's avatar
Gus Grubba committed
572 573 574 575 576 577 578 579
    //-- Remember selected message
    if(selectedMsg) {
        int idx = findMessage(selectedMsg);
        if(idx >= 0) {
            _selected = idx;
            emit selectedChanged();
        }
    }
580 581
}

582 583
//-----------------------------------------------------------------------------
void
584
QGCMAVLinkSystem::_checkCompID(QGCMAVLinkMessage* message)
585 586
{
    if(_compIDsStr.isEmpty()) {
587
        _compIDsStr << tr("Comp All");
588 589 590 591
    }
    if(!_compIDs.contains(static_cast<int>(message->cid()))) {
        int cid = static_cast<int>(message->cid());
        _compIDs.append(cid);
592
        _compIDsStr << tr("Comp %1").arg(cid);
593 594 595 596
        emit compIDsChanged();
    }
}

Gus Grubba's avatar
Gus Grubba committed
597
//-----------------------------------------------------------------------------
598
MAVLinkChartController::MAVLinkChartController(MAVLinkInspectorController *parent, int index)
Gus Grubba's avatar
Gus Grubba committed
599
    : QObject(parent)
600
    , _index(index)
601
    , _controller(parent)
Gus Grubba's avatar
Gus Grubba committed
602
{
603 604
    connect(&_updateSeriesTimer, &QTimer::timeout, this, &MAVLinkChartController::_refreshSeries);
    updateXRange();
Gus Grubba's avatar
Gus Grubba committed
605 606
}

607
//-----------------------------------------------------------------------------
608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638
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
639
        qint64 t = static_cast<qint64>(QGC::bootTimeMilliseconds());
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 697 698 699 700 701 702 703 704 705 706 707
        _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)
708
{
709 710 711 712 713 714 715 716 717 718 719 720 721 722 723
    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;
            }
        }
    }
724 725
}

726 727 728 729 730 731 732 733
//-----------------------------------------------------------------------------
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
734 735
    connect(&_updateFrequencyTimer, &QTimer::timeout, this, &MAVLinkInspectorController::_refreshFrequency);
    _updateFrequencyTimer.start(1000);
Gus Grubba's avatar
Gus Grubba committed
736 737
    MultiVehicleManager *manager = qgcApp()->toolbox()->multiVehicleManager();
    connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &MAVLinkInspectorController::_setActiveVehicle);
Gus Grubba's avatar
Gus Grubba committed
738 739 740 741 742
    _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();
743 744 745 746 747 748 749 750 751 752 753
    _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();
754 755 756 757 758
}

//-----------------------------------------------------------------------------
MAVLinkInspectorController::~MAVLinkInspectorController()
{
759
    _charts.clearAndDeleteContents();
760
    _systems.clearAndDeleteContents();
761 762
}

Gus Grubba's avatar
Gus Grubba committed
763 764 765 766 767 768 769 770 771 772 773 774
//----------------------------------------------------------------------------------------
QStringList
MAVLinkInspectorController::timeScales()
{
    if(!_timeScales.count()) {
        for(int i = 0; i < _timeScaleSt.count(); i++) {
            _timeScales << _timeScaleSt[i]->label;
        }
    }
    return _timeScales;
}

775 776 777 778 779 780 781 782 783 784 785 786
//----------------------------------------------------------------------------------------
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
787 788 789 790 791
//----------------------------------------------------------------------------------------
void
MAVLinkInspectorController::_setActiveVehicle(Vehicle* vehicle)
{
    if(vehicle) {
792
        QGCMAVLinkSystem* v = _findVehicle(static_cast<uint8_t>(vehicle->id()));
Gus Grubba's avatar
Gus Grubba committed
793
        if(v) {
794
            _activeSystem = v;
Gus Grubba's avatar
Gus Grubba committed
795
        } else {
796
            _activeSystem = nullptr;
Gus Grubba's avatar
Gus Grubba committed
797 798
        }
    } else {
799
        _activeSystem = nullptr;
Gus Grubba's avatar
Gus Grubba committed
800
    }
801
    emit activeSystemChanged();
Gus Grubba's avatar
Gus Grubba committed
802 803
}

804
//-----------------------------------------------------------------------------
805
QGCMAVLinkSystem*
806 807
MAVLinkInspectorController::_findVehicle(uint8_t id)
{
808 809
    for(int i = 0; i < _systems.count(); i++) {
        QGCMAVLinkSystem* v = qobject_cast<QGCMAVLinkSystem*>(_systems.get(i));
810 811 812 813 814 815 816 817 818
        if(v) {
            if(v->id() == id) {
                return v;
            }
        }
    }
    return nullptr;
}

Gus Grubba's avatar
Gus Grubba committed
819 820 821 822
//-----------------------------------------------------------------------------
void
MAVLinkInspectorController::_refreshFrequency()
{
823 824
    for(int i = 0; i < _systems.count(); i++) {
        QGCMAVLinkSystem* v = qobject_cast<QGCMAVLinkSystem*>(_systems.get(i));
Gus Grubba's avatar
Gus Grubba committed
825 826 827 828 829 830 831 832 833 834 835
        if(v) {
            for(int i = 0; i < v->messages()->count(); i++) {
                QGCMAVLinkMessage* m = qobject_cast<QGCMAVLinkMessage*>(v->messages()->get(i));
                if(m) {
                    m->updateFreq();
                }
            }
        }
    }
}

836 837 838 839
//-----------------------------------------------------------------------------
void
MAVLinkInspectorController::_vehicleAdded(Vehicle* vehicle)
{
840
    QGCMAVLinkSystem* v = _findVehicle(static_cast<uint8_t>(vehicle->id()));
841
    if(v) {
842
        v->messages()->clearAndDeleteContents();
843
    } else {
844 845 846
        v = new QGCMAVLinkSystem(this, static_cast<uint8_t>(vehicle->id()));
        _systems.append(v);
        _systemNames.append(tr("System %1").arg(vehicle->id()));
847
    }
848
    emit systemsChanged();
849 850 851 852 853 854
}

//-----------------------------------------------------------------------------
void
MAVLinkInspectorController::_vehicleRemoved(Vehicle* vehicle)
{
855
    QGCMAVLinkSystem* v = _findVehicle(static_cast<uint8_t>(vehicle->id()));
856 857
    if(v) {
        v->deleteLater();
858 859 860 861
        _systems.removeOne(v);
        QString vs = tr("System %1").arg(vehicle->id());
        _systemNames.removeOne(vs);
        emit systemsChanged();
862 863 864 865 866
    }
}

//-----------------------------------------------------------------------------
void
867
MAVLinkInspectorController::_receiveMessage(LinkInterface*, mavlink_message_t message)
868
{
869
    QGCMAVLinkMessage* m = nullptr;
870
    QGCMAVLinkSystem* v = _findVehicle(message.sysid);
871
    if(!v) {
872 873 874 875 876 877 878
        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
879
        }
880
    } else {
Gus Grubba's avatar
Gus Grubba committed
881
        m = v->findMessage(message.msgid, message.compid);
882
    }
883 884 885
    if(!m) {
        m = new QGCMAVLinkMessage(this, &message);
        v->append(m);
886
    } else {
887
        m->update(&message);
888 889 890 891
    }
}

//-----------------------------------------------------------------------------
892 893
MAVLinkChartController*
MAVLinkInspectorController::createChart()
894
{
895
    MAVLinkChartController* pChart = new MAVLinkChartController(this, _charts.count());
896 897 898 899
    QQmlEngine::setObjectOwnership(pChart, QQmlEngine::CppOwnership);
    _charts.append(pChart);
    emit chartsChanged();
    return pChart;
900 901
}

902 903
//-----------------------------------------------------------------------------
void
904
MAVLinkInspectorController::deleteChart(MAVLinkChartController* chart)
905
{
906 907 908
    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
909
            if(c && c == chart) {
910
                _charts.removeOne(c);
Gus Grubba's avatar
Gus Grubba committed
911
                delete c;
912
                break;
913 914
            }
        }
915
        emit chartsChanged();
916 917 918 919
    }
}

//-----------------------------------------------------------------------------
920 921 922 923
MAVLinkInspectorController::TimeScale_st::TimeScale_st(QObject* parent, const QString& l, uint32_t t)
    : QObject(parent)
    , label(l)
    , timeScale(t)
924 925 926 927
{
}

//-----------------------------------------------------------------------------
928 929 930 931
MAVLinkInspectorController::Range_st::Range_st(QObject* parent, const QString& l, qreal r)
    : QObject(parent)
    , label(l)
    , range(r)
932
{
Gus Grubba's avatar
Gus Grubba committed
933 934
}

935 936 937 938 939 940 941 942 943
void MAVLinkInspectorController::setActiveSystem(int systemId)
{
    QGCMAVLinkSystem* v = _findVehicle(systemId);
    if (v != _activeSystem) {
        _activeSystem = v;
        emit activeSystemChanged();
    }
}