diff --git a/src/AnalyzeView/MAVLinkInspectorController.cc b/src/AnalyzeView/MAVLinkInspectorController.cc index 6ab01f1176b7462044bb55b942362900dc31d401..3984ca7039ef80133b6c773156c9dc5f8eb4d656 100644 --- a/src/AnalyzeView/MAVLinkInspectorController.cc +++ b/src/AnalyzeView/MAVLinkInspectorController.cc @@ -18,14 +18,6 @@ QT_CHARTS_USE_NAMESPACE Q_DECLARE_METATYPE(QAbstractSeries*) -//----------------------------------------------------------------------------- -QGCMAVLinkMessageField::Range_st::Range_st(QObject* parent, const QString& l, qreal r) - : QObject(parent) - , label(l) - , range(r) -{ -} - //----------------------------------------------------------------------------- QGCMAVLinkMessageField::QGCMAVLinkMessageField(QGCMAVLinkMessage *parent, QString name, QString type) : QObject(parent) @@ -34,46 +26,35 @@ QGCMAVLinkMessageField::QGCMAVLinkMessageField(QGCMAVLinkMessage *parent, QStrin , _msg(parent) { qCDebug(MAVLinkInspectorLog) << "Field:" << name << type; - _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(); } -//---------------------------------------------------------------------------------------- -QStringList -QGCMAVLinkMessageField::rangeList() +//----------------------------------------------------------------------------- +void +QGCMAVLinkMessageField::addSeries(QAbstractSeries* series, bool left) { - if(!_rangeList.count()) { - for(int i = 0; i < _rangeSt.count(); i++) { - _rangeList << _rangeSt[i]->label; - } + if(!_pSeries) { + _left = left; + _pSeries = series; + emit seriesChanged(); + _dataIndex = 0; + _msg->msgCtl()->addChartField(this, left); + _msg->select(); } - return _rangeList; } //----------------------------------------------------------------------------- void -QGCMAVLinkMessageField::setRange(quint32 r) +QGCMAVLinkMessageField::delSeries() { - if(r < static_cast(_rangeSt.count())) { - _rangeIndex = r; - _range = _rangeSt[static_cast(r)]->range; - emit rangeChanged(); - //-- If not Auto, use defined range - if(_rangeIndex > 0) { - _rangeMin = -_range; - emit rangeMinChanged(); - _rangeMax = _range; - emit rangeMaxChanged(); - } + if(_pSeries) { + _values.clear(); + _msg->msgCtl()->delChartField(this, _left); + QLineSeries* lineSeries = static_cast(_pSeries); + lineSeries->replace(_values); + _pSeries = nullptr; + _left = false; + emit seriesChanged(); + _msg->select(); } } @@ -81,6 +62,7 @@ QGCMAVLinkMessageField::setRange(quint32 r) QString QGCMAVLinkMessageField::label() { + //-- Label is message name + field name return QString(_msg->name() + ": " + _name); } @@ -94,29 +76,6 @@ QGCMAVLinkMessageField::setSelectable(bool sel) } } -//----------------------------------------------------------------------------- -void -QGCMAVLinkMessageField::setSelected(bool sel) -{ - if(_selected != sel) { - _selected = sel; - emit selectedChanged(); - _values.clear(); - _times.clear(); - _rangeMin = 0; - _rangeMax = 0; - _dataIndex = 0; - emit rangeMinChanged(); - emit rangeMaxChanged(); - if(_selected) { - _msg->msgCtl()->addChartField(this); - } else { - _msg->msgCtl()->delChartField(this); - } - _msg->select(); - } -} - //----------------------------------------------------------------------------- void QGCMAVLinkMessageField::updateValue(QString newValue, qreal v) @@ -125,34 +84,38 @@ QGCMAVLinkMessageField::updateValue(QString newValue, qreal v) _value = newValue; emit valueChanged(); } - if(_selected) { + if(_pSeries) { int count = _values.count(); //-- Arbitrary limit of 1 minute of data at 50Hz for now if(count < (50 * 60)) { - _values.append(v); - _times.append(QGC::groundTimeMilliseconds()); + QPointF p(QGC::groundTimeMilliseconds(), v); + _values.append(p); } else { if(_dataIndex >= count) _dataIndex = 0; - _values[_dataIndex] = v; - _times[_dataIndex] = QGC::groundTimeMilliseconds(); + _values[_dataIndex].setX(QGC::groundTimeMilliseconds()); + _values[_dataIndex].setY(v); _dataIndex++; } //-- Auto Range - if(_rangeIndex == 0) { + if((!_left && _msg->msgCtl()->rightRangeIdx() == 0) || (_left && _msg->msgCtl()->leftRangeIdx() == 0)) { qreal vmin = std::numeric_limits::max(); qreal vmax = std::numeric_limits::min(); for(int i = 0; i < _values.count(); i++) { - qreal v = _values[i]; + qreal v = _values[i].y(); if(vmax < v) vmax = v; if(vmin > v) vmin = v; } + bool changed = false; if(std::abs(_rangeMin - vmin) > 0.000001) { _rangeMin = vmin; - emit rangeMinChanged(); + changed = true; } if(std::abs(_rangeMax - vmax) > 0.000001) { _rangeMax = vmax; - emit rangeMaxChanged(); + changed = true; + } + if(changed) { + _msg->msgCtl()->updateYRange(_left); } } _msg->msgCtl()->updateXRange(); @@ -166,14 +129,8 @@ QGCMAVLinkMessageField::_updateSeries() { int count = _values.count(); if (count > 1) { - _series.clear(); - int idx = _dataIndex; - for(int i = 0; i < count; i++, idx++) { - if(idx >= count) idx = 0; - QPointF p(_times[idx], _values[idx]); - _series.append(p); - } - emit seriesChanged(); + QLineSeries* lineSeries = static_cast(_pSeries); + lineSeries->replace(_values); } } @@ -539,6 +496,14 @@ MAVLinkInspectorController::TimeScale_st::TimeScale_st(QObject* parent, const QS { } +//----------------------------------------------------------------------------- +MAVLinkInspectorController::Range_st::Range_st(QObject* parent, const QString& l, qreal r) + : QObject(parent) + , label(l) + , range(r) +{ +} + //----------------------------------------------------------------------------- MAVLinkInspectorController::MAVLinkInspectorController() { @@ -551,22 +516,30 @@ MAVLinkInspectorController::MAVLinkInspectorController() _updateTimer.start(1000); MultiVehicleManager *manager = qgcApp()->toolbox()->multiVehicleManager(); connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &MAVLinkInspectorController::_setActiveVehicle); - _rangeXMax = QDateTime::fromMSecsSinceEpoch(0); - _rangeXMin = QDateTime::fromMSecsSinceEpoch(std::numeric_limits::max()); _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(); + _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(); + updateXRange(); } //----------------------------------------------------------------------------- MAVLinkInspectorController::~MAVLinkInspectorController() { - _reset(); } - //---------------------------------------------------------------------------------------- QStringList MAVLinkInspectorController::timeScales() @@ -579,6 +552,54 @@ MAVLinkInspectorController::timeScales() return _timeScales; } +//---------------------------------------------------------------------------------------- +QStringList +MAVLinkInspectorController::rangeList() +{ + if(!_rangeList.count()) { + for(int i = 0; i < _rangeSt.count(); i++) { + _rangeList << _rangeSt[i]->label; + } + } + return _rangeList; +} + +//----------------------------------------------------------------------------- +void +MAVLinkInspectorController::setLeftRangeIdx(quint32 r) +{ + if(r < static_cast(_rangeSt.count())) { + _leftRangeIndex = r; + _timeRange = _rangeSt[static_cast(r)]->range; + emit leftRangeChanged(); + //-- If not Auto, use defined range + if(_leftRangeIndex > 0) { + _leftRangeMin = -_timeRange; + emit leftRangeMinChanged(); + _leftRangeMax = _timeRange; + emit leftRangeMaxChanged(); + } + } +} + +//----------------------------------------------------------------------------- +void +MAVLinkInspectorController::setRightRangeIdx(quint32 r) +{ + if(r < static_cast(_rangeSt.count())) { + _rightRangeIndex = r; + _timeRange = _rangeSt[static_cast(r)]->range; + emit rightRangeChanged(); + //-- If not Auto, use defined range + if(_rightRangeIndex > 0) { + _rightRangeMin = -_timeRange; + emit rightRangeMinChanged(); + _rightRangeMax = _timeRange; + emit rightRangeMaxChanged(); + } + } +} + //---------------------------------------------------------------------------------------- void MAVLinkInspectorController::_setActiveVehicle(Vehicle* vehicle) @@ -686,53 +707,54 @@ MAVLinkInspectorController::_receiveMessage(LinkInterface*, mavlink_message_t me //----------------------------------------------------------------------------- void -MAVLinkInspectorController::_reset() -{ -} - -//----------------------------------------------------------------------------- -void -MAVLinkInspectorController::addChartField(QGCMAVLinkMessageField* field) +MAVLinkInspectorController::addChartField(QGCMAVLinkMessageField* field, bool left) { QVariant f = QVariant::fromValue(field); - for(int i = 0; i < _chartFields.count(); i++) { - if(_chartFields.at(i) == f) { + QVariantList* pList; + if(left) { + pList = &_leftChartFields; + } else { + pList = &_rightChartFields; + } + for(int i = 0; i < pList->count(); i++) { + if(pList->at(i) == f) { return; } } - _chartFields.append(f); - emit chartFieldCountChanged(); + pList->append(f); + if(left) { + emit leftChartFieldsChanged(); + } else { + emit rightChartFieldsChanged(); + } + emit seriesCountChanged(); } //----------------------------------------------------------------------------- void -MAVLinkInspectorController::delChartField(QGCMAVLinkMessageField* field) +MAVLinkInspectorController::delChartField(QGCMAVLinkMessageField* field, bool left) { QVariant f = QVariant::fromValue(field); - for(int i = 0; i < _chartFields.count(); i++) { - if(_chartFields.at(i) == f) { - _chartFields.removeAt(i); - emit chartFieldCountChanged(); - if(_chartFields.count() == 0) { - _rangeXMax = QDateTime::fromMSecsSinceEpoch(0); - _rangeXMin = QDateTime::fromMSecsSinceEpoch(std::numeric_limits::max()); + QVariantList* pList; + if(left) { + pList = &_leftChartFields; + } else { + pList = &_rightChartFields; + } + for(int i = 0; i < pList->count(); i++) { + if(pList->at(i) == f) { + pList->removeAt(i); + if(left) { + emit leftChartFieldsChanged(); + } else { + emit rightChartFieldsChanged(); } + emit seriesCountChanged(); return; } } } -//----------------------------------------------------------------------------- -void -MAVLinkInspectorController::updateSeries(int index, QAbstractSeries* series) -{ - if(index < _chartFields.count() && series) { - QGCMAVLinkMessageField* f = qvariant_cast(_chartFields.at(index)); - QLineSeries* lineSeries = static_cast(series); - lineSeries->replace(f->series()); - } -} - //----------------------------------------------------------------------------- void MAVLinkInspectorController::setTimeScale(quint32 t) @@ -754,3 +776,79 @@ MAVLinkInspectorController::updateXRange() emit rangeMaxXChanged(); } } + +//----------------------------------------------------------------------------- +void +MAVLinkInspectorController::updateYRange(bool left) +{ + QVariantList* pList; + if(left) { + pList = &_leftChartFields; + } else { + pList = &_rightChartFields; + } + if(pList->count()) { + qreal vmin = std::numeric_limits::max(); + qreal vmax = std::numeric_limits::min(); + for(int i = 0; i < pList->count(); i++) { + QObject* object = qvariant_cast(pList->at(i)); + QGCMAVLinkMessageField* pField = qobject_cast(object); + if(pField) { + if(vmax < pField->rangeMax()) vmax = pField->rangeMax(); + if(vmin > pField->rangeMin()) vmin = pField->rangeMin(); + } + } + if(left) { + if(std::abs(_leftRangeMin - vmin) > 0.000001) { + _leftRangeMin = vmin; + emit leftRangeMinChanged(); + } + if(std::abs(_leftRangeMax - vmax) > 0.000001) { + _leftRangeMax = vmax; + emit leftRangeMaxChanged(); + } + } else { + if(std::abs(_rightRangeMin - vmin) > 0.000001) { + _rightRangeMin = vmin; + emit rightRangeMinChanged(); + } + if(std::abs(_rightRangeMax - vmax) > 0.000001) { + _rightRangeMax = vmax; + emit rightRangeMaxChanged(); + } + } + } +} + +//----------------------------------------------------------------------------- +void +MAVLinkInspectorController::addSeries(QGCMAVLinkMessageField* field, QAbstractSeries* series, bool left) +{ + if(field) { + field->addSeries(series, left); + } +} + +//----------------------------------------------------------------------------- +void +MAVLinkInspectorController::delSeries(QGCMAVLinkMessageField* field) +{ + if(field) { + field->delSeries(); + } + if(_leftChartFields.count() == 0) { + _leftRangeMin = 0; + _leftRangeMax = 1; + emit leftRangeMinChanged(); + emit leftRangeMaxChanged(); + } + if(_rightChartFields.count() == 0) { + _rightRangeMin = 0; + _rightRangeMax = 1; + emit rightRangeMinChanged(); + emit rightRangeMaxChanged(); + } + if(_leftChartFields.count() == 0 && _rightChartFields.count() == 0) { + updateXRange(); + } +} diff --git a/src/AnalyzeView/MAVLinkInspectorController.h b/src/AnalyzeView/MAVLinkInspectorController.h index 264cf303517d60b689d853590dd43cd9d9fe4a1c..3052629db960bd35ecc143c58a9f11d289a6ba19 100644 --- a/src/AnalyzeView/MAVLinkInspectorController.h +++ b/src/AnalyzeView/MAVLinkInspectorController.h @@ -28,75 +28,57 @@ class MAVLinkInspectorController; //----------------------------------------------------------------------------- class QGCMAVLinkMessageField : public QObject { Q_OBJECT - Q_PROPERTY(QString name READ name CONSTANT) - Q_PROPERTY(QString label READ label CONSTANT) - Q_PROPERTY(QString type READ type CONSTANT) - Q_PROPERTY(QString value READ value NOTIFY valueChanged) - Q_PROPERTY(QStringList rangeList READ rangeList NOTIFY rangeListChanged) - Q_PROPERTY(qreal rangeMin READ rangeMin NOTIFY rangeMinChanged) - Q_PROPERTY(qreal rangeMax READ rangeMax NOTIFY rangeMaxChanged) - Q_PROPERTY(bool selectable READ selectable NOTIFY selectableChanged) - Q_PROPERTY(bool selected READ selected WRITE setSelected NOTIFY selectedChanged) - Q_PROPERTY(quint32 range READ range WRITE setRange NOTIFY rangeChanged) + Q_PROPERTY(QString name READ name CONSTANT) + Q_PROPERTY(QString label READ label CONSTANT) + Q_PROPERTY(QString type READ type CONSTANT) + Q_PROPERTY(QString value READ value NOTIFY valueChanged) + Q_PROPERTY(bool selectable READ selectable NOTIFY selectableChanged) + Q_PROPERTY(bool left READ left NOTIFY seriesChanged) + Q_PROPERTY(QAbstractSeries* series READ series NOTIFY seriesChanged) public: QGCMAVLinkMessageField(QGCMAVLinkMessage* parent, QString name, QString type); - QString name () { return _name; } - QString label (); - QString type () { return _type; } - QString value () { return _value; } - QStringList rangeList (); - qreal rangeMin () { return _rangeMin; } - qreal rangeMax () { return _rangeMax; } - QList series () { return _series; } - bool selectable () { return _selectable; } - bool selected () { return _selected; } - quint32 range () { return _rangeIndex; } - - void setSelectable (bool sel); - void setSelected (bool sel); - void setRange (quint32 r); - void updateValue (QString newValue, qreal v); + QString name () { return _name; } + QString label (); + QString type () { return _type; } + QString value () { return _value; } + bool selectable () { return _selectable; } + bool selected () { return _pSeries != nullptr; } + bool left () { return _left; } + QAbstractSeries*series () { return _pSeries; } + QList* values () { return &_values;} + qreal rangeMin () { return _rangeMin; } + qreal rangeMax () { return _rangeMax; } + + void setSelectable (bool sel); + void updateValue (QString newValue, qreal v); + + void addSeries (QAbstractSeries* series, bool left); + void delSeries (); signals: - void rangeMinChanged (); - void rangeMaxChanged (); - void seriesChanged (); - void selectableChanged (); - void selectedChanged (); - void valueChanged (); - void rangeListChanged (); - void rangeChanged (); + void seriesChanged (); + void selectableChanged (); + void valueChanged (); private: - void _updateSeries (); + void _updateSeries (); private: - class Range_st : public QObject { - public: - Range_st(QObject* parent, const QString& l, qreal r); - QString label; - qreal range; - }; - QString _type; QString _name; QString _value; - QGCMAVLinkMessage* _msg = nullptr; bool _selectable = true; - bool _selected = false; + bool _left = false; int _dataIndex = 0; qreal _rangeMin = 0; qreal _rangeMax = 0; - quint32 _rangeIndex = 0; ///> Auto Range - qreal _range = 0; - QStringList _rangeList; - QVector _values; - QVector _times; - QList _series; - QList _rangeSt; + + QAbstractSeries* _pSeries = nullptr; + QGCMAVLinkMessage* _msg = nullptr; + QList _values; }; //----------------------------------------------------------------------------- @@ -186,41 +168,73 @@ public: MAVLinkInspectorController(); ~MAVLinkInspectorController(); - Q_PROPERTY(QStringList vehicleNames READ vehicleNames NOTIFY vehiclesChanged) - Q_PROPERTY(QmlObjectListModel* vehicles READ vehicles NOTIFY vehiclesChanged) - Q_PROPERTY(QGCMAVLinkVehicle* activeVehicle READ activeVehicle NOTIFY activeVehiclesChanged) - Q_PROPERTY(int chartFieldCount READ chartFieldCount NOTIFY chartFieldCountChanged) - Q_PROPERTY(QVariantList chartFields READ chartFields NOTIFY chartFieldCountChanged) - Q_PROPERTY(QDateTime rangeXMin READ rangeXMin NOTIFY rangeMinXChanged) - Q_PROPERTY(QDateTime rangeXMax READ rangeXMax NOTIFY rangeMaxXChanged) - Q_PROPERTY(QStringList timeScales READ timeScales NOTIFY timeScalesChanged) - Q_PROPERTY(quint32 timeScale READ timeScale WRITE setTimeScale NOTIFY timeScaleChanged) - - Q_INVOKABLE void updateSeries (int index, QAbstractSeries *series); - - QmlObjectListModel* vehicles () { return &_vehicles; } - QGCMAVLinkVehicle* activeVehicle () { return _activeVehicle; } - QStringList vehicleNames () { return _vehicleNames; } - quint32 timeScale () { return _timeScale; } - QStringList timeScales (); - QVariantList chartFields () { return _chartFields; } - QDateTime rangeXMin () { return _rangeXMin; } - QDateTime rangeXMax () { return _rangeXMax; } - - void setTimeScale (quint32 t); - int chartFieldCount () { return _chartFields.count(); } - void addChartField (QGCMAVLinkMessageField* field); - void delChartField (QGCMAVLinkMessageField* field); - void updateXRange (); + Q_PROPERTY(QStringList vehicleNames READ vehicleNames NOTIFY vehiclesChanged) + Q_PROPERTY(QmlObjectListModel* vehicles READ vehicles NOTIFY vehiclesChanged) + Q_PROPERTY(QGCMAVLinkVehicle* activeVehicle READ activeVehicle NOTIFY activeVehiclesChanged) + Q_PROPERTY(QVariantList rightChartFields READ rightChartFields NOTIFY rightChartFieldsChanged) + Q_PROPERTY(QVariantList leftChartFields READ leftChartFields NOTIFY leftChartFieldsChanged) + Q_PROPERTY(int seriesCount READ seriesCount NOTIFY seriesCountChanged) + Q_PROPERTY(QDateTime rangeXMin READ rangeXMin NOTIFY rangeMinXChanged) + Q_PROPERTY(QDateTime rangeXMax READ rangeXMax NOTIFY rangeMaxXChanged) + Q_PROPERTY(qreal rightRangeMin READ rightRangeMin NOTIFY rightRangeMinChanged) + Q_PROPERTY(qreal rightRangeMax READ rightRangeMax NOTIFY rightRangeMaxChanged) + Q_PROPERTY(qreal leftRangeMin READ leftRangeMin NOTIFY leftRangeMinChanged) + Q_PROPERTY(qreal leftRangeMax READ leftRangeMax NOTIFY leftRangeMaxChanged) + Q_PROPERTY(QStringList timeScales READ timeScales NOTIFY timeScalesChanged) + Q_PROPERTY(QStringList rangeList READ rangeList NOTIFY rangeListChanged) + + Q_PROPERTY(quint32 leftRangeIdx READ leftRangeIdx WRITE setLeftRangeIdx NOTIFY leftRangeChanged) + Q_PROPERTY(quint32 rightRangeIdx READ rightRangeIdx WRITE setRightRangeIdx NOTIFY rightRangeChanged) + Q_PROPERTY(quint32 timeScale READ timeScale WRITE setTimeScale NOTIFY timeScaleChanged) + + Q_INVOKABLE void addSeries (QGCMAVLinkMessageField* field, QAbstractSeries* series, bool left); + Q_INVOKABLE void delSeries (QGCMAVLinkMessageField* field); + + QmlObjectListModel* vehicles () { return &_vehicles; } + QGCMAVLinkVehicle* activeVehicle () { return _activeVehicle; } + QStringList vehicleNames () { return _vehicleNames; } + quint32 timeScale () { return _timeScale; } + QStringList timeScales (); + int seriesCount () { return _rightChartFields.count() + _leftChartFields.count(); } + QStringList rangeList (); + QVariantList rightChartFields () { return _rightChartFields; } + QVariantList leftChartFields () { return _leftChartFields; } + QDateTime rangeXMin () { return _rangeXMin; } + QDateTime rangeXMax () { return _rangeXMax; } + + qreal rightRangeMin () { return _rightRangeMin; } + qreal rightRangeMax () { return _rightRangeMax; } + quint32 rightRangeIdx () { return _rightRangeIndex; } + + qreal leftRangeMin () { return _leftRangeMin; } + qreal leftRangeMax () { return _leftRangeMax; } + quint32 leftRangeIdx () { return _leftRangeIndex; } + + void setTimeScale (quint32 t); + void setRightRangeIdx (quint32 r); + void setLeftRangeIdx (quint32 r); + void addChartField (QGCMAVLinkMessageField* field, bool left); + void delChartField (QGCMAVLinkMessageField* field, bool left); + void updateXRange (); + void updateYRange (bool left); signals: void vehiclesChanged (); void activeVehiclesChanged (); - void chartFieldCountChanged (); + void rightChartFieldsChanged (); + void leftChartFieldsChanged (); void timeScaleChanged (); void rangeMinXChanged (); void rangeMaxXChanged (); void timeScalesChanged (); + void rangeListChanged (); + void rightRangeMinChanged (); + void rightRangeMaxChanged (); + void rightRangeChanged (); + void leftRangeMinChanged (); + void leftRangeMaxChanged (); + void leftRangeChanged (); + void seriesCountChanged (); private slots: void _receiveMessage (LinkInterface* link, mavlink_message_t message); @@ -230,7 +244,6 @@ private slots: void _refreshFrequency (); private: - void _reset (); QGCMAVLinkVehicle* _findVehicle (uint8_t id); private: @@ -242,16 +255,33 @@ private: uint32_t timeScale; }; + class Range_st : public QObject { + public: + Range_st(QObject* parent, const QString& l, qreal r); + QString label; + qreal range; + }; + int _selectedSystemID = 0; ///< Currently selected system int _selectedComponentID = 0; ///< Currently selected component QStringList _timeScales; + QStringList _rangeList; quint32 _timeScale = 0; ///< 5 Seconds QDateTime _rangeXMin; QDateTime _rangeXMax; + qreal _leftRangeMin = 0; + qreal _leftRangeMax = 1; + quint32 _leftRangeIndex = 0; ///> Auto Range + qreal _rightRangeMin = 0; + qreal _rightRangeMax = 1; + quint32 _rightRangeIndex = 0; ///> Auto Range + qreal _timeRange = 0; QGCMAVLinkVehicle* _activeVehicle = nullptr; QTimer _updateTimer; QStringList _vehicleNames; QmlObjectListModel _vehicles; ///< List of QGCMAVLinkVehicle - QVariantList _chartFields; + QVariantList _rightChartFields; + QVariantList _leftChartFields; QList_timeScaleSt; + QList _rangeSt; }; diff --git a/src/AnalyzeView/MAVLinkInspectorPage.qml b/src/AnalyzeView/MAVLinkInspectorPage.qml index a60e2c62dcfd08555f924c3a5d5eb698aed994c6..71bc9f3c0927226989b1c37b6f8592d9b8e1c06d 100644 --- a/src/AnalyzeView/MAVLinkInspectorPage.qml +++ b/src/AnalyzeView/MAVLinkInspectorPage.qml @@ -257,14 +257,16 @@ AnalyzePage { QGCLabel { text: qsTr("Message Fields:") } + //--------------------------------------------------------- Rectangle { Layout.fillWidth: true height: 1 color: qgcPal.text } Item { height: ScreenTools.defaultFontPixelHeight * 0.25; width: 1 } + //--------------------------------------------------------- GridLayout { - columns: 4 + columns: 5 columnSpacing: ScreenTools.defaultFontPixelWidth rowSpacing: ScreenTools.defaultFontPixelHeight * 0.25 Repeater { @@ -299,9 +301,35 @@ AnalyzePage { delegate: QGCCheckBox { Layout.row: index Layout.column: 3 - enabled: object.selected || (object.selectable && controller.chartFieldCount < 2) - checked: enabled ? object.selected : false - onClicked: { if(enabled) object.selected = checked } + enabled: (object.series !== null && object.left) || (object.selectable && controller.seriesCount < chartView.maxSeriesCount) + checked: enabled ? (object.series !== null && object.left) : false + onClicked: { + if(enabled) { + if(checked) { + chartView.addDimension(object, true) + } else { + chartView.delDimension(object) + } + } + } + } + } + Repeater { + model: curMessage ? curMessage.fields : [] + delegate: QGCCheckBox { + Layout.row: index + Layout.column: 4 + enabled: (object.series !== null && !object.left) || (object.selectable && controller.seriesCount < chartView.maxSeriesCount && (object.series === null && !object.left)) + checked: enabled ? (object.series !== null && !object.left) : false + onClicked: { + if(enabled) { + if(checked) { + chartView.addDimension(object, false) + } else { + chartView.delDimension(object) + } + } + } } } } @@ -312,86 +340,69 @@ AnalyzePage { height: ScreenTools.defaultFontPixelHeight * 20 theme: ChartView.ChartThemeDark antialiasing: true - visible: controller.chartFieldCount > 0 + visible: controller.leftChartFields.length > 0 || controller.rightChartFields.length > 0 animationOptions: ChartView.NoAnimation legend.visible: false margins.bottom: ScreenTools.defaultFontPixelHeight * 1.5 margins.top: chartHeader.height + (ScreenTools.defaultFontPixelHeight * 2) + property int maxSeriesCount: seriesColors.length + property var seriesColors: ["antiquewhite", "aqua", "chartreuse", "chocolate", "crimson", "darkturquoise", "aquamarine", "azure", "coral", "cornflowerblue", "darkorange", "gold", "hotpink", "lavenderblush", "lightskyblue"] + + function addDimension(field, left) { + console.log(field.name + ' ' + field + ' AxisY1: ' + axisY1 + ' AxisY2: ' + axisY2) + console.log(controller.seriesCount + ' ' + chartView.seriesColors[controller.seriesCount]) + var serie = createSeries(ChartView.SeriesTypeLine, field.label) + serie.axisX = axisX + if(left) { + serie.axisY = axisY1 + } else { + serie.axisYRight = axisY2 + } + serie.useOpenGL = true + serie.color = chartView.seriesColors[controller.seriesCount] + controller.addSeries(field, serie, left) + } + + function delDimension(field) { + chartView.removeSeries(field.series) + controller.delSeries(field) + console.log('Remove: ' + controller.seriesCount + ' ' + field.name) + } + DateTimeAxis { id: axisX min: visible ? controller.rangeXMin : new Date() max: visible ? controller.rangeXMax : new Date() - visible: controller.chartFieldCount > 0 - format: "mm:ss" + format: "hh:mm:ss" tickCount: 5 gridVisible: true - labelsFont.pixelSize: ScreenTools.smallFontPointSize + labelsFont.family: "Fixed" + labelsFont.pixelSize: ScreenTools.smallFontPointSize } ValueAxis { id: axisY1 - min: visible ? controller.chartFields[0].rangeMin : 0 - max: visible ? controller.chartFields[0].rangeMax : 0 - visible: controller.chartFieldCount > 0 + min: visible ? controller.leftRangeMin : 0 + max: visible ? controller.leftRangeMax : 0 + visible: controller.leftChartFields.length > 0 lineVisible: false - labelsFont.pixelSize: ScreenTools.smallFontPointSize - labelsColor: qgcPal.colorRed + labelsFont.family: "Fixed" + labelsFont.pixelSize: ScreenTools.smallFontPointSize + //labelsColor: qgcPal.colorRed } ValueAxis { id: axisY2 - min: visible ? controller.chartFields[1].rangeMin : 0 - max: visible ? controller.chartFields[1].rangeMax : 0 - visible: controller.chartFieldCount > 1 + min: visible ? controller.rightRangeMin : 0 + max: visible ? controller.rightRangeMax : 0 + visible: controller.rightChartFields.length > 0 lineVisible: false - labelsFont.pixelSize: ScreenTools.smallFontPointSize - labelsColor: qgcPal.colorGreen + labelsFont.family: "Fixed" + labelsFont.pixelSize: ScreenTools.smallFontPointSize + //labelsColor: qgcPal.colorGreen } - LineSeries { - id: lineSeries1 - name: controller.chartFieldCount ? controller.chartFields[0].label : "" - axisX: axisX - axisY: axisY1 - color: qgcPal.colorRed - useOpenGL: true - } - - LineSeries { - id: lineSeries2 - name: controller.chartFieldCount > 1 ? controller.chartFields[1].label : "" - axisX: axisX - axisYRight: axisY2 - color: qgcPal.colorGreen - useOpenGL: true - } - - Timer { - id: refreshTimer - interval: 1 / 20 * 1000 // 20 Hz - running: controller.chartFieldCount > 0 - repeat: true - onTriggered: { - if(controller.chartFieldCount > 0) { - controller.updateSeries(0, lineSeries1) - } - if(controller.chartFieldCount > 1) { - controller.updateSeries(1, lineSeries2) - } else { - if(lineSeries2.count > 0) { - lineSeries2.removePoints(0,lineSeries2.count) - } - } - } - onRunningChanged: { - if(!running) { - if(lineSeries1.count > 0) { - lineSeries1.removePoints(0,lineSeries1.count) - } - } - } - } RowLayout { id: chartHeader anchors.left: parent.left @@ -417,45 +428,38 @@ AnalyzePage { Layout.alignment: Qt.AlignVCenter } GridLayout { - columns: 3 + columns: 2 columnSpacing: ScreenTools.defaultFontPixelWidth rowSpacing: ScreenTools.defaultFontPixelHeight * 0.25 Layout.alignment: Qt.AlignRight | Qt.AlignVCenter Layout.fillWidth: true - Repeater { - model: controller.chartFieldCount ? controller.chartFields : [] - delegate: QGCLabel { - text: chartView.series(index).name - color: chartView.series(index).color - font.pixelSize: ScreenTools.smallFontPointSize - Layout.row: index - Layout.column: 0 - Layout.alignment: Qt.AlignVCenter - } + QGCLabel { + text: qsTr("Range Left:"); + font.pixelSize: ScreenTools.smallFontPointSize + Layout.alignment: Qt.AlignVCenter } - Repeater { - model: controller.chartFieldCount ? controller.chartFields : [] - delegate: QGCLabel { - text: qsTr("Range:"); - font.pixelSize: ScreenTools.smallFontPointSize - Layout.row: index - Layout.column: 1 - Layout.alignment: Qt.AlignVCenter - } + QGCComboBox { + Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 8 + height: ScreenTools.defaultFontPixelHeight * 1.5 + model: controller.rangeList + currentIndex: controller.leftRangeIdx + onActivated: controller.leftRangeIdx = index + font.pixelSize: ScreenTools.smallFontPointSize + Layout.alignment: Qt.AlignVCenter } - Repeater { - model: controller.chartFieldCount ? controller.chartFields : [] - delegate: QGCComboBox { - width: ScreenTools.defaultFontPixelWidth * 12 - height: ScreenTools.defaultFontPixelHeight * 1.5 - model: modelData.rangeList - currentIndex: modelData.range - onActivated: modelData.range = index - font.pixelSize: ScreenTools.smallFontPointSize - Layout.row: index - Layout.column: 2 - Layout.alignment: Qt.AlignVCenter - } + QGCLabel { + text: qsTr("Range Right:"); + font.pixelSize: ScreenTools.smallFontPointSize + Layout.alignment: Qt.AlignVCenter + } + QGCComboBox { + Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 8 + height: ScreenTools.defaultFontPixelHeight * 1.5 + model: controller.rangeList + currentIndex: controller.rightRangeIdx + onActivated: controller.rightRangeIdx = index + font.pixelSize: ScreenTools.smallFontPointSize + Layout.alignment: Qt.AlignVCenter } } }