From 0de02e587940efba40f3a586230fe35898291e12 Mon Sep 17 00:00:00 2001 From: Gus Grubba Date: Tue, 31 Dec 2019 15:52:21 -0500 Subject: [PATCH] WIP - MAVLink chart as a control. Add any number of charts with any number of series. All individually controlled. --- src/AnalyzeView/MAVLinkInspectorController.cc | 344 ++++++++---------- src/AnalyzeView/MAVLinkInspectorController.h | 195 +++++----- src/AnalyzeView/MAVLinkInspectorPage.qml | 18 +- src/QGCApplication.cc | 22 +- src/QmlControls/MAVLinkChart.qml | 113 +++--- 5 files changed, 314 insertions(+), 378 deletions(-) diff --git a/src/AnalyzeView/MAVLinkInspectorController.cc b/src/AnalyzeView/MAVLinkInspectorController.cc index 6d03b0b8cb..f08754a55d 100644 --- a/src/AnalyzeView/MAVLinkInspectorController.cc +++ b/src/AnalyzeView/MAVLinkInspectorController.cc @@ -32,14 +32,13 @@ QGCMAVLinkMessageField::QGCMAVLinkMessageField(QGCMAVLinkMessage *parent, QStrin //----------------------------------------------------------------------------- void -QGCMAVLinkMessageField::addSeries(QAbstractSeries* series, bool left) +QGCMAVLinkMessageField::addSeries(MAVLinkChartController* chart, QAbstractSeries* series) { if(!_pSeries) { - _left = left; + _chart = chart; _pSeries = series; emit seriesChanged(); _dataIndex = 0; - _msg->msgCtl()->addChartField(this, left); _msg->select(); } } @@ -50,11 +49,10 @@ QGCMAVLinkMessageField::delSeries() { if(_pSeries) { _values.clear(); - _msg->msgCtl()->delChartField(this, _left); QLineSeries* lineSeries = static_cast(_pSeries); lineSeries->replace(_values); _pSeries = nullptr; - _left = false; + _chart = nullptr; emit seriesChanged(); _msg->select(); } @@ -86,7 +84,7 @@ QGCMAVLinkMessageField::updateValue(QString newValue, qreal v) _value = newValue; emit valueChanged(); } - if(_pSeries) { + if(_pSeries && _chart) { int count = _values.count(); //-- Arbitrary limit of 1 minute of data at 50Hz for now if(count < (50 * 60)) { @@ -99,7 +97,7 @@ QGCMAVLinkMessageField::updateValue(QString newValue, qreal v) _dataIndex++; } //-- Auto Range - if((!_left && _msg->msgCtl()->rightRangeIdx() == 0) || (_left && _msg->msgCtl()->leftRangeIdx() == 0)) { + if(_chart->rangeYIndex() == 0) { qreal vmin = std::numeric_limits::max(); qreal vmax = std::numeric_limits::min(); for(int i = 0; i < _values.count(); i++) { @@ -117,7 +115,7 @@ QGCMAVLinkMessageField::updateValue(QString newValue, qreal v) changed = true; } if(changed) { - _msg->msgCtl()->updateYRange(_left); + _chart->updateYRange(); } } } @@ -143,9 +141,8 @@ QGCMAVLinkMessageField::updateSeries() } //----------------------------------------------------------------------------- -QGCMAVLinkMessage::QGCMAVLinkMessage(MAVLinkInspectorController *parent, mavlink_message_t* message) +QGCMAVLinkMessage::QGCMAVLinkMessage(QObject *parent, mavlink_message_t* message) : QObject(parent) - , _msgCtl(parent) { _message = *message; const mavlink_message_info_t* msgInfo = mavlink_get_message_info(message); @@ -497,19 +494,131 @@ QGCMAVLinkVehicle::_checkCompID(QGCMAVLinkMessage* message) } //----------------------------------------------------------------------------- -MAVLinkInspectorController::TimeScale_st::TimeScale_st(QObject* parent, const QString& l, uint32_t t) +MAVLinkChartController::MAVLinkChartController(MAVLinkInspectorController *parent) : QObject(parent) - , label(l) - , timeScale(t) + , _controller(parent) { + connect(&_updateSeriesTimer, &QTimer::timeout, this, &MAVLinkChartController::_refreshSeries); + updateXRange(); } //----------------------------------------------------------------------------- -MAVLinkInspectorController::Range_st::Range_st(QObject* parent, const QString& l, qreal r) - : QObject(parent) - , label(l) - , range(r) +void +MAVLinkChartController::setRangeYIndex(quint32 r) +{ + if(r < static_cast(_controller->rangeSt().count())) { + _rangeYIndex = r; + qreal range = _controller->rangeSt()[static_cast(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(_controller->timeScaleSt().count())) { + qint64 t = static_cast(QGC::groundTimeMilliseconds()); + _rangeXMax = QDateTime::fromMSecsSinceEpoch(t); + _rangeXMin = QDateTime::fromMSecsSinceEpoch(t - _controller->timeScaleSt()[static_cast(_rangeXIndex)]->timeScale); + emit rangeXMinChanged(); + emit rangeXMaxChanged(); + } +} + +//----------------------------------------------------------------------------- +void +MAVLinkChartController::updateYRange() +{ + if(_chartFields.count()) { + qreal vmin = std::numeric_limits::max(); + qreal vmax = std::numeric_limits::min(); + for(int i = 0; i < _chartFields.count(); i++) { + QObject* object = qvariant_cast(_chartFields.at(i)); + QGCMAVLinkMessageField* pField = qobject_cast(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(_chartFields.at(i)); + QGCMAVLinkMessageField* pField = qobject_cast(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) { + 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; + } + } + } } //----------------------------------------------------------------------------- @@ -521,9 +630,7 @@ MAVLinkInspectorController::MAVLinkInspectorController() MAVLinkProtocol* mavlinkProtocol = qgcApp()->toolbox()->mavlinkProtocol(); connect(mavlinkProtocol, &MAVLinkProtocol::messageReceived, this, &MAVLinkInspectorController::_receiveMessage); connect(&_updateFrequencyTimer, &QTimer::timeout, this, &MAVLinkInspectorController::_refreshFrequency); - connect(&_updateSeriesTimer, &QTimer::timeout, this, &MAVLinkInspectorController::_refreshSeries); _updateFrequencyTimer.start(1000); - _updateSeriesTimer.start(UPDATE_FREQUENCY); MultiVehicleManager *manager = qgcApp()->toolbox()->multiVehicleManager(); connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &MAVLinkInspectorController::_setActiveVehicle); _timeScaleSt.append(new TimeScale_st(this, tr("5 Sec"), 5 * 1000)); @@ -542,7 +649,6 @@ MAVLinkInspectorController::MAVLinkInspectorController() _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(); } //----------------------------------------------------------------------------- @@ -574,42 +680,6 @@ MAVLinkInspectorController::rangeList() return _rangeList; } -//----------------------------------------------------------------------------- -void -MAVLinkInspectorController::setLeftRangeIdx(quint32 r) -{ - if(r < static_cast(_rangeSt.count())) { - _leftRangeIndex = r; - qreal range = _rangeSt[static_cast(r)]->range; - emit leftRangeChanged(); - //-- If not Auto, use defined range - if(_leftRangeIndex > 0) { - _leftRangeMin = -range; - emit leftRangeMinChanged(); - _leftRangeMax = range; - emit leftRangeMaxChanged(); - } - } -} - -//----------------------------------------------------------------------------- -void -MAVLinkInspectorController::setRightRangeIdx(quint32 r) -{ - if(r < static_cast(_rangeSt.count())) { - _rightRangeIndex = r; - qreal range = _rangeSt[static_cast(r)]->range; - emit rightRangeChanged(); - //-- If not Auto, use defined range - if(_rightRangeIndex > 0) { - _rightRangeMin = -range; - emit rightRangeMinChanged(); - _rightRangeMax = range; - emit rightRangeMaxChanged(); - } - } -} - //---------------------------------------------------------------------------------------- void MAVLinkInspectorController::_setActiveVehicle(Vehicle* vehicle) @@ -716,160 +786,46 @@ MAVLinkInspectorController::_receiveMessage(LinkInterface*, mavlink_message_t me } //----------------------------------------------------------------------------- -void -MAVLinkInspectorController::addChartField(QGCMAVLinkMessageField* field, bool left) -{ - QVariant f = QVariant::fromValue(field); - QVariantList* pList; - if(left) { - pList = &_leftChartFields; - } else { - pList = &_rightChartFields; - } - for(int i = 0; i < pList->count(); i++) { - if(pList->at(i) == f) { - return; - } - } - pList->append(f); - if(left) { - emit leftChartFieldsChanged(); - } else { - emit rightChartFieldsChanged(); - } - emit seriesCountChanged(); -} - -//----------------------------------------------------------------------------- -void -MAVLinkInspectorController::delChartField(QGCMAVLinkMessageField* field, bool left) -{ - QVariant f = QVariant::fromValue(field); - 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::setTimeScale(quint32 t) +MAVLinkChartController* +MAVLinkInspectorController::createChart() { - _timeScale = t; - emit timeScaleChanged(); - updateXRange(); + MAVLinkChartController* pChart = new MAVLinkChartController(this); + QQmlEngine::setObjectOwnership(pChart, QQmlEngine::CppOwnership); + _charts.append(pChart); + emit chartsChanged(); + return pChart; } //----------------------------------------------------------------------------- void -MAVLinkInspectorController::updateXRange() +MAVLinkInspectorController::deleteChart(MAVLinkChartController* chart) { - if(_timeScale < static_cast(_timeScaleSt.count())) { - qint64 t = static_cast(QGC::groundTimeMilliseconds()); - _rangeXMax = QDateTime::fromMSecsSinceEpoch(t); - _rangeXMin = QDateTime::fromMSecsSinceEpoch(t - _timeScaleSt[static_cast(_timeScale)]->timeScale); - emit rangeMinXChanged(); - 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(); + if(chart) { + for(int i = 0; i < _charts.count(); i++) { + MAVLinkChartController* c = qobject_cast(_charts.get(i)); + if(c) { + _charts.removeOne(c); + break; } } + chart->deleteLater(); + emit chartsChanged(); } } //----------------------------------------------------------------------------- -void -MAVLinkInspectorController::addSeries(QGCMAVLinkMessageField* field, QAbstractSeries* series, bool left) +MAVLinkInspectorController::TimeScale_st::TimeScale_st(QObject* parent, const QString& l, uint32_t t) + : QObject(parent) + , label(l) + , timeScale(t) { - if(field) { - field->addSeries(series, left); - _updateSeriesTimer.start(UPDATE_FREQUENCY); - } } //----------------------------------------------------------------------------- -void -MAVLinkInspectorController::delSeries(QGCMAVLinkMessageField* field) +MAVLinkInspectorController::Range_st::Range_st(QObject* parent, const QString& l, qreal r) + : QObject(parent) + , label(l) + , range(r) { - if(field) { - field->delSeries(); - } - if(_leftChartFields.count() == 0 && _rightChartFields.count() == 0) { - updateXRange(); - _updateSeriesTimer.stop(); - } } -//----------------------------------------------------------------------------- -void -MAVLinkInspectorController::_refreshSeries() -{ - updateXRange(); - for(int i = 0; i < _leftChartFields.count(); i++) { - QObject* object = qvariant_cast(_leftChartFields.at(i)); - QGCMAVLinkMessageField* pField = qobject_cast(object); - if(pField) { - pField->updateSeries(); - } - } - for(int i = 0; i < _rightChartFields.count(); i++) { - QObject* object = qvariant_cast(_rightChartFields.at(i)); - QGCMAVLinkMessageField* pField = qobject_cast(object); - if(pField) { - pField->updateSeries(); - } - } -} diff --git a/src/AnalyzeView/MAVLinkInspectorController.h b/src/AnalyzeView/MAVLinkInspectorController.h index 53ba832cdf..b3ba378278 100644 --- a/src/AnalyzeView/MAVLinkInspectorController.h +++ b/src/AnalyzeView/MAVLinkInspectorController.h @@ -23,20 +23,20 @@ Q_DECLARE_LOGGING_CATEGORY(MAVLinkInspectorLog) QT_CHARTS_USE_NAMESPACE class QGCMAVLinkMessage; +class MAVLinkChartController; class MAVLinkInspectorController; //----------------------------------------------------------------------------- class QGCMAVLinkMessageField : public QObject { Q_OBJECT +public: 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; } @@ -45,7 +45,6 @@ public: 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; } @@ -54,7 +53,7 @@ public: void setSelectable (bool sel); void updateValue (QString newValue, qreal v); - void addSeries (QAbstractSeries* series, bool left); + void addSeries (MAVLinkChartController* chart, QAbstractSeries* series); void delSeries (); void updateSeries (); @@ -68,19 +67,20 @@ private: QString _name; QString _value; bool _selectable = true; - bool _left = false; int _dataIndex = 0; qreal _rangeMin = 0; qreal _rangeMax = 0; QAbstractSeries* _pSeries = nullptr; QGCMAVLinkMessage* _msg = nullptr; + MAVLinkChartController* _chart = nullptr; QList _values; }; //----------------------------------------------------------------------------- class QGCMAVLinkMessage : public QObject { Q_OBJECT +public: Q_PROPERTY(quint32 id READ id NOTIFY indexChanged) Q_PROPERTY(quint32 cid READ cid NOTIFY indexChanged) Q_PROPERTY(QString name READ name NOTIFY indexChanged) @@ -89,8 +89,7 @@ class QGCMAVLinkMessage : public QObject { Q_PROPERTY(QmlObjectListModel* fields READ fields NOTIFY indexChanged) Q_PROPERTY(bool selected READ selected NOTIFY selectedChanged) -public: - QGCMAVLinkMessage(MAVLinkInspectorController* parent, mavlink_message_t* message); + QGCMAVLinkMessage(QObject* parent, mavlink_message_t* message); quint32 id () { return _message.msgid; } quint8 cid () { return _message.compid; } @@ -101,8 +100,6 @@ public: QmlObjectListModel* fields () { return &_fields; } bool selected () { return _selected; } - MAVLinkInspectorController* msgCtl () { return _msgCtl; } - void select (); void update (mavlink_message_t* message); void updateFreq (); @@ -120,19 +117,18 @@ private: uint64_t _count = 0; uint64_t _lastCount = 0; mavlink_message_t _message; //-- List of QGCMAVLinkMessageField - MAVLinkInspectorController* _msgCtl = nullptr; bool _selected = false; }; //----------------------------------------------------------------------------- class QGCMAVLinkVehicle : public QObject { Q_OBJECT +public: Q_PROPERTY(quint8 id READ id CONSTANT) Q_PROPERTY(QmlObjectListModel* messages READ messages NOTIFY messagesChanged) Q_PROPERTY(QList compIDs READ compIDs NOTIFY compIDsChanged) Q_PROPERTY(QStringList compIDsStr READ compIDsStr NOTIFY compIDsChanged) -public: QGCMAVLinkVehicle(QObject* parent, quint8 id); quint8 id () { return _id; } @@ -158,93 +154,86 @@ private: }; //----------------------------------------------------------------------------- -class MAVLinkInspectorController : public QObject -{ +class MAVLinkChartController : public QObject { Q_OBJECT public: - MAVLinkInspectorController(); - ~MAVLinkInspectorController(); + MAVLinkChartController(MAVLinkInspectorController* parent); - 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_PROPERTY(QVariantList chartFields READ chartFields NOTIFY chartFieldsChanged) + Q_PROPERTY(QDateTime rangeXMin READ rangeXMin NOTIFY rangeXMinChanged) + Q_PROPERTY(QDateTime rangeXMax READ rangeXMax NOTIFY rangeXMaxChanged) + Q_PROPERTY(qreal rangeYMin READ rangeYMin NOTIFY rangeYMinChanged) + Q_PROPERTY(qreal rangeYMax READ rangeYMax NOTIFY rangeYMaxChanged) + + Q_PROPERTY(quint32 rangeYIndex READ rangeYIndex WRITE setRangeYIndex NOTIFY rangeYIndexChanged) + Q_PROPERTY(quint32 rangeXIndex READ rangeXIndex WRITE setRangeXIndex NOTIFY rangeXIndexChanged) + + Q_INVOKABLE void addSeries (QGCMAVLinkMessageField* field, QAbstractSeries* series); 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); + Q_INVOKABLE MAVLinkInspectorController* controller() { return _controller; } + + QVariantList chartFields () { return _chartFields; } + QDateTime rangeXMin () { return _rangeXMin; } + QDateTime rangeXMax () { return _rangeXMax; } + qreal rangeYMin () { return _rangeYMin; } + qreal rangeYMax () { return _rangeYMax; } + quint32 rangeXIndex () { return _rangeXIndex; } + quint32 rangeYIndex () { return _rangeYIndex; } + + void setRangeXIndex (quint32 t); + void setRangeYIndex (quint32 r); void updateXRange (); - void updateYRange (bool left); + void updateYRange (); signals: - void vehiclesChanged (); - void activeVehiclesChanged (); - 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 (); + void chartFieldsChanged (); + void rangeXMinChanged (); + void rangeXMaxChanged (); + void rangeYMinChanged (); + void rangeYMaxChanged (); + void rangeYIndexChanged (); + void rangeXIndexChanged (); private slots: - void _receiveMessage (LinkInterface* link, mavlink_message_t message); - void _vehicleAdded (Vehicle* vehicle); - void _vehicleRemoved (Vehicle* vehicle); - void _setActiveVehicle (Vehicle* vehicle); - void _refreshFrequency (); - void _refreshSeries (); + void _refreshSeries (); private: - QGCMAVLinkVehicle* _findVehicle (uint8_t id); + QTimer _updateSeriesTimer; + QDateTime _rangeXMin; + QDateTime _rangeXMax; + qreal _rangeYMin = 0; + qreal _rangeYMax = 1; + quint32 _rangeXIndex = 0; ///< 5 Seconds + quint32 _rangeYIndex = 0; ///< Auto Range + QVariantList _chartFields; + MAVLinkInspectorController* _controller = nullptr; +}; -private: +//----------------------------------------------------------------------------- +class MAVLinkInspectorController : public QObject +{ + Q_OBJECT +public: + MAVLinkInspectorController(); + ~MAVLinkInspectorController(); + + Q_PROPERTY(QStringList vehicleNames READ vehicleNames NOTIFY vehiclesChanged) + Q_PROPERTY(QmlObjectListModel* vehicles READ vehicles NOTIFY vehiclesChanged) + Q_PROPERTY(QmlObjectListModel* charts READ charts NOTIFY chartsChanged) + Q_PROPERTY(QGCMAVLinkVehicle* activeVehicle READ activeVehicle NOTIFY activeVehiclesChanged) + Q_PROPERTY(QStringList timeScales READ timeScales NOTIFY timeScalesChanged) + Q_PROPERTY(QStringList rangeList READ rangeList NOTIFY rangeListChanged) + + Q_INVOKABLE MAVLinkChartController* createChart (); + Q_INVOKABLE void deleteChart (MAVLinkChartController* chart); + + QmlObjectListModel* vehicles () { return &_vehicles; } + QmlObjectListModel* charts () { return &_charts; } + QGCMAVLinkVehicle* activeVehicle () { return _activeVehicle; } + QStringList vehicleNames () { return _vehicleNames; } + QStringList timeScales (); + QStringList rangeList (); class TimeScale_st : public QObject { public: @@ -260,26 +249,38 @@ private: qreal range; }; + const QList& timeScaleSt () { return _timeScaleSt; } + const QList& rangeSt () { return _rangeSt; } + +signals: + void vehiclesChanged (); + void chartsChanged (); + void activeVehiclesChanged (); + void timeScalesChanged (); + void rangeListChanged (); + +private slots: + void _receiveMessage (LinkInterface* link, mavlink_message_t message); + void _vehicleAdded (Vehicle* vehicle); + void _vehicleRemoved (Vehicle* vehicle); + void _setActiveVehicle (Vehicle* vehicle); + void _refreshFrequency (); + +private: + QGCMAVLinkVehicle* _findVehicle (uint8_t id); + +private: + 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 QGCMAVLinkVehicle* _activeVehicle = nullptr; QTimer _updateFrequencyTimer; - QTimer _updateSeriesTimer; QStringList _vehicleNames; QmlObjectListModel _vehicles; ///< List of QGCMAVLinkVehicle - QVariantList _rightChartFields; - QVariantList _leftChartFields; + QmlObjectListModel _charts; ///< List of MAVLinkCharts QList_timeScaleSt; QList _rangeSt; + }; diff --git a/src/AnalyzeView/MAVLinkInspectorPage.qml b/src/AnalyzeView/MAVLinkInspectorPage.qml index 444e192748..ed110ccce5 100644 --- a/src/AnalyzeView/MAVLinkInspectorPage.qml +++ b/src/AnalyzeView/MAVLinkInspectorPage.qml @@ -302,12 +302,12 @@ AnalyzePage { delegate: QGCCheckBox { Layout.row: index Layout.column: 3 - enabled: (object.series !== null && object.left) || (object.selectable && controller.seriesCount < 12) - checked: enabled ? (object.series !== null && object.left) : false + enabled: (object.series !== null) || (object.selectable) + checked: enabled ? (object.series !== null) : false onClicked: { if(enabled) { if(checked) { - chart1.addDimension(object, true) + chart1.addDimension(object) } else { chart1.delDimension(object) } @@ -320,12 +320,12 @@ AnalyzePage { delegate: QGCCheckBox { Layout.row: index Layout.column: 4 - enabled: (object.series !== null && !object.left) || (object.selectable && controller.seriesCount < 12 && (object.series === null && !object.left)) - checked: enabled ? (object.series !== null && !object.left) : false + enabled: (object.series !== null) || (object.selectable) + checked: enabled ? (object.series !== null) : false onClicked: { if(enabled) { if(checked) { - chart2.addDimension(object, false) + chart2.addDimension(object) } else { chart2.delDimension(object) } @@ -338,17 +338,11 @@ AnalyzePage { MAVLinkChart { id: chart1 height: ScreenTools.defaultFontPixelHeight * 20 - visible: controller.leftChartFields.length > 0 - min: controller.leftRangeMin - max: controller.leftRangeMax Layout.fillWidth: true } MAVLinkChart { id: chart2 height: ScreenTools.defaultFontPixelHeight * 20 - visible: controller.rightChartFields.length > 0 - min: controller.rightRangeMin - max: controller.rightRangeMax Layout.fillWidth: true } } diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index 7bb7c470e9..37536d019a 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -92,7 +92,6 @@ #include "QGCFileDownload.h" #include "FirmwareImage.h" #include "MavlinkConsoleController.h" -#include "MAVLinkInspectorController.h" #include "GeoTagController.h" #include "LogReplayLink.h" #include "VehicleObjectAvoidance.h" @@ -502,6 +501,7 @@ void QGCApplication::_initCommon() qmlRegisterUncreatableType (kQGroundControl, 1, 0, "CameraCalc", kRefOnly); qmlRegisterUncreatableType (kQGroundControl, 1, 0, "LogReplayLink", kRefOnly); qmlRegisterType (kQGroundControl, 1, 0, "LogReplayLinkController"); + qmlRegisterUncreatableType (kQGroundControl, 1, 0, "MAVLinkChart", kRefOnly); #if defined(QGC_ENABLE_PAIRING) qmlRegisterUncreatableType (kQGroundControl, 1, 0, "PairingManager", kRefOnly); #endif @@ -528,7 +528,6 @@ void QGCApplication::_initCommon() qmlRegisterType (kQGCControllers, 1, 0, "RCChannelMonitorController"); qmlRegisterType (kQGCControllers, 1, 0, "JoystickConfigController"); qmlRegisterType (kQGCControllers, 1, 0, "LogDownloadController"); - qmlRegisterType (kQGCControllers, 1, 0, "MAVLinkInspectorController"); qmlRegisterType (kQGCControllers, 1, 0, "SyslinkComponentController"); qmlRegisterType (kQGCControllers, 1, 0, "EditPositionDialogController"); @@ -617,21 +616,18 @@ QGCApplication* qgcApp(void) return QGCApplication::_app; } -void QGCApplication::informationMessageBoxOnMainThread(const QString& title, const QString& msg) +void QGCApplication::informationMessageBoxOnMainThread(const QString& /*title*/, const QString& msg) { - Q_UNUSED(title); showMessage(msg); } -void QGCApplication::warningMessageBoxOnMainThread(const QString& title, const QString& msg) +void QGCApplication::warningMessageBoxOnMainThread(const QString& /*title*/, const QString& msg) { - Q_UNUSED(title) showMessage(msg); } -void QGCApplication::criticalMessageBoxOnMainThread(const QString& title, const QString& msg) +void QGCApplication::criticalMessageBoxOnMainThread(const QString& /*title*/, const QString& msg) { - Q_UNUSED(title) showMessage(msg); } @@ -670,12 +666,11 @@ void QGCApplication::checkTelemetrySavePathOnMainThread() _checkTelemetrySavePath(false /* useMessageBox */); } -bool QGCApplication::_checkTelemetrySavePath(bool useMessageBox) +bool QGCApplication::_checkTelemetrySavePath(bool /*useMessageBox*/) { QString saveDirPath = _toolbox->settingsManager()->appSettings()->telemetrySavePath(); if (saveDirPath.isEmpty()) { QString error = tr("Unable to save telemetry log. Application save directory is not set."); - Q_UNUSED(useMessageBox); showMessage(error); return false; } @@ -793,10 +788,8 @@ void QGCApplication::_checkForNewVersion() #endif } -void QGCApplication::_currentVersionDownloadFinished(QString remoteFile, QString localFile) +void QGCApplication::_currentVersionDownloadFinished(QString /*remoteFile*/, QString localFile) { - Q_UNUSED(remoteFile); - #ifdef __mobile__ Q_UNUSED(localFile); #else @@ -822,9 +815,8 @@ void QGCApplication::_currentVersionDownloadFinished(QString remoteFile, QString #endif } -void QGCApplication::_currentVersionDownloadError(QString errorMsg) +void QGCApplication::_currentVersionDownloadError(QString /*errorMsg*/) { - Q_UNUSED(errorMsg); _currentVersionDownload->deleteLater(); } diff --git a/src/QmlControls/MAVLinkChart.qml b/src/QmlControls/MAVLinkChart.qml index 8868371ed1..6fd978790b 100644 --- a/src/QmlControls/MAVLinkChart.qml +++ b/src/QmlControls/MAVLinkChart.qml @@ -20,12 +20,14 @@ ChartView { margins.bottom: ScreenTools.defaultFontPixelHeight * 1.5 margins.top: chartHeader.height + (ScreenTools.defaultFontPixelHeight * 2) - property int maxSeriesCount: seriesColors.length - property var seriesColors: ["chartreuse", "chocolate", "yellowgreen", "thistle", "silver", "darkturquoise", "blue", "green"] - property alias max: axisY.max - property alias min: axisY.min + property var chartController: null + property int maxSeriesCount: seriesColors.length + property var seriesColors: ["chartreuse", "chocolate", "yellowgreen", "thistle", "silver", "darkturquoise", "blue", "green"] - function addDimension(field, left) { + function addDimension(field) { + if(!chartController) { + chartController = controller.createChart() + } console.log(field.name + ' AxisY: ' + axisY) console.log(chartView.count + ' ' + chartView.seriesColors[chartView.count]) var serie = createSeries(ChartView.SeriesTypeLine, field.label) @@ -34,88 +36,79 @@ ChartView { serie.useOpenGL = true serie.color = chartView.seriesColors[chartView.count] serie.width = 1 - controller.addSeries(field, serie, left) + chartController.addSeries(field, serie) } function delDimension(field) { - chartView.removeSeries(field.series) - controller.delSeries(field) - console.log('Remove: ' + chartView.count + ' ' + field.name) + if(chartController) { + chartView.removeSeries(field.series) + chartController.delSeries(field) + console.log('Remove: ' + chartView.count + ' ' + field.name) + if(chartView.count === 0) { + controller.deleteChart(chartController) + chartController = null + } + } } DateTimeAxis { - id: axisX - min: controller.rangeXMin - max: controller.rangeXMax - format: "mm:ss.zzz" - tickCount: 5 - gridVisible: true - labelsFont.family: "Fixed" - labelsFont.pixelSize: ScreenTools.smallFontPointSize + id: axisX + min: chartController ? chartController.rangeXMin : 0 + max: chartController ? chartController.rangeXMax : 0 + format: "mm:ss.zzz" + tickCount: 5 + gridVisible: true + labelsFont.family: "Fixed" + labelsFont.pixelSize: ScreenTools.smallFontPointSize } ValueAxis { - id: axisY - lineVisible: false - labelsFont.family: "Fixed" - labelsFont.pixelSize: ScreenTools.smallFontPointSize + id: axisY + min: chartController ? chartController.rangeYMin : 0 + max: chartController ? chartController.rangeYMax : 0 + lineVisible: false + labelsFont.family: "Fixed" + labelsFont.pixelSize: ScreenTools.smallFontPointSize } RowLayout { - id: chartHeader - anchors.left: parent.left - anchors.leftMargin: ScreenTools.defaultFontPixelWidth * 4 - anchors.right: parent.right - anchors.rightMargin: ScreenTools.defaultFontPixelWidth * 4 - anchors.top: parent.top - anchors.topMargin: ScreenTools.defaultFontPixelHeight * 1.5 - spacing: 0 - QGCLabel { - text: qsTr("Scale:"); - font.pixelSize: ScreenTools.smallFontPointSize - Layout.alignment: Qt.AlignVCenter - } - QGCComboBox { - id: timeScaleSelector - width: ScreenTools.defaultFontPixelWidth * 10 - height: ScreenTools.defaultFontPixelHeight - model: controller.timeScales - currentIndex: controller.timeScale - onActivated: controller.timeScale = index - font.pixelSize: ScreenTools.smallFontPointSize - Layout.alignment: Qt.AlignVCenter - } + id: chartHeader + anchors.left: parent.left + anchors.leftMargin: ScreenTools.defaultFontPixelWidth * 4 + anchors.right: parent.right + anchors.rightMargin: ScreenTools.defaultFontPixelWidth * 4 + anchors.top: parent.top + anchors.topMargin: ScreenTools.defaultFontPixelHeight * 1.5 GridLayout { - columns: 2 - columnSpacing: ScreenTools.defaultFontPixelWidth - rowSpacing: ScreenTools.defaultFontPixelHeight * 0.25 - Layout.alignment: Qt.AlignRight | Qt.AlignVCenter - Layout.fillWidth: true + columns: 2 + columnSpacing: ScreenTools.defaultFontPixelWidth + rowSpacing: ScreenTools.defaultFontPixelHeight * 0.25 + Layout.alignment: Qt.AlignVCenter QGCLabel { - text: qsTr("Range Left:"); + text: qsTr("Scale:"); font.pixelSize: ScreenTools.smallFontPointSize 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 + Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 10 + height: ScreenTools.defaultFontPixelHeight + model: controller.timeScales + currentIndex: chartController ? chartController.rangeXIndex : 0 + onActivated: { if(chartController) chartController.rangeXIndex = index; } font.pixelSize: ScreenTools.smallFontPointSize Layout.alignment: Qt.AlignVCenter } QGCLabel { - text: qsTr("Range Right:"); + text: qsTr("Range:"); font.pixelSize: ScreenTools.smallFontPointSize Layout.alignment: Qt.AlignVCenter } QGCComboBox { - Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 8 - height: ScreenTools.defaultFontPixelHeight * 1.5 + Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 10 + height: ScreenTools.defaultFontPixelHeight model: controller.rangeList - currentIndex: controller.rightRangeIdx - onActivated: controller.rightRangeIdx = index + currentIndex: chartController ? chartController.rangeYIndex : 0 + onActivated: { if(chartController) chartController.rangeYIndex = index; } font.pixelSize: ScreenTools.smallFontPointSize Layout.alignment: Qt.AlignVCenter } -- GitLab