MAVLinkInspectorController.cc 33.2 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 182 183
    : 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);
    }
}

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();
}

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

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

464 465 466 467 468 469
//-----------------------------------------------------------------------------
QGCMAVLinkVehicle::~QGCMAVLinkVehicle()
{
    _messages.clearAndDeleteContents();
}

470 471
//-----------------------------------------------------------------------------
QGCMAVLinkMessage*
Gus Grubba's avatar
Gus Grubba committed
472
QGCMAVLinkVehicle::findMessage(uint32_t id, uint8_t cid)
473 474 475 476
{
    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
477
            if(m->id() == id && m->cid() == cid) {
478 479 480 481 482 483 484
                return m;
            }
        }
    }
    return nullptr;
}

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

498 499 500 501 502 503 504 505 506 507 508 509 510
//-----------------------------------------------------------------------------
void
QGCMAVLinkVehicle::_resetSelection()
{
    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
511 512 513 514 515 516 517
//-----------------------------------------------------------------------------
void
QGCMAVLinkVehicle::setSelected(int sel)
{
    if(sel < _messages.count()) {
        _selected = sel;
        emit selectedChanged();
518 519 520 521 522 523
        _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
524 525 526
    }
}

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

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

573 574 575 576 577 578 579 580 581 582 583 584 585 586 587
//-----------------------------------------------------------------------------
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();
    }
}

Gus Grubba's avatar
Gus Grubba committed
588
//-----------------------------------------------------------------------------
589
MAVLinkChartController::MAVLinkChartController(MAVLinkInspectorController *parent, int index)
Gus Grubba's avatar
Gus Grubba committed
590
    : QObject(parent)
591
    , _index(index)
592
    , _controller(parent)
Gus Grubba's avatar
Gus Grubba committed
593
{
594 595
    connect(&_updateSeriesTimer, &QTimer::timeout, this, &MAVLinkChartController::_refreshSeries);
    updateXRange();
Gus Grubba's avatar
Gus Grubba committed
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 628 629
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
630
        qint64 t = static_cast<qint64>(QGC::bootTimeMilliseconds());
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 697 698
        _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)
699
{
700 701 702 703 704 705 706 707 708 709 710 711 712 713 714
    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;
            }
        }
    }
715 716
}

717 718 719 720 721 722 723 724
//-----------------------------------------------------------------------------
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
725 726
    connect(&_updateFrequencyTimer, &QTimer::timeout, this, &MAVLinkInspectorController::_refreshFrequency);
    _updateFrequencyTimer.start(1000);
Gus Grubba's avatar
Gus Grubba committed
727 728
    MultiVehicleManager *manager = qgcApp()->toolbox()->multiVehicleManager();
    connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &MAVLinkInspectorController::_setActiveVehicle);
Gus Grubba's avatar
Gus Grubba committed
729 730 731 732 733
    _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();
734 735 736 737 738 739 740 741 742 743 744
    _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();
745 746 747 748 749
}

//-----------------------------------------------------------------------------
MAVLinkInspectorController::~MAVLinkInspectorController()
{
750 751
    _charts.clearAndDeleteContents();
    _vehicles.clearAndDeleteContents();
752 753
}

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

766 767 768 769 770 771 772 773 774 775 776 777
//----------------------------------------------------------------------------------------
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
778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794
//----------------------------------------------------------------------------------------
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();
}

795 796 797 798 799 800 801 802 803 804 805 806 807 808 809
//-----------------------------------------------------------------------------
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
810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826
//-----------------------------------------------------------------------------
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();
                }
            }
        }
    }
}

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

//-----------------------------------------------------------------------------
void
MAVLinkInspectorController::_vehicleRemoved(Vehicle* vehicle)
{
847 848 849 850
    QGCMAVLinkVehicle* v = _findVehicle(static_cast<uint8_t>(vehicle->id()));
    if(v) {
        v->deleteLater();
        _vehicles.removeOne(v);
851
        QString vs = tr("Vehicle %1").arg(vehicle->id());
852 853
        _vehicleNames.removeOne(vs);
        emit vehiclesChanged();
854 855 856 857 858
    }
}

//-----------------------------------------------------------------------------
void
859
MAVLinkInspectorController::_receiveMessage(LinkInterface*, mavlink_message_t message)
860
{
861 862 863 864 865
    QGCMAVLinkMessage* m = nullptr;
    QGCMAVLinkVehicle* v = _findVehicle(message.sysid);
    if(!v) {
        v = new QGCMAVLinkVehicle(this, message.sysid);
        _vehicles.append(v);
866
        _vehicleNames.append(tr("Vehicle %1").arg(message.sysid));
867
        emit vehiclesChanged();
Gus Grubba's avatar
Gus Grubba committed
868 869 870 871
        if(!_activeVehicle) {
            _activeVehicle = v;
            emit activeVehiclesChanged();
        }
872
    } else {
Gus Grubba's avatar
Gus Grubba committed
873
        m = v->findMessage(message.msgid, message.compid);
874
    }
875 876 877
    if(!m) {
        m = new QGCMAVLinkMessage(this, &message);
        v->append(m);
878
    } else {
879
        m->update(&message);
880 881 882 883
    }
}

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

894 895
//-----------------------------------------------------------------------------
void
896
MAVLinkInspectorController::deleteChart(MAVLinkChartController* chart)
897
{
898 899 900
    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
901
            if(c && c == chart) {
902
                _charts.removeOne(c);
Gus Grubba's avatar
Gus Grubba committed
903
                delete c;
904
                break;
905 906
            }
        }
907
        emit chartsChanged();
908 909 910 911
    }
}

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

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