diff --git a/src/AnalyzeView/MAVLinkInspectorController.cc b/src/AnalyzeView/MAVLinkInspectorController.cc index e1dd71f57e2b1bf4c0442485924c018deba91682..6ab01f1176b7462044bb55b942362900dc31d401 100644 --- a/src/AnalyzeView/MAVLinkInspectorController.cc +++ b/src/AnalyzeView/MAVLinkInspectorController.cc @@ -18,6 +18,14 @@ 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) @@ -26,6 +34,47 @@ 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() +{ + if(!_rangeList.count()) { + for(int i = 0; i < _rangeSt.count(); i++) { + _rangeList << _rangeSt[i]->label; + } + } + return _rangeList; +} + +//----------------------------------------------------------------------------- +void +QGCMAVLinkMessageField::setRange(quint32 r) +{ + 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(); + } + } } //----------------------------------------------------------------------------- @@ -88,20 +137,23 @@ QGCMAVLinkMessageField::updateValue(QString newValue, qreal v) _times[_dataIndex] = QGC::groundTimeMilliseconds(); _dataIndex++; } - qreal vmin = std::numeric_limits::max(); - qreal vmax = std::numeric_limits::min(); - for(int i = 0; i < _values.count(); i++) { - qreal v = _values[i]; - if(vmax < v) vmax = v; - if(vmin > v) vmin = v; - } - if(std::abs(_rangeMin - vmin) > 0.000001) { - _rangeMin = vmin; - emit rangeMinChanged(); - } - if(std::abs(_rangeMax - vmax) > 0.000001) { - _rangeMax = vmax; - emit rangeMaxChanged(); + //-- Auto Range + if(_rangeIndex == 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]; + if(vmax < v) vmax = v; + if(vmin > v) vmin = v; + } + if(std::abs(_rangeMin - vmin) > 0.000001) { + _rangeMin = vmin; + emit rangeMinChanged(); + } + if(std::abs(_rangeMax - vmax) > 0.000001) { + _rangeMax = vmax; + emit rangeMaxChanged(); + } } _msg->msgCtl()->updateXRange(); _updateSeries(); @@ -479,6 +531,14 @@ QGCMAVLinkVehicle::_checkCompID(QGCMAVLinkMessage* message) } } +//----------------------------------------------------------------------------- +MAVLinkInspectorController::TimeScale_st::TimeScale_st(QObject* parent, const QString& l, uint32_t t) + : QObject(parent) + , label(l) + , timeScale(t) +{ +} + //----------------------------------------------------------------------------- MAVLinkInspectorController::MAVLinkInspectorController() { @@ -493,10 +553,11 @@ MAVLinkInspectorController::MAVLinkInspectorController() connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &MAVLinkInspectorController::_setActiveVehicle); _rangeXMax = QDateTime::fromMSecsSinceEpoch(0); _rangeXMin = QDateTime::fromMSecsSinceEpoch(std::numeric_limits::max()); - _timeScales << tr("5 Sec"); - _timeScales << tr("10 Sec"); - _timeScales << tr("30 Sec"); - _timeScales << tr("60 Sec"); + _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(); } //----------------------------------------------------------------------------- @@ -506,6 +567,18 @@ MAVLinkInspectorController::~MAVLinkInspectorController() } +//---------------------------------------------------------------------------------------- +QStringList +MAVLinkInspectorController::timeScales() +{ + if(!_timeScales.count()) { + for(int i = 0; i < _timeScaleSt.count(); i++) { + _timeScales << _timeScaleSt[i]->label; + } + } + return _timeScales; +} + //---------------------------------------------------------------------------------------- void MAVLinkInspectorController::_setActiveVehicle(Vehicle* vehicle) @@ -673,15 +746,11 @@ MAVLinkInspectorController::setTimeScale(quint32 t) void MAVLinkInspectorController::updateXRange() { - int ts = 5 * 1000; - switch(_timeScale) { - case 1: ts = 10 * 1000; break; - case 2: ts = 30 * 1000; break; - case 3: ts = 60 * 1000; break; + 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(); } - qint64 t = static_cast(QGC::groundTimeMilliseconds()); - _rangeXMax = QDateTime::fromMSecsSinceEpoch(t); - _rangeXMin = QDateTime::fromMSecsSinceEpoch(t - ts); - emit rangeMinXChanged(); - emit rangeMaxXChanged(); } diff --git a/src/AnalyzeView/MAVLinkInspectorController.h b/src/AnalyzeView/MAVLinkInspectorController.h index 17c753b420032938206f92b236eae73c353bafb9..264cf303517d60b689d853590dd43cd9d9fe4a1c 100644 --- a/src/AnalyzeView/MAVLinkInspectorController.h +++ b/src/AnalyzeView/MAVLinkInspectorController.h @@ -32,10 +32,12 @@ class QGCMAVLinkMessageField : public QObject { 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) public: QGCMAVLinkMessageField(QGCMAVLinkMessage* parent, QString name, QString type); @@ -44,14 +46,17 @@ public: 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); signals: @@ -61,11 +66,21 @@ signals: void selectableChanged (); void selectedChanged (); void valueChanged (); + void rangeListChanged (); + void rangeChanged (); private: 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; @@ -75,9 +90,13 @@ private: 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; }; //----------------------------------------------------------------------------- @@ -174,8 +193,7 @@ public: 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 CONSTANT) + 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); @@ -184,7 +202,7 @@ public: QGCMAVLinkVehicle* activeVehicle () { return _activeVehicle; } QStringList vehicleNames () { return _vehicleNames; } quint32 timeScale () { return _timeScale; } - QStringList timeScales () { return _timeScales; } + QStringList timeScales (); QVariantList chartFields () { return _chartFields; } QDateTime rangeXMin () { return _rangeXMin; } QDateTime rangeXMax () { return _rangeXMax; } @@ -202,6 +220,7 @@ signals: void timeScaleChanged (); void rangeMinXChanged (); void rangeMaxXChanged (); + void timeScalesChanged (); private slots: void _receiveMessage (LinkInterface* link, mavlink_message_t message); @@ -211,11 +230,18 @@ private slots: void _refreshFrequency (); private: - void _reset (); - + void _reset (); QGCMAVLinkVehicle* _findVehicle (uint8_t id); private: + + class TimeScale_st : public QObject { + public: + TimeScale_st(QObject* parent, const QString& l, uint32_t t); + QString label; + uint32_t timeScale; + }; + int _selectedSystemID = 0; ///< Currently selected system int _selectedComponentID = 0; ///< Currently selected component QStringList _timeScales; @@ -227,4 +253,5 @@ private: QStringList _vehicleNames; QmlObjectListModel _vehicles; ///< List of QGCMAVLinkVehicle QVariantList _chartFields; + QList_timeScaleSt; }; diff --git a/src/AnalyzeView/MAVLinkInspectorPage.qml b/src/AnalyzeView/MAVLinkInspectorPage.qml index 73a437517389a8d50adb43d8e8009aecf3a74fee..a60e2c62dcfd08555f924c3a5d5eb698aed994c6 100644 --- a/src/AnalyzeView/MAVLinkInspectorPage.qml +++ b/src/AnalyzeView/MAVLinkInspectorPage.qml @@ -314,9 +314,9 @@ AnalyzePage { antialiasing: true visible: controller.chartFieldCount > 0 animationOptions: ChartView.NoAnimation - legend.font.pixelSize: ScreenTools.smallFontPointSize + legend.visible: false margins.bottom: ScreenTools.defaultFontPixelHeight * 1.5 - margins.top: ScreenTools.defaultFontPixelHeight * 1.5 + margins.top: chartHeader.height + (ScreenTools.defaultFontPixelHeight * 2) DateTimeAxis { id: axisX @@ -336,6 +336,7 @@ AnalyzePage { visible: controller.chartFieldCount > 0 lineVisible: false labelsFont.pixelSize: ScreenTools.smallFontPointSize + labelsColor: qgcPal.colorRed } ValueAxis { @@ -345,6 +346,7 @@ AnalyzePage { visible: controller.chartFieldCount > 1 lineVisible: false labelsFont.pixelSize: ScreenTools.smallFontPointSize + labelsColor: qgcPal.colorGreen } LineSeries { @@ -390,17 +392,72 @@ AnalyzePage { } } } - QGCComboBox { - id: timeScaleSelector + 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 - width: ScreenTools.defaultFontPixelWidth * 10 - height: ScreenTools.defaultFontPixelHeight * 1.5 - model: controller.timeScales - currentIndex: controller.timeScale - onActivated: controller.timeScale = index + 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 + } + GridLayout { + columns: 3 + 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 + } + } + 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 + } + } + 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 + } + } + } } } }