diff --git a/CMakeLists.txt b/CMakeLists.txt
index 915162a4ecaa..376d24164abd 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -168,7 +168,7 @@ find_package(Qt6
${QGC_QT_MINIMUM_VERSION}...${QGC_QT_MAXIMUM_VERSION}
REQUIRED
COMPONENTS
- Charts
+ Graphs
Concurrent
Core
Core5Compat
diff --git a/src/AnalyzeView/MAVLinkInspector/MAVLinkChart.qml b/src/AnalyzeView/MAVLinkInspector/MAVLinkChart.qml
index 01aa8f5411d0..6542216ecc3c 100644
--- a/src/AnalyzeView/MAVLinkInspector/MAVLinkChart.qml
+++ b/src/AnalyzeView/MAVLinkInspector/MAVLinkChart.qml
@@ -1,21 +1,17 @@
import QtQuick
import QtQuick.Controls
import QtQuick.Layouts
-import QtCharts
+import QtGraphs
import QGroundControl
import QGroundControl.Controls
-ChartView {
+GraphsView {
id: chartView
- theme: ChartView.ChartThemeDark
- antialiasing: true
- animationOptions: ChartView.NoAnimation
- legend.visible: false
- backgroundColor: qgcPal.window
- backgroundRoundness: 0
- margins.bottom: ScreenTools.defaultFontPixelHeight * 1.5
- margins.top: chartHeader.height + (ScreenTools.defaultFontPixelHeight * 2)
+ marginBottom: ScreenTools.defaultFontPixelHeight * 1.5
+ marginTop: chartHeader.height + (ScreenTools.defaultFontPixelHeight * 2)
+ marginLeft: 0
+ marginRight: 0
visible: chartController.chartFields.length > 0
required property var inspectorController
@@ -23,21 +19,29 @@ ChartView {
property var _seriesColors: ["#00E04B","#DE8500","#F32836","#BFBFBF","#536DFF","#EECC44"]
+ Component {
+ id: lineSeriesComponent
+ LineSeries { }
+ }
+
function addDimension(field) {
- var color = _seriesColors[chartView.count]
- var serie = createSeries(ChartView.SeriesTypeLine, field.label)
- serie.axisX = axisX
- serie.axisY = axisY
- serie.useOpenGL = QGroundControl.videoManager.gstreamerEnabled // Details on why here: https://github.com/mavlink/qgroundcontrol/issues/13068
- serie.color = color
- serie.width = 1
+ var color = _seriesColors[chartView.seriesList.length]
+ var serie = lineSeriesComponent.createObject(chartView, {color: color, width: 1})
+ chartView.addSeries(serie)
chartController.addSeries(field, serie)
}
function delDimension(field) {
if(chartController) {
- chartView.removeSeries(field.series)
- chartController.delSeries(field)
+ for (var i = 0; i < chartView.seriesList.length; i++) {
+ if (chartView.seriesList[i] === field.series) {
+ var s = chartView.seriesList[i]
+ chartView.removeSeries(i)
+ chartController.delSeries(field)
+ s.destroy()
+ break
+ }
+ }
}
}
@@ -45,43 +49,72 @@ ChartView {
return chartController.chartFields.length < _seriesColors.length
}
+ theme: GraphsTheme {
+ colorScheme: GraphsTheme.ColorScheme.Dark
+ backgroundColor: qgcPal.window
+ backgroundVisible: true
+ plotAreaBackgroundColor: qgcPal.window
+ grid.mainColor: Qt.rgba(qgcPal.text.r, qgcPal.text.g, qgcPal.text.b, 0.3)
+ grid.subColor: Qt.rgba(qgcPal.text.r, qgcPal.text.g, qgcPal.text.b, 0.15)
+ grid.mainWidth: 1
+ labelBackgroundVisible: false
+ labelTextColor: qgcPal.text
+ axisXLabelFont.family: ScreenTools.fixedFontFamily
+ axisXLabelFont.pointSize: ScreenTools.smallFontPointSize
+ axisYLabelFont.family: ScreenTools.fixedFontFamily
+ axisYLabelFont.pointSize: ScreenTools.smallFontPointSize
+ }
+
MAVLinkChartController {
id: chartController
inspectorController: chartView.inspectorController
chartIndex: chartView.chartIndex
}
- DateTimeAxis {
+ axisX: ValueAxis {
id: axisX
- min: chartController ? chartController.rangeXMin : new Date()
- max: chartController ? chartController.rangeXMax : new Date()
+ min: chartController ? chartController.rangeXMin : 0
+ max: chartController ? chartController.rangeXMax : 1
visible: chartController !== null
- format: "
mm:ss.zzz"
- tickCount: 5
- gridVisible: true
- labelsFont.family: ScreenTools.fixedFontFamily
- labelsFont.pointSize: ScreenTools.smallFontPointSize
- labelsColor: qgcPal.text
+ tickInterval: chartController ? chartController.rangeXMs / 3 : 5000
+ subTickCount: 0
+ labelsVisible: true
+ labelDelegate: Component {
+ Item {
+ property string text
+ implicitWidth: label.implicitWidth
+ implicitHeight: label.implicitHeight
+ Text {
+ id: label
+ text: {
+ var ms = parseFloat(parent.text)
+ if (isNaN(ms)) return parent.text
+ var d = new Date(ms)
+ return d.getMinutes().toString().padStart(2, '0') + ":" + d.getSeconds().toString().padStart(2, '0')
+ }
+ color: qgcPal.text
+ font.family: ScreenTools.fixedFontFamily
+ font.pointSize: ScreenTools.smallFontPointSize
+ }
+ }
+ }
}
- ValueAxis {
+ axisY: ValueAxis {
id: axisY
min: chartController ? chartController.rangeYMin : 0
max: chartController ? chartController.rangeYMax : 0
visible: chartController !== null
lineVisible: false
- labelsFont.family: ScreenTools.fixedFontFamily
- labelsFont.pointSize: ScreenTools.smallFontPointSize
- labelsColor: qgcPal.text
}
Row {
id: chartHeader
- anchors.left: parent.left
+ anchors.left: parent ? parent.left : undefined
anchors.leftMargin: ScreenTools.defaultFontPixelWidth * 4
- anchors.right: parent.right
+ anchors.right: parent ? parent.right : undefined
anchors.rightMargin: ScreenTools.defaultFontPixelWidth * 4
- anchors.top: parent.top
+ anchors.top: parent ? parent.top : undefined
anchors.topMargin: ScreenTools.defaultFontPixelHeight * 1.5
spacing: ScreenTools.defaultFontPixelWidth * 2
visible: chartController !== null
@@ -123,7 +156,7 @@ ChartView {
model: chartController ? chartController.chartFields : []
QGCLabel {
text: modelData.label
- color: chartView.series(index).color
+ color: index < chartView.seriesList.length ? chartView.seriesList[index].color : qgcPal.text
font.pointSize: ScreenTools.smallFontPointSize
}
}
diff --git a/src/AnalyzeView/MAVLinkInspector/MAVLinkChartController.cc b/src/AnalyzeView/MAVLinkInspector/MAVLinkChartController.cc
index cc35144283cf..8d3e4cbed1aa 100644
--- a/src/AnalyzeView/MAVLinkInspector/MAVLinkChartController.cc
+++ b/src/AnalyzeView/MAVLinkInspector/MAVLinkChartController.cc
@@ -4,11 +4,9 @@
#include "QGCApplication.h"
#include "QGCLoggingCategory.h"
-#include
+#include
#include
-Q_DECLARE_METATYPE(QAbstractSeries*)
-
QGC_LOGGING_CATEGORY(MAVLinkChartControllerLog, "AnalyzeView.MAVLinkChartController")
MAVLinkChartController::MAVLinkChartController(QObject *parent)
@@ -17,8 +15,6 @@ MAVLinkChartController::MAVLinkChartController(QObject *parent)
{
// qCDebug(MAVLinkChartControllerLog) << Q_FUNC_INFO << this;
- (void) qRegisterMetaType("QAbstractSeries*");
-
(void) connect(_updateSeriesTimer, &QTimer::timeout, this, &MAVLinkChartController::_refreshSeries);
}
@@ -61,6 +57,14 @@ void MAVLinkChartController::setRangeYIndex(quint32 index)
}
}
+qreal MAVLinkChartController::rangeXMs() const
+{
+ if (_rangeXIndex < static_cast(_inspectorController->timeScaleSt().count())) {
+ return static_cast(_inspectorController->timeScaleSt()[static_cast(_rangeXIndex)]->timeScale);
+ }
+ return 5000.0;
+}
+
void MAVLinkChartController::setRangeXIndex(quint32 index)
{
if (index == _rangeXIndex) {
@@ -80,10 +84,10 @@ void MAVLinkChartController::updateXRange()
}
const qint64 bootTime = static_cast(qgcApp()->msecsSinceBoot());
- _rangeXMax = QDateTime::fromMSecsSinceEpoch(bootTime);
+ _rangeXMax = static_cast(bootTime);
emit rangeXMaxChanged();
- _rangeXMin = QDateTime::fromMSecsSinceEpoch(bootTime - _inspectorController->timeScaleSt()[static_cast(_rangeXIndex)]->timeScale);
+ _rangeXMin = static_cast(bootTime - _inspectorController->timeScaleSt()[static_cast(_rangeXIndex)]->timeScale);
emit rangeXMinChanged();
}
diff --git a/src/AnalyzeView/MAVLinkInspector/MAVLinkChartController.h b/src/AnalyzeView/MAVLinkInspector/MAVLinkChartController.h
index 1ab9f6d71b3c..bd26c64af462 100644
--- a/src/AnalyzeView/MAVLinkInspector/MAVLinkChartController.h
+++ b/src/AnalyzeView/MAVLinkInspector/MAVLinkChartController.h
@@ -19,17 +19,18 @@ class MAVLinkChartController : public QObject
QML_ELEMENT
Q_MOC_INCLUDE("MAVLinkInspectorController.h")
Q_MOC_INCLUDE("MAVLinkMessageField.h")
- Q_MOC_INCLUDE("QtCharts/qabstractseries.h")
+ Q_MOC_INCLUDE("QtGraphs/qabstractseries.h")
Q_PROPERTY(MAVLinkInspectorController* inspectorController READ inspectorController WRITE setInspectorController REQUIRED)
Q_PROPERTY(int chartIndex MEMBER _chartIndex REQUIRED)
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 rangeXMin READ rangeXMin NOTIFY rangeXMinChanged)
+ Q_PROPERTY(qreal 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_PROPERTY(qreal rangeXMs READ rangeXMs NOTIFY rangeXIndexChanged)
public:
@@ -42,11 +43,12 @@ class MAVLinkChartController : public QObject
void setInspectorController(MAVLinkInspectorController *inspectorController);
MAVLinkInspectorController *inspectorController() const { return _inspectorController; }
QVariantList chartFields() const { return _chartFields; }
- QDateTime rangeXMin() const { return _rangeXMin; }
- QDateTime rangeXMax() const { return _rangeXMax; }
+ qreal rangeXMin() const { return _rangeXMin; }
+ qreal rangeXMax() const { return _rangeXMax; }
qreal rangeYMin() const { return _rangeYMin; }
qreal rangeYMax() const { return _rangeYMax; }
quint32 rangeXIndex() const { return _rangeXIndex; }
+ qreal rangeXMs() const;
quint32 rangeYIndex() const { return _rangeYIndex; }
int chartIndex() const { return _chartIndex; }
@@ -72,8 +74,8 @@ private slots:
MAVLinkInspectorController *_inspectorController = nullptr;
QTimer *_updateSeriesTimer = nullptr;
- QDateTime _rangeXMin;
- QDateTime _rangeXMax;
+ qreal _rangeXMin = 0;
+ qreal _rangeXMax = 0;
qreal _rangeYMin = 0;
qreal _rangeYMax = 1;
quint32 _rangeXIndex = 0; ///< 5 Seconds
diff --git a/src/AnalyzeView/MAVLinkInspector/MAVLinkInspectorPage.qml b/src/AnalyzeView/MAVLinkInspector/MAVLinkInspectorPage.qml
index d3ac13d9498a..21a3e2fc3106 100644
--- a/src/AnalyzeView/MAVLinkInspector/MAVLinkInspectorPage.qml
+++ b/src/AnalyzeView/MAVLinkInspector/MAVLinkInspectorPage.qml
@@ -3,7 +3,7 @@ import QtQuick.Controls
import QtQuick.Layouts
import QtQuick.Dialogs
import QtQuick.Window
-import QtCharts
+import QtGraphs
import QGroundControl
import QGroundControl.Controls
diff --git a/src/AnalyzeView/MAVLinkInspector/MAVLinkMessageField.cc b/src/AnalyzeView/MAVLinkInspector/MAVLinkMessageField.cc
index 06c1c161eab8..10ae96ddf4ea 100644
--- a/src/AnalyzeView/MAVLinkInspector/MAVLinkMessageField.cc
+++ b/src/AnalyzeView/MAVLinkInspector/MAVLinkMessageField.cc
@@ -4,8 +4,8 @@
#include "QGCApplication.h"
#include "QGCLoggingCategory.h"
-#include
-#include
+#include
+#include
QGC_LOGGING_CATEGORY(MAVLinkMessageFieldLog, "AnalyzeView.MAVLinkMessageField")
diff --git a/src/AnalyzeView/MAVLinkInspector/MAVLinkMessageField.h b/src/AnalyzeView/MAVLinkInspector/MAVLinkMessageField.h
index 321fbaa7760e..73a054037f32 100644
--- a/src/AnalyzeView/MAVLinkInspector/MAVLinkMessageField.h
+++ b/src/AnalyzeView/MAVLinkInspector/MAVLinkMessageField.h
@@ -16,7 +16,7 @@ class QGCMAVLinkMessageField : public QObject
{
Q_OBJECT
// QML_ELEMENT
- Q_MOC_INCLUDE()
+ Q_MOC_INCLUDE()
Q_PROPERTY(QString name READ name CONSTANT)
Q_PROPERTY(QString label READ label CONSTANT)
Q_PROPERTY(QString type READ type CONSTANT)
diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt
index 6a6bd52091de..5b3da6df06c8 100644
--- a/src/CMakeLists.txt
+++ b/src/CMakeLists.txt
@@ -90,7 +90,7 @@ target_include_directories(${CMAKE_PROJECT_NAME}
target_link_libraries(${CMAKE_PROJECT_NAME}
PRIVATE
# Qt6 Core
- Qt6::Charts
+ Qt6::Graphs
Qt6::Concurrent
Qt6::Core
Qt6::Core5Compat
@@ -102,7 +102,7 @@ target_link_libraries(${CMAKE_PROJECT_NAME}
Qt6::StateMachine
Qt6::Svg
Qt6::TextToSpeech
- Qt6::Widgets
+ Qt6::Widgets # Only for Platform.cc pre-startup error dialogs (QMessageBox)
Qt6::Xml
# Qt6 QML/Quick
diff --git a/src/PlanView/TerrainStatus.qml b/src/PlanView/TerrainStatus.qml
index 6dad91c345c2..ff01b99ac47c 100644
--- a/src/PlanView/TerrainStatus.qml
+++ b/src/PlanView/TerrainStatus.qml
@@ -1,5 +1,5 @@
import QtQuick
-import QtCharts
+import QtGraphs
import QGroundControl
import QGroundControl.Controls
@@ -50,49 +50,68 @@ Rectangle {
height: terrainProfileFlickable.height
width: terrainProfileFlickable.width
- ChartView {
+ GraphsView {
id: chart
anchors.fill: parent
- margins.top: 0
- margins.right: 0
- margins.bottom: 0
- margins.left: 0
- backgroundColor: "transparent"
- legend.visible: false
- antialiasing: true
-
- ValueAxis {
+ marginTop: 0
+ marginRight: ScreenTools.defaultFontPixelWidth * 2
+ marginBottom: 0
+ marginLeft: 0
+
+ theme: GraphsTheme {
+ colorScheme: GraphsTheme.ColorScheme.Light
+ backgroundColor: "transparent"
+ backgroundVisible: false
+ plotAreaBackgroundColor: qgcPal.window
+ grid.mainColor: applyOpacity(qgcPal.text, 0.5)
+ grid.subColor: applyOpacity(qgcPal.text, 0.3)
+ grid.mainWidth: 1
+ labelBackgroundVisible: false
+ labelTextColor: qgcPal.text
+ axisXLabelFont.family: ScreenTools.fixedFontFamily
+ axisXLabelFont.pointSize: ScreenTools.smallFontPointSize
+ axisYLabelFont.family: ScreenTools.fixedFontFamily
+ axisYLabelFont.pointSize: ScreenTools.smallFontPointSize
+ }
+
+ axisX: ValueAxis {
id: axisX
min: 0
- max: _unitsConversion.metersToAppSettingsHorizontalDistanceUnits(missionController.missionTotalDistance)
+ max: _unitsConversion.metersToAppSettingsHorizontalDistanceUnits(_missionTotalDistance)
lineVisible: true
- labelsFont.family: ScreenTools.fixedFontFamily
- labelsFont.pointSize: ScreenTools.smallFontPointSize
- labelsColor: qgcPal.text
- tickCount: 5
- gridLineColor: applyOpacity(qgcPal.text, 0.25)
+ tickInterval: max > 0 ? max / 4 : 1
}
- ValueAxis {
+ axisY: ValueAxis {
id: axisY
min: _unitsConversion.metersToAppSettingsVerticalDistanceUnits(_minAMSLAltitude)
max: _unitsConversion.metersToAppSettingsVerticalDistanceUnits(_maxAMSLAltitude)
lineVisible: true
- labelsFont.family: ScreenTools.fixedFontFamily
- labelsFont.pointSize: ScreenTools.smallFontPointSize
- labelsColor: qgcPal.text
- tickCount: 4
- gridLineColor: applyOpacity(qgcPal.text, 0.25)
+ tickInterval: (max - min) > 0 ? (max - min) / 3 : 1
}
LineSeries {
- id: lineSeries
- axisX: axisX
- axisY: axisY
- visible: true
+ id: terrainSeries
+ color: "green"
+ width: 2
+ }
- XYPoint { x: 0; y: _unitsConversion.metersToAppSettingsVerticalDistanceUnits(_minAMSLAltitude) }
- XYPoint { x: _unitsConversion.metersToAppSettingsHorizontalDistanceUnits(_missionTotalDistance); y: _unitsConversion.metersToAppSettingsVerticalDistanceUnits(_maxAMSLAltitude) }
+ LineSeries {
+ id: flightSeries
+ color: "orange"
+ width: 2
+ }
+
+ LineSeries {
+ id: missingSeries
+ color: "yellow"
+ width: 2
+ }
+
+ LineSeries {
+ id: collisionSeries
+ color: "red"
+ width: 3
}
}
@@ -103,6 +122,10 @@ Rectangle {
height: chart.plotArea.height
visibleWidth: chart.plotArea.width
missionController: root.missionController
+ horizontalScale: _unitsConversion.metersToAppSettingsHorizontalDistanceUnits(1)
+ verticalScale: _unitsConversion.metersToAppSettingsVerticalDistanceUnits(1)
+
+ onProfileChanged: terrainProfile.updateSeries(terrainSeries, flightSeries, missingSeries, collisionSeries)
Repeater {
model: missionController.visualItems
diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc
index ea389a17bc6a..0ccb8d2d1636 100644
--- a/src/QGCApplication.cc
+++ b/src/QGCApplication.cc
@@ -49,7 +49,7 @@
QGC_LOGGING_CATEGORY(QGCApplicationLog, "API.QGCApplication")
QGCApplication::QGCApplication(int &argc, char *argv[], const QGCCommandLineParser::CommandLineParseResult &cli)
- : QApplication(argc, argv)
+ : QGuiApplication(argc, argv)
, _runningUnitTests(cli.runningUnitTests)
, _simpleBootTest(cli.simpleBootTest)
, _fakeMobile(cli.fakeMobile)
@@ -635,12 +635,12 @@ QT_WARNING_DISABLE_DEPRECATED
bool QGCApplication::compressEvent(QEvent *event, QObject *receiver, QPostEventList *postedEvents)
{
if (event->type() != QEvent::MetaCall) {
- return QApplication::compressEvent(event, receiver, postedEvents);
+ return QGuiApplication::compressEvent(event, receiver, postedEvents);
}
const QMetaCallEvent *mce = static_cast(event);
if (!mce->sender() || !_compressedSignals.contains(mce->sender()->metaObject(), mce->signalId())) {
- return QApplication::compressEvent(event, receiver, postedEvents);
+ return QGuiApplication::compressEvent(event, receiver, postedEvents);
}
for (QPostEventList::iterator it = postedEvents->begin(); it != postedEvents->end(); ++it) {
@@ -676,7 +676,7 @@ bool QGCApplication::event(QEvent *e)
{
if (e->type() == QEvent::Quit) {
if (!_mainRootWindow) {
- return QApplication::event(e);
+ return QGuiApplication::event(e);
}
// On OSX if the user selects Quit from the menu (or Command-Q) the ApplicationWindow does not signal closing. Instead you get a Quit event here only.
// This in turn causes the standard QGC shutdown sequence to not run. So in this case we close the window ourselves such that the
@@ -694,7 +694,7 @@ bool QGCApplication::event(QEvent *e)
}
}
- return QApplication::event(e);
+ return QGuiApplication::event(e);
}
QGCImageProvider *QGCApplication::qgcImageProvider()
diff --git a/src/QGCApplication.h b/src/QGCApplication.h
index 35f7fb01bb27..1edcb707bc51 100644
--- a/src/QGCApplication.h
+++ b/src/QGCApplication.h
@@ -6,7 +6,7 @@
#include
#include
#include
-#include
+#include
namespace QGCCommandLineParser {
struct CommandLineParseResult;
@@ -24,7 +24,7 @@ struct QMetaObject;
#if defined(qApp)
#undef qApp
#endif
-#define qApp (static_cast(QApplication::instance()))
+#define qApp (static_cast(QGuiApplication::instance()))
#if defined(qGuiApp)
#undef qGuiApp
@@ -36,9 +36,7 @@ struct QMetaObject;
Q_DECLARE_LOGGING_CATEGORY(QGCApplicationLog)
/// The main application and management class.
-/// Needs QApplication base to support QtCharts module.
-/// TODO: Use QtGraphs to convert to QGuiApplication
-class QGCApplication : public QApplication
+class QGCApplication : public QGuiApplication
{
Q_OBJECT
diff --git a/src/QmlControls/PIDTuning.qml b/src/QmlControls/PIDTuning.qml
index bbb4091926bb..9d168a33915a 100644
--- a/src/QmlControls/PIDTuning.qml
+++ b/src/QmlControls/PIDTuning.qml
@@ -1,6 +1,6 @@
import QtQuick
import QtQuick.Controls
-import QtCharts
+import QtGraphs
import QtQuick.Layouts
import QGroundControl
@@ -31,6 +31,15 @@ RowLayout {
readonly property int _tickSeparation: 5
readonly property int _maxTickSections: 10
+ property string _chartTitle: ""
+ readonly property var _seriesColors: ["#21be2b", "#c62828", "#1565c0", "#f9a825", "#6a1b9a", "#00838f"]
+ property var _legendModel: []
+
+ Component {
+ id: lineSeriesComponent
+ LineSeries { }
+ }
+
function adjustYAxisMin(yAxis, newValue) {
var newMin = Math.min(yAxis.min, newValue)
if (newMin % 5 != 0) {
@@ -50,8 +59,8 @@ RowLayout {
}
function resetGraphs() {
- for (var i = 0; i < chart.count; ++i) {
- chart.series(i).removePoints(0, chart.series(i).count)
+ for (var i = 0; i < chart.seriesList.length; ++i) {
+ chart.seriesList[i].clear()
}
_xAxis.min = 0
_xAxis.max = 0
@@ -80,14 +89,23 @@ RowLayout {
}
function axisIndexChanged() {
- chart.removeAllSeries()
- axis[_currentAxis].plot.forEach(function(e) {
- chart.createSeries(ChartView.SeriesTypeLine, e.name, xAxis, yAxis);
+ while (chart.seriesList.length > 0) {
+ var s = chart.seriesList[0]
+ chart.removeSeries(0)
+ s.destroy()
+ }
+ var legendItems = []
+ axis[_currentAxis].plot.forEach(function(e, idx) {
+ var color = _seriesColors[idx % _seriesColors.length]
+ var series = lineSeriesComponent.createObject(chart, {name: e.name, color: color})
+ chart.addSeries(series)
+ legendItems.push({name: e.name, color: color})
})
+ _legendModel = legendItems
var chartTitle = axis[_currentAxis].plotTitle
if (chartTitle == null)
chartTitle = axis[_currentAxis].name
- chart.title = chartTitle + " " + title
+ _chartTitle = chartTitle + " " + title
saveTuningParamValues()
resetGraphs()
}
@@ -101,31 +119,6 @@ RowLayout {
Component.onDestruction: globals.activeVehicle.setPIDTuningTelemetryMode(Vehicle.ModeDisabled)
on_CurrentAxisChanged: axisIndexChanged()
- ValueAxis {
- id: xAxis
- min: 0
- max: 0
- labelFormat: "%.1f"
- titleText: ScreenTools.isShortScreen ? "" : qsTr("sec") // Save space on small screens
- tickCount: Math.min(Math.max(Math.floor(chart.width / (ScreenTools.defaultFontPixelWidth * 7)), 4), 11)
- labelsFont.pointSize: ScreenTools.defaultFontPointSize
- labelsFont.family: ScreenTools.normalFontFamily
- titleFont.pointSize: ScreenTools.defaultFontPointSize
- titleFont.family: ScreenTools.normalFontFamily
- }
-
- ValueAxis {
- id: yAxis
- min: 0
- max: 10
- titleText: unit
- tickCount: Math.min(((max - min) / _tickSeparation), _maxTickSections) + 1
- labelsFont.pointSize: ScreenTools.defaultFontPointSize
- labelsFont.family: ScreenTools.normalFontFamily
- titleFont.pointSize: ScreenTools.defaultFontPointSize
- titleFont.family: ScreenTools.normalFontFamily
- }
-
Timer {
id: dataTimer
interval: 10
@@ -142,7 +135,7 @@ RowLayout {
for (var i = 0; i < len; ++i) {
var value = axis[_currentAxis].plot[i].value
if (!isNaN(value)) {
- chart.series(i).append(_msecs/1000, value)
+ chart.seriesList[i].append(_msecs/1000, value)
if (firstPoint) {
_yAxis.min = value
_yAxis.max = value
@@ -152,8 +145,8 @@ RowLayout {
}
// limit history
var minSec = _msecs/1000 - 3*60
- while (chart.series(i).count > 0 && chart.series(i).at(0).x < minSec) {
- chart.series(i).remove(0)
+ while (chart.seriesList[i].count > 0 && chart.seriesList[i].at(0).x < minSec) {
+ chart.seriesList[i].remove(0)
}
}
}
@@ -173,21 +166,51 @@ RowLayout {
spacing: ScreenTools.defaultFontPixelHeight / 4
clip: true // chart has redraw problems
- ChartView {
+ QGCLabel {
+ id: chartTitleLabel
+ text: _chartTitle
+ font.pointSize: ScreenTools.defaultFontPointSize
+ font.family: ScreenTools.normalFontFamily
+ anchors.horizontalCenter: parent.horizontalCenter
+ }
+
+ GraphsView {
id: chart
width: Math.max(_minChartWidth, availableWidth - rightPanel.width - parent.spacing - _margins)
- height: Math.max(_minChartHeight, availableHeight - leftPanelBottomColumn.height - parent.spacing - _margins)
- antialiasing: true
- legend.alignment: Qt.AlignBottom
- legend.font.pointSize: ScreenTools.defaultFontPointSize
- legend.font.family: ScreenTools.normalFontFamily
- titleFont.pointSize: ScreenTools.defaultFontPointSize
- titleFont.family: ScreenTools.normalFontFamily
-
- property real _chartMargin: 0
+ height: Math.max(_minChartHeight, availableHeight - leftPanelBottomColumn.height - chartTitleLabel.height - legendRow.height - parent.spacing * 3 - _margins)
+
property real _minChartWidth: ScreenTools.defaultFontPixelWidth * 40
property real _minChartHeight: ScreenTools.defaultFontPixelHeight * 15
+ theme: GraphsTheme {
+ colorScheme: GraphsTheme.ColorScheme.Light
+ plotAreaBackgroundColor: "white"
+ grid.mainColor: "#cccccc"
+ grid.subColor: "#e0e0e0"
+ grid.mainWidth: 1
+ labelBackgroundVisible: false
+ }
+
+ axisX: ValueAxis {
+ id: xAxis
+ min: 0
+ max: 0
+ labelFormat: "%.1f"
+ titleText: ScreenTools.isShortScreen ? "" : qsTr("sec")
+ titleFont.pointSize: ScreenTools.defaultFontPointSize
+ titleFont.family: ScreenTools.normalFontFamily
+ }
+
+ axisY: ValueAxis {
+ id: yAxis
+ min: 0
+ max: 10
+ titleText: unit
+ tickInterval: _tickSeparation
+ titleFont.pointSize: ScreenTools.defaultFontPointSize
+ titleFont.family: ScreenTools.normalFontFamily
+ }
+
// enable mouse dragging
MouseArea {
property var _startPoint: undefined
@@ -195,9 +218,11 @@ RowLayout {
anchors.fill: parent
onPressed: (mouse) => {
_startPoint = Qt.point(mouse.x, mouse.y)
- var start = chart.mapToValue(_startPoint)
- var next = chart.mapToValue(Qt.point(mouse.x+1, mouse.y+1))
- _scaling = next.x - start.x
+ if (chart.seriesList.length > 0) {
+ var start = chart.seriesList[0].dataPointCoordinatesAt(_startPoint.x, _startPoint.y)
+ var next = chart.seriesList[0].dataPointCoordinatesAt(mouse.x+1, mouse.y+1)
+ _scaling = next.x - start.x
+ }
}
onWheel: (wheel) => {
if (wheel.angleDelta.y > 0)
@@ -223,6 +248,29 @@ RowLayout {
}
}
+ Row {
+ id: legendRow
+ spacing: ScreenTools.defaultFontPixelWidth
+ anchors.horizontalCenter: parent.horizontalCenter
+
+ Repeater {
+ model: _legendModel
+ Row {
+ spacing: ScreenTools.defaultFontPixelWidth / 2
+ Rectangle {
+ width: ScreenTools.defaultFontPixelHeight
+ height: ScreenTools.defaultFontPixelHeight / 3
+ color: modelData.color
+ anchors.verticalCenter: parent.verticalCenter
+ }
+ QGCLabel {
+ text: modelData.name
+ font.pointSize: ScreenTools.smallFontPointSize
+ }
+ }
+ }
+ }
+
Column {
id: leftPanelBottomColumn
spacing: ScreenTools.defaultFontPixelHeight / 4
diff --git a/src/QmlControls/TerrainProfile.cc b/src/QmlControls/TerrainProfile.cc
index fceebb25855b..e0befd417600 100644
--- a/src/QmlControls/TerrainProfile.cc
+++ b/src/QmlControls/TerrainProfile.cc
@@ -6,20 +6,15 @@
#include "QGCLoggingCategory.h"
#include "QGCApplication.h"
-#include
-
QGC_LOGGING_CATEGORY(TerrainProfileLog, "Terrain.TerrainProfile")
TerrainProfile::TerrainProfile(QQuickItem* parent)
: QQuickItem(parent)
{
- setFlag(QQuickItem::ItemHasContents, true);
-
- connect(this, &QQuickItem::heightChanged, this, &QQuickItem::update);
- connect(this, &TerrainProfile::visibleWidthChanged, this, &QQuickItem::update);
+ connect(this, &QQuickItem::heightChanged, this, &TerrainProfile::_updateProfile);
+ connect(this, &TerrainProfile::visibleWidthChanged, this, &TerrainProfile::_updateProfile);
- // This collapse multiple _updateSignals in a row to a single update
- connect(this, &TerrainProfile::_updateSignal, this, &QQuickItem::update, Qt::QueuedConnection);
+ connect(this, &TerrainProfile::_updateSignal, this, &TerrainProfile::_updateProfile, Qt::QueuedConnection);
qgcApp()->addCompressedSignal(QMetaMethod::fromSignal(&TerrainProfile::_updateSignal));
}
@@ -37,9 +32,10 @@ void TerrainProfile::setMissionController(MissionController* missionController)
emit missionControllerChanged();
connect(_missionController, &MissionController::visualItemsChanged, this, &TerrainProfile::_newVisualItems);
-
connect(this, &TerrainProfile::visibleWidthChanged, this, &TerrainProfile::_updateSignal, Qt::QueuedConnection);
connect(_missionController, &MissionController::recalcTerrainProfile, this, &TerrainProfile::_updateSignal, Qt::QueuedConnection);
+
+ emit _updateSignal();
}
}
@@ -49,28 +45,10 @@ void TerrainProfile::_newVisualItems(void)
emit _updateSignal();
}
-void TerrainProfile::_createGeometry(QSGGeometryNode*& geometryNode, QSGGeometry*& geometry, QSGGeometry::DrawingMode drawingMode, const QColor& color)
-{
- QSGFlatColorMaterial* terrainMaterial = new QSGFlatColorMaterial;
- terrainMaterial->setColor(color);
-
- geometry = new QSGGeometry(QSGGeometry::defaultAttributes_Point2D(), 0);
- geometry->setDrawingMode(drawingMode);
- geometry->setLineWidth(2);
-
- geometryNode = new QSGGeometryNode;
- geometryNode->setFlag(QSGNode::OwnsGeometry);
- geometryNode->setFlag(QSGNode::OwnsMaterial);
- geometryNode->setFlag(QSGNode::OwnedByParent);
- geometryNode->setMaterial(terrainMaterial);
- geometryNode->setGeometry(geometry);
-}
-
void TerrainProfile::_updateSegmentCounts(FlightPathSegment* segment, int& cFlightProfileSegments, int& cTerrainProfilePoints, int& cMissingTerrainSegments, int& cTerrainCollisionSegments, double& minTerrainHeight, double& maxTerrainHeight)
{
if (_shouldAddFlightProfileSegment(segment)) {
if (segment->segmentType() == FlightPathSegment::SegmentTypeTerrainFrame) {
- // We show a full above terrain profile for flight segment
cFlightProfileSegments += segment->amslTerrainHeights().count() - 1;
} else {
cFlightProfileSegments++;
@@ -91,135 +69,18 @@ void TerrainProfile::_updateSegmentCounts(FlightPathSegment* segment, int& cFlig
}
}
-void TerrainProfile::_addTerrainProfileSegment(FlightPathSegment* segment, double currentDistance, double amslAltRange, QSGGeometry::Point2D* terrainVertices, int& terrainProfileVertexIndex)
-{
- double terrainDistance = 0;
- for (int heightIndex=0; heightIndexamslTerrainHeights().count(); heightIndex++) {
- // Move along the x axis which is distance
- if (heightIndex == 0) {
- // The first point in the segment is at the position of the last point. So nothing to do here.
- } else if (heightIndex == segment->amslTerrainHeights().count() - 2) {
- // The distance between the last two heights differs with each terrain query
- terrainDistance += segment->finalDistanceBetween();
- } else {
- // The distance between all terrain heights except for the last is the same
- terrainDistance += segment->distanceBetween();
- }
-
- // Move along the y axis which is a view or terrain height as a percentage between the min/max AMSL altitude for all segments
- double amslTerrainHeight = segment->amslTerrainHeights()[heightIndex].value();
- double terrainHeightPercent = (amslTerrainHeight - _minAMSLAlt) / amslAltRange;
-
- float x = (currentDistance + terrainDistance) * _pixelsPerMeter;
- float y = height() - (terrainHeightPercent * height());
- terrainVertices[terrainProfileVertexIndex++].set(x, y);
- }
-}
-
-void TerrainProfile::_addMissingTerrainSegment(FlightPathSegment* segment, double currentDistance, QSGGeometry::Point2D* missingTerrainVertices, int& missingterrainProfileVertexIndex)
-{
- if (_shouldAddMissingTerrainSegment(segment)) {
- float x = currentDistance * _pixelsPerMeter;
- float y = height();
- missingTerrainVertices[missingterrainProfileVertexIndex++].set(x, y);
- missingTerrainVertices[missingterrainProfileVertexIndex++].set(x + (segment->totalDistance() * _pixelsPerMeter), y);
- }
-}
-
-void TerrainProfile::_addTerrainCollisionSegment(FlightPathSegment* segment, double currentDistance, double amslAltRange, QSGGeometry::Point2D* terrainCollisionVertices, int& terrainCollisionVertexIndex)
+void TerrainProfile::_updateProfile(void)
{
- if (segment->terrainCollision()) {
- double amslCoord1Height = segment->coord1AMSLAlt();
- double amslCoord2Height = segment->coord2AMSLAlt();
- double coord1HeightPercent = (amslCoord1Height - _minAMSLAlt) / amslAltRange;
- double coord2HeightPercent = (amslCoord2Height - _minAMSLAlt) / amslAltRange;
-
- float x = currentDistance * _pixelsPerMeter;
- float y = height() - (coord1HeightPercent * height());
-
- terrainCollisionVertices[terrainCollisionVertexIndex++].set(x, y);
-
- x += segment->totalDistance() * _pixelsPerMeter;
- y = height() - (coord2HeightPercent * height());
-
- terrainCollisionVertices[terrainCollisionVertexIndex++].set(x, y);
- }
-}
-
-void TerrainProfile::_addFlightProfileSegment(FlightPathSegment* segment, double currentDistance, double amslAltRange, QSGGeometry::Point2D* flightProfileVertices, int& flightProfileVertexIndex)
-{
- if (!_shouldAddFlightProfileSegment(segment)) {
+ if (!_missionController || !_visualItems) {
return;
}
- if (segment->segmentType() == FlightPathSegment::SegmentTypeTerrainFrame) {
- double terrainDistance = 0;
- double distanceToSurface = segment->coord1AMSLAlt() - segment->amslTerrainHeights().first().value();
- for (int heightIndex=0; heightIndexamslTerrainHeights().count(); heightIndex++) {
- // Move along the x axis which is distance
- if (heightIndex == 0) {
- // The first point in the segment is at the position of the last point. So nothing to do here.
- } else if (heightIndex == segment->amslTerrainHeights().count() - 2) {
- // The distance between the last two heights differs with each terrain query
- terrainDistance += segment->finalDistanceBetween();
- } else {
- // The distance between all terrain heights except for the last is the same
- terrainDistance += segment->distanceBetween();
- }
-
- if (heightIndex > 1) {
- // Add first coord of segment
- auto previousVertex = flightProfileVertices[flightProfileVertexIndex-1];
- flightProfileVertices[flightProfileVertexIndex++].set(previousVertex.x, previousVertex.y);
- }
-
- // Add second coord of segment (or very first one)
- double amslTerrainHeight = segment->amslTerrainHeights()[heightIndex].value() + distanceToSurface;
- double terrainHeightPercent = (amslTerrainHeight - _minAMSLAlt) / amslAltRange;
-
- float x = (currentDistance + terrainDistance) * _pixelsPerMeter;
- float y = height() - (terrainHeightPercent * height());
- flightProfileVertices[flightProfileVertexIndex++].set(x, y);
-
- }
- } else {
- double amslCoord1Height = segment->coord1AMSLAlt();
- double amslCoord2Height = segment->coord2AMSLAlt();
- double coord1HeightPercent = (amslCoord1Height - _minAMSLAlt) / amslAltRange;
- double coord2HeightPercent = (amslCoord2Height - _minAMSLAlt) / amslAltRange;
-
- float x = currentDistance * _pixelsPerMeter;
- float y = height() - (coord1HeightPercent * height());
-
- flightProfileVertices[flightProfileVertexIndex++].set(x, y);
-
- x += segment->totalDistance() * _pixelsPerMeter;
- y = height() - (coord2HeightPercent * height());
-
- flightProfileVertices[flightProfileVertexIndex++].set(x, y);
- }
-}
-
-QSGNode* TerrainProfile::updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePaintNodeData* /*updatePaintNodeData*/)
-{
- QSGNode* rootNode = static_cast(oldNode);
- QSGGeometry* terrainProfileGeometry = nullptr;
- QSGGeometry* missingTerrainGeometry = nullptr;
- QSGGeometry* flightProfileGeometry = nullptr;
- QSGGeometry* terrainCollisionGeometry = nullptr;
- int cTerrainProfilePoints = 0;
- int cMissingTerrainSegments = 0;
- int cFlightProfileSegments = 0;
- int cTerrainCollisionSegments = 0;
- double minTerrainHeight = qQNaN();
- double maxTerrainHeight = qQNaN();
-
- // First we need to determine:
- // - how many terrain profile vertices we need
- // - how many missing terrain segments there are
- // - how many flight profile segments we need
- // - how many terrain collision segments there are
- // - what is the total distance so we can calculate pixels per meter
+ int cTerrainProfilePoints = 0;
+ int cMissingTerrainSegments = 0;
+ int cFlightProfileSegments = 0;
+ int cTerrainCollisionSegments = 0;
+ double minTerrainHeight = qQNaN();
+ double maxTerrainHeight = qQNaN();
for (int viIndex=0; viIndex<_visualItems->count(); viIndex++) {
VisualMissionItem* visualItem = _visualItems->value(viIndex);
@@ -238,11 +99,9 @@ QSGNode* TerrainProfile::updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePai
}
}
- // The profile view min/max is setup to include a full terrain profile as well as the flight path segments.
_minAMSLAlt = std::fmin(_missionController->minAMSLAltitude(), minTerrainHeight);
_maxAMSLAlt = std::fmax(_missionController->maxAMSLAltitude(), maxTerrainHeight);
- // We add a buffer to the min/max alts such that the visuals don't draw lines right at the edges of the display
double amslAltRange = _maxAMSLAlt - _minAMSLAlt;
double amslAltRangeBuffer = amslAltRange * 0.1;
_maxAMSLAlt += amslAltRangeBuffer;
@@ -250,68 +109,39 @@ QSGNode* TerrainProfile::updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePai
_minAMSLAlt -= amslAltRangeBuffer;
_minAMSLAlt = std::fmax(_minAMSLAlt, 0.0);
}
- amslAltRange = _maxAMSLAlt - _minAMSLAlt;
+
+ const double missionTotalDistance = _missionController->missionTotalDistance();
+ _pixelsPerMeter = (missionTotalDistance > 0.0) ? (_visibleWidth / missionTotalDistance) : 0.0;
static int counter = 0;
qCDebug(TerrainProfileLog) << "missionController min/max" << _missionController->minAMSLAltitude() << _missionController->maxAMSLAltitude();
- qCDebug(TerrainProfileLog) << QStringLiteral("updatePaintNode counter:%1 cFlightProfileSegments:%2 cTerrainProfilePoints:%3 cMissingTerrainSegments:%4 cTerrainCollisionSegments:%5 _minAMSLAlt:%6 _maxAMSLAlt:%7 maxTerrainHeight:%8")
+ qCDebug(TerrainProfileLog) << QStringLiteral("updateProfile counter:%1 cFlightProfileSegments:%2 cTerrainProfilePoints:%3 cMissingTerrainSegments:%4 cTerrainCollisionSegments:%5 _minAMSLAlt:%6 _maxAMSLAlt:%7 maxTerrainHeight:%8")
.arg(counter++).arg(cFlightProfileSegments).arg(cTerrainProfilePoints).arg(cMissingTerrainSegments).arg(cTerrainCollisionSegments).arg(_minAMSLAlt).arg(_maxAMSLAlt).arg(maxTerrainHeight);
- _pixelsPerMeter = _visibleWidth / _missionController->missionTotalDistance();
+ setImplicitWidth(_visibleWidth);
+ setWidth(implicitWidth());
- // Instantiate nodes
- if (!rootNode) {
- rootNode = new QSGNode;
+ emit implicitWidthChanged();
+ emit widthChanged();
+ emit pixelsPerMeterChanged();
+ emit minAMSLAltChanged();
+ emit maxAMSLAltChanged();
+ emit profileChanged();
+}
- QSGGeometryNode* terrainProfileNode = nullptr;
- QSGGeometryNode* missingTerrainNode = nullptr;
- QSGGeometryNode* flightProfileNode = nullptr;
- QSGGeometryNode* terrainCollisionNode = nullptr;
+void TerrainProfile::updateSeries(QXYSeries* terrainSeries, QXYSeries* flightSeries, QXYSeries* missingSeries, QXYSeries* collisionSeries)
+{
+ if (!_missionController || !_visualItems) {
+ return;
+ }
- _createGeometry(terrainProfileNode, terrainProfileGeometry, QSGGeometry::DrawLineStrip, "green");
- _createGeometry(missingTerrainNode, missingTerrainGeometry, QSGGeometry::DrawLines, "yellow");
- _createGeometry(flightProfileNode, flightProfileGeometry, QSGGeometry::DrawLines, "orange");
- _createGeometry(terrainCollisionNode, terrainCollisionGeometry, QSGGeometry::DrawLines, "red");
+ QList terrainPoints;
+ QList flightPoints;
+ QList missingPoints;
+ QList collisionPoints;
- rootNode->appendChildNode(terrainProfileNode);
- rootNode->appendChildNode(missingTerrainNode);
- rootNode->appendChildNode(flightProfileNode);
- rootNode->appendChildNode(terrainCollisionNode);
- }
+ double currentDistance = 0;
- // Allocate space for the vertices
-
- QSGNode* node = rootNode->childAtIndex(0);
- terrainProfileGeometry = static_cast(node)->geometry();
- terrainProfileGeometry->allocate(cTerrainProfilePoints);
- node->markDirty(QSGNode::DirtyGeometry);
-
- node = rootNode->childAtIndex(1);
- missingTerrainGeometry = static_cast(node)->geometry();
- missingTerrainGeometry->allocate(cMissingTerrainSegments * 2);
- node->markDirty(QSGNode::DirtyGeometry);
-
- node = rootNode->childAtIndex(2);
- flightProfileGeometry = static_cast(node)->geometry();
- flightProfileGeometry->allocate(cFlightProfileSegments * 2);
- node->markDirty(QSGNode::DirtyGeometry);
-
- node = rootNode->childAtIndex(3);
- terrainCollisionGeometry = static_cast(node)->geometry();
- terrainCollisionGeometry->allocate(cTerrainCollisionSegments * 2);
- node->markDirty(QSGNode::DirtyGeometry);
-
- int flightProfileVertexIndex = 0;
- int terrainProfileVertexIndex = 0;
- int missingterrainProfileVertexIndex = 0;
- int terrainCollisionVertexIndex = 0;
- double currentDistance = 0;
- QSGGeometry::Point2D* flightProfileVertices = flightProfileGeometry->vertexDataAsPoint2D();
- QSGGeometry::Point2D* terrainProfileVertices = terrainProfileGeometry->vertexDataAsPoint2D();
- QSGGeometry::Point2D* missingTerrainVertices = missingTerrainGeometry->vertexDataAsPoint2D();
- QSGGeometry::Point2D* terrainCollisionVertices = terrainCollisionGeometry->vertexDataAsPoint2D();
-
- // This step places the vertices for display into the nodes
for (int viIndex=0; viIndex<_visualItems->count(); viIndex++) {
VisualMissionItem* visualItem = _visualItems->value(viIndex);
ComplexMissionItem* complexItem = _visualItems->value(viIndex);
@@ -323,10 +153,10 @@ QSGNode* TerrainProfile::updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePai
for (int segmentIndex=0; segmentIndexflightPathSegments()->count(); segmentIndex++) {
FlightPathSegment* segment = complexItem->flightPathSegments()->value(segmentIndex);
- _addFlightProfileSegment (segment, currentDistance, amslAltRange, flightProfileVertices, flightProfileVertexIndex);
- _addTerrainProfileSegment (segment, currentDistance, amslAltRange, terrainProfileVertices, terrainProfileVertexIndex);
- _addMissingTerrainSegment (segment, currentDistance, missingTerrainVertices, missingterrainProfileVertexIndex);
- _addTerrainCollisionSegment (segment, currentDistance, amslAltRange, terrainCollisionVertices, terrainCollisionVertexIndex);
+ _addTerrainPoints (segment, currentDistance, terrainPoints);
+ _addFlightPoints (segment, currentDistance, flightPoints);
+ _addMissingPoints (segment, currentDistance, missingPoints);
+ _addCollisionPoints (segment, currentDistance, collisionPoints);
currentDistance += segment->totalDistance();
}
@@ -336,25 +166,104 @@ QSGNode* TerrainProfile::updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePai
if (visualItem->simpleFlightPathSegment()) {
FlightPathSegment* segment = visualItem->simpleFlightPathSegment();
- _addFlightProfileSegment (segment, currentDistance, amslAltRange, flightProfileVertices, flightProfileVertexIndex);
- _addTerrainProfileSegment (segment, currentDistance, amslAltRange, terrainProfileVertices, terrainProfileVertexIndex);
- _addMissingTerrainSegment (segment, currentDistance, missingTerrainVertices, missingterrainProfileVertexIndex);
- _addTerrainCollisionSegment (segment, currentDistance, amslAltRange, terrainCollisionVertices, terrainCollisionVertexIndex);
+ _addTerrainPoints (segment, currentDistance, terrainPoints);
+ _addFlightPoints (segment, currentDistance, flightPoints);
+ _addMissingPoints (segment, currentDistance, missingPoints);
+ _addCollisionPoints (segment, currentDistance, collisionPoints);
currentDistance += segment->totalDistance();
}
}
- setImplicitWidth(_visibleWidth/*(_totalDistance * pixelsPerMeter) + (_horizontalMargin * 2)*/);
- setWidth(implicitWidth());
+ if (terrainSeries) {
+ terrainSeries->replace(terrainPoints);
+ }
+ if (flightSeries) {
+ flightSeries->replace(flightPoints);
+ }
+ if (missingSeries) {
+ missingSeries->replace(missingPoints);
+ }
+ if (collisionSeries) {
+ collisionSeries->replace(collisionPoints);
+ }
- emit implicitWidthChanged();
- emit widthChanged();
- emit pixelsPerMeterChanged();
- emit minAMSLAltChanged();
- emit maxAMSLAltChanged();
+ qCDebug(TerrainProfileLog) << QStringLiteral("updateSeries terrain:%1 flight:%2 missing:%3 collision:%4")
+ .arg(terrainPoints.count()).arg(flightPoints.count()).arg(missingPoints.count()).arg(collisionPoints.count());
+}
+
+void TerrainProfile::_addTerrainPoints(FlightPathSegment* segment, double currentDistance, QList& points)
+{
+ if (_shouldAddMissingTerrainSegment(segment)) {
+ return;
+ }
+
+ double terrainDistance = 0;
+ for (int heightIndex=0; heightIndexamslTerrainHeights().count(); heightIndex++) {
+ if (heightIndex == 0) {
+ // First point at start of segment
+ } else if (heightIndex == segment->amslTerrainHeights().count() - 2) {
+ terrainDistance += segment->finalDistanceBetween();
+ } else {
+ terrainDistance += segment->distanceBetween();
+ }
+
+ const double amslTerrainHeight = segment->amslTerrainHeights()[heightIndex].value() * _verticalScale;
+ points.append(QPointF((currentDistance + terrainDistance) * _horizontalScale, amslTerrainHeight));
+ }
+}
- return rootNode;
+void TerrainProfile::_addFlightPoints(FlightPathSegment* segment, double currentDistance, QList& points)
+{
+ if (!_shouldAddFlightProfileSegment(segment)) {
+ if (!points.isEmpty()) {
+ points.append(QPointF(currentDistance * _horizontalScale, qQNaN()));
+ }
+ return;
+ }
+
+ if (segment->segmentType() == FlightPathSegment::SegmentTypeTerrainFrame) {
+ double terrainDistance = 0;
+ double distanceToSurface = segment->coord1AMSLAlt() - segment->amslTerrainHeights().first().value();
+ for (int heightIndex=0; heightIndexamslTerrainHeights().count(); heightIndex++) {
+ if (heightIndex == 0) {
+ // First point
+ } else if (heightIndex == segment->amslTerrainHeights().count() - 2) {
+ terrainDistance += segment->finalDistanceBetween();
+ } else {
+ terrainDistance += segment->distanceBetween();
+ }
+
+ const double amslTerrainHeight = (segment->amslTerrainHeights()[heightIndex].value() + distanceToSurface) * _verticalScale;
+ points.append(QPointF((currentDistance + terrainDistance) * _horizontalScale, amslTerrainHeight));
+ }
+ } else {
+ points.append(QPointF(currentDistance * _horizontalScale, segment->coord1AMSLAlt() * _verticalScale));
+ points.append(QPointF((currentDistance + segment->totalDistance()) * _horizontalScale, segment->coord2AMSLAlt() * _verticalScale));
+ }
+}
+
+void TerrainProfile::_addMissingPoints(FlightPathSegment* segment, double currentDistance, QList& points)
+{
+ if (_shouldAddMissingTerrainSegment(segment)) {
+ if (!points.isEmpty()) {
+ points.append(QPointF(currentDistance * _horizontalScale, qQNaN()));
+ }
+ const double minAlt = _minAMSLAlt * _verticalScale;
+ points.append(QPointF(currentDistance * _horizontalScale, minAlt));
+ points.append(QPointF((currentDistance + segment->totalDistance()) * _horizontalScale, minAlt));
+ }
+}
+
+void TerrainProfile::_addCollisionPoints(FlightPathSegment* segment, double currentDistance, QList& points)
+{
+ if (segment->terrainCollision()) {
+ if (!points.isEmpty()) {
+ points.append(QPointF(currentDistance * _horizontalScale, qQNaN()));
+ }
+ points.append(QPointF(currentDistance * _horizontalScale, segment->coord1AMSLAlt() * _verticalScale));
+ points.append(QPointF((currentDistance + segment->totalDistance()) * _horizontalScale, segment->coord2AMSLAlt() * _verticalScale));
+ }
}
bool TerrainProfile::_shouldAddFlightProfileSegment(FlightPathSegment* segment)
diff --git a/src/QmlControls/TerrainProfile.h b/src/QmlControls/TerrainProfile.h
index 7c6ddf57125f..2418cf2ef509 100644
--- a/src/QmlControls/TerrainProfile.h
+++ b/src/QmlControls/TerrainProfile.h
@@ -2,9 +2,8 @@
#include
#include
-#include
-#include
#include
+#include
Q_DECLARE_LOGGING_CATEGORY(TerrainProfileLog)
@@ -27,13 +26,16 @@ class TerrainProfile : public QQuickItem
Q_PROPERTY(double pixelsPerMeter MEMBER _pixelsPerMeter NOTIFY pixelsPerMeterChanged)
Q_PROPERTY(double minAMSLAlt MEMBER _minAMSLAlt NOTIFY minAMSLAltChanged)
Q_PROPERTY(double maxAMSLAlt MEMBER _maxAMSLAlt NOTIFY maxAMSLAltChanged)
+ Q_PROPERTY(double horizontalScale MEMBER _horizontalScale)
+ Q_PROPERTY(double verticalScale MEMBER _verticalScale)
MissionController* missionController(void) { return _missionController; }
void setMissionController(MissionController* missionController);
- // Overrides from QQuickItem
- QSGNode* updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePaintNodeData* updatePaintNodeData);
+ /// Populates the given series with terrain/flight profile data.
+ /// Call this from QML when profileChanged is emitted.
+ Q_INVOKABLE void updateSeries(QXYSeries* terrainSeries, QXYSeries* flightSeries, QXYSeries* missingSeries, QXYSeries* collisionSeries);
// Override from QQmlParserStatus
void componentComplete(void) final;
@@ -44,18 +46,19 @@ class TerrainProfile : public QQuickItem
void pixelsPerMeterChanged (void);
void minAMSLAltChanged (void);
void maxAMSLAltChanged (void);
+ void profileChanged (void);
void _updateSignal (void);
private slots:
void _newVisualItems (void);
+ void _updateProfile (void);
private:
- void _createGeometry (QSGGeometryNode*& geometryNode, QSGGeometry*& geometry, QSGGeometry::DrawingMode drawingMode, const QColor& color);
void _updateSegmentCounts (FlightPathSegment* segment, int& cFlightProfileSegments, int& cTerrainPoints, int& cMissingTerrainSegments, int& cTerrainCollisionSegments, double& minTerrainHeight, double& maxTerrainHeight);
- void _addTerrainProfileSegment (FlightPathSegment* segment, double currentDistance, double amslAltRange, QSGGeometry::Point2D* terrainProfileVertices, int& terrainVertexIndex);
- void _addMissingTerrainSegment (FlightPathSegment* segment, double currentDistance, QSGGeometry::Point2D* missingTerrainVertices, int& missingTerrainVertexIndex);
- void _addTerrainCollisionSegment (FlightPathSegment* segment, double currentDistance, double amslAltRange, QSGGeometry::Point2D* terrainCollisionVertices, int& terrainCollisionVertexIndex);
- void _addFlightProfileSegment (FlightPathSegment* segment, double currentDistance, double amslAltRange, QSGGeometry::Point2D* flightProfileVertices, int& flightProfileVertexIndex);
+ void _addTerrainPoints (FlightPathSegment* segment, double currentDistance, QList& points);
+ void _addFlightPoints (FlightPathSegment* segment, double currentDistance, QList& points);
+ void _addMissingPoints (FlightPathSegment* segment, double currentDistance, QList& points);
+ void _addCollisionPoints (FlightPathSegment* segment, double currentDistance, QList& points);
bool _shouldAddFlightProfileSegment (FlightPathSegment* segment);
bool _shouldAddMissingTerrainSegment (FlightPathSegment* segment);
@@ -65,10 +68,8 @@ private slots:
double _pixelsPerMeter = 0;
double _minAMSLAlt = 0;
double _maxAMSLAlt = 0;
-
- static const int _lineWidth = 7;
+ double _horizontalScale = 1;
+ double _verticalScale = 1;
Q_DISABLE_COPY(TerrainProfile)
};
-
-QML_DECLARE_TYPE(TerrainProfile)