Unverified Commit 992e6e57 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #8844 from DonLakeFlyer/TerrainProfileCrash

Fix Terrain profile crash
parents 37d3db3d fdb53cb4
...@@ -27,23 +27,24 @@ Rectangle { ...@@ -27,23 +27,24 @@ Rectangle {
property real _margin: ScreenTools.defaultFontPixelWidth / 2 property real _margin: ScreenTools.defaultFontPixelWidth / 2
property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 10.5 property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 10.5
property var _vehicle: QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.offlineEditingVehicle property var _vehicle: QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.offlineEditingVehicle
property real _cameraMinTriggerInterval: missionItem.cameraCalc.minTriggerInterval.rawValue property real _cameraMinTriggerInterval: _missionItem.cameraCalc.minTriggerInterval.rawValue
property bool _polygonDone: false property bool _polygonDone: false
property string _doneAdjusting: qsTr("Done") property string _doneAdjusting: qsTr("Done")
property bool _presetsAvailable: missionItem.presetNames.length !== 0 property var _missionItem: missionItem
property bool _presetsAvailable: _missionItem.presetNames.length !== 0
function polygonCaptureStarted() { function polygonCaptureStarted() {
missionItem.clearPolygon() _missionItem.clearPolygon()
} }
function polygonCaptureFinished(coordinates) { function polygonCaptureFinished(coordinates) {
for (var i=0; i<coordinates.length; i++) { for (var i=0; i<coordinates.length; i++) {
missionItem.addPolygonCoordinate(coordinates[i]) _missionItem.addPolygonCoordinate(coordinates[i])
} }
} }
function polygonAdjustVertex(vertexIndex, vertexCoordinate) { function polygonAdjustVertex(vertexIndex, vertexCoordinate) {
missionItem.adjustPolygonCoordinate(vertexIndex, vertexCoordinate) _missionItem.adjustPolygonCoordinate(vertexIndex, vertexCoordinate)
} }
function polygonAdjustStarted() { } function polygonAdjustStarted() { }
...@@ -63,7 +64,7 @@ Rectangle { ...@@ -63,7 +64,7 @@ Rectangle {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: _margin spacing: _margin
visible: !missionItem.surveyAreaPolygon.isValid || missionItem.wizardMode visible: !_missionItem.surveyAreaPolygon.isValid || _missionItem.wizardMode
ColumnLayout { ColumnLayout {
Layout.fillWidth: true Layout.fillWidth: true
...@@ -104,16 +105,16 @@ Rectangle { ...@@ -104,16 +105,16 @@ Rectangle {
text: qsTr("WARNING: Photo interval is below minimum interval (%1 secs) supported by camera.").arg(_cameraMinTriggerInterval.toFixed(1)) text: qsTr("WARNING: Photo interval is below minimum interval (%1 secs) supported by camera.").arg(_cameraMinTriggerInterval.toFixed(1))
wrapMode: Text.WordWrap wrapMode: Text.WordWrap
color: qgcPal.warningText color: qgcPal.warningText
visible: missionItem.cameraShots > 0 && _cameraMinTriggerInterval !== 0 && _cameraMinTriggerInterval > missionItem.timeBetweenShots visible: _missionItem.cameraShots > 0 && _cameraMinTriggerInterval !== 0 && _cameraMinTriggerInterval > _missionItem.timeBetweenShots
} }
CameraCalcGrid { CameraCalcGrid {
cameraCalc: missionItem.cameraCalc cameraCalc: _missionItem.cameraCalc
vehicleFlightIsFrontal: true vehicleFlightIsFrontal: true
distanceToSurfaceLabel: qsTr("Altitude") distanceToSurfaceLabel: qsTr("Altitude")
distanceToSurfaceAltitudeMode: missionItem.followTerrain ? distanceToSurfaceAltitudeMode: _missionItem.followTerrain ?
QGroundControl.AltitudeModeAboveTerrain : QGroundControl.AltitudeModeAboveTerrain :
(missionItem.cameraCalc.distanceToSurfaceRelative ? QGroundControl.AltitudeModeRelative : QGroundControl.AltitudeModeAbsolute) (_missionItem.cameraCalc.distanceToSurfaceRelative ? QGroundControl.AltitudeModeRelative : QGroundControl.AltitudeModeAbsolute)
frontalDistanceLabel: qsTr("Trigger Dist") frontalDistanceLabel: qsTr("Trigger Dist")
sideDistanceLabel: qsTr("Spacing") sideDistanceLabel: qsTr("Spacing")
} }
...@@ -135,9 +136,9 @@ Rectangle { ...@@ -135,9 +136,9 @@ Rectangle {
QGCLabel { text: qsTr("Angle") } QGCLabel { text: qsTr("Angle") }
FactTextField { FactTextField {
fact: missionItem.gridAngle fact: _missionItem.gridAngle
Layout.fillWidth: true Layout.fillWidth: true
onUpdated: angleSlider.value = missionItem.gridAngle.value onUpdated: angleSlider.value = _missionItem.gridAngle.value
} }
QGCSlider { QGCSlider {
...@@ -149,8 +150,8 @@ Rectangle { ...@@ -149,8 +150,8 @@ Rectangle {
Layout.fillWidth: true Layout.fillWidth: true
Layout.columnSpan: 2 Layout.columnSpan: 2
Layout.preferredHeight: ScreenTools.defaultFontPixelHeight * 1.5 Layout.preferredHeight: ScreenTools.defaultFontPixelHeight * 1.5
onValueChanged: missionItem.gridAngle.value = value onValueChanged: _missionItem.gridAngle.value = value
Component.onCompleted: value = missionItem.gridAngle.value Component.onCompleted: value = _missionItem.gridAngle.value
updateValueWhileDragging: true updateValueWhileDragging: true
} }
...@@ -158,14 +159,14 @@ Rectangle { ...@@ -158,14 +159,14 @@ Rectangle {
text: qsTr("Turnaround dist") text: qsTr("Turnaround dist")
} }
FactTextField { FactTextField {
fact: missionItem.turnAroundDistance fact: _missionItem.turnAroundDistance
Layout.fillWidth: true Layout.fillWidth: true
} }
} }
QGCButton { QGCButton {
text: qsTr("Rotate Entry Point") text: qsTr("Rotate Entry Point")
onClicked: missionItem.rotateEntryPoint(); onClicked: _missionItem.rotateEntryPoint();
} }
ColumnLayout { ColumnLayout {
...@@ -180,40 +181,40 @@ Rectangle { ...@@ -180,40 +181,40 @@ Rectangle {
model: [ model: [
{ {
text: qsTr("Hover and capture image"), text: qsTr("Hover and capture image"),
fact: missionItem.hoverAndCapture, fact: _missionItem.hoverAndCapture,
enabled: !missionItem.followTerrain, enabled: !_missionItem.followTerrain,
visible: missionItem.hoverAndCaptureAllowed visible: _missionItem.hoverAndCaptureAllowed
}, },
{ {
text: qsTr("Refly at 90 deg offset"), text: qsTr("Refly at 90 deg offset"),
fact: missionItem.refly90Degrees, fact: _missionItem.refly90Degrees,
enabled: !missionItem.followTerrain, enabled: !_missionItem.followTerrain,
visible: true visible: true
}, },
{ {
text: qsTr("Images in turnarounds"), text: qsTr("Images in turnarounds"),
fact: missionItem.cameraTriggerInTurnAround, fact: _missionItem.cameraTriggerInTurnAround,
enabled: missionItem.hoverAndCaptureAllowed ? !missionItem.hoverAndCapture.rawValue : true, enabled: _missionItem.hoverAndCaptureAllowed ? !_missionItem.hoverAndCapture.rawValue : true,
visible: true visible: true
}, },
{ {
text: qsTr("Fly alternate transects"), text: qsTr("Fly alternate transects"),
fact: missionItem.flyAlternateTransects, fact: _missionItem.flyAlternateTransects,
enabled: true, enabled: true,
visible: _vehicle ? (_vehicle.fixedWing || _vehicle.vtol) : false visible: _vehicle ? (_vehicle.fixedWing || _vehicle.vtol) : false
}, },
{ {
text: qsTr("Relative altitude"), text: qsTr("Relative altitude"),
enabled: missionItem.cameraCalc.isManualCamera && !missionItem.followTerrain, enabled: _missionItem.cameraCalc.isManualCamera && !_missionItem.followTerrain,
visible: QGroundControl.corePlugin.options.showMissionAbsoluteAltitude || (!missionItem.cameraCalc.distanceToSurfaceRelative && !missionItem.followTerrain), visible: QGroundControl.corePlugin.options.showMissionAbsoluteAltitude || (!_missionItem.cameraCalc.distanceToSurfaceRelative && !_missionItem.followTerrain),
checked: missionItem.cameraCalc.distanceToSurfaceRelative checked: _missionItem.cameraCalc.distanceToSurfaceRelative
} }
] ]
onItemClicked: { onItemClicked: {
if (index == 4) { if (index == 4) {
missionItem.cameraCalc.distanceToSurfaceRelative = !missionItem.cameraCalc.distanceToSurfaceRelative _missionItem.cameraCalc.distanceToSurfaceRelative = !_missionItem.cameraCalc.distanceToSurfaceRelative
console.log(missionItem.cameraCalc.distanceToSurfaceRelative) console.log(_missionItem.cameraCalc.distanceToSurfaceRelative)
} }
} }
} }
...@@ -241,7 +242,7 @@ Rectangle { ...@@ -241,7 +242,7 @@ Rectangle {
visible: tabBar.currentIndex === 1 visible: tabBar.currentIndex === 1
CameraCalcCamera { CameraCalcCamera {
cameraCalc: missionItem.cameraCalc cameraCalc: _missionItem.cameraCalc
} }
} // Camera Column } // Camera Column
...@@ -251,6 +252,7 @@ Rectangle { ...@@ -251,6 +252,7 @@ Rectangle {
anchors.right: parent.right anchors.right: parent.right
spacing: _margin spacing: _margin
visible: tabBar.currentIndex === 2 visible: tabBar.currentIndex === 2
missionItem: _missionItem
} }
// Presets Tab // Presets Tab
...@@ -269,7 +271,7 @@ Rectangle { ...@@ -269,7 +271,7 @@ Rectangle {
QGCComboBox { QGCComboBox {
id: presetCombo id: presetCombo
Layout.fillWidth: true Layout.fillWidth: true
model: missionItem.presetNames model: _missionItem.presetNames
} }
RowLayout { RowLayout {
...@@ -278,14 +280,14 @@ Rectangle { ...@@ -278,14 +280,14 @@ Rectangle {
QGCButton { QGCButton {
Layout.fillWidth: true Layout.fillWidth: true
text: qsTr("Apply Preset") text: qsTr("Apply Preset")
enabled: missionItem.presetNames.length != 0 enabled: _missionItem.presetNames.length != 0
onClicked: missionItem.loadPreset(presetCombo.textAt(presetCombo.currentIndex)) onClicked: _missionItem.loadPreset(presetCombo.textAt(presetCombo.currentIndex))
} }
QGCButton { QGCButton {
Layout.fillWidth: true Layout.fillWidth: true
text: qsTr("Delete Preset") text: qsTr("Delete Preset")
enabled: missionItem.presetNames.length != 0 enabled: _missionItem.presetNames.length != 0
onClicked: mainWindow.showComponentDialog(deletePresetMessage, qsTr("Delete Preset"), mainWindow.showDialogDefaultWidth, StandardButton.Yes | StandardButton.No) onClicked: mainWindow.showComponentDialog(deletePresetMessage, qsTr("Delete Preset"), mainWindow.showDialogDefaultWidth, StandardButton.Yes | StandardButton.No)
Component { Component {
...@@ -294,7 +296,7 @@ Rectangle { ...@@ -294,7 +296,7 @@ Rectangle {
message: qsTr("Are you sure you want to delete '%1' preset?").arg(presetName) message: qsTr("Are you sure you want to delete '%1' preset?").arg(presetName)
property string presetName: presetCombo.textAt(presetCombo.currentIndex) property string presetName: presetCombo.textAt(presetCombo.currentIndex)
function accept() { function accept() {
missionItem.deletePreset(presetName) _missionItem.deletePreset(presetName)
hideDialog() hideDialog()
} }
} }
...@@ -326,9 +328,9 @@ Rectangle { ...@@ -326,9 +328,9 @@ Rectangle {
QGCLabel { text: qsTr("Angle") } QGCLabel { text: qsTr("Angle") }
FactTextField { FactTextField {
fact: missionItem.gridAngle fact: _missionItem.gridAngle
Layout.fillWidth: true Layout.fillWidth: true
onUpdated: presetsAngleSlider.value = missionItem.gridAngle.value onUpdated: presetsAngleSlider.value = _missionItem.gridAngle.value
} }
QGCSlider { QGCSlider {
...@@ -340,8 +342,8 @@ Rectangle { ...@@ -340,8 +342,8 @@ Rectangle {
Layout.fillWidth: true Layout.fillWidth: true
Layout.columnSpan: 2 Layout.columnSpan: 2
Layout.preferredHeight: ScreenTools.defaultFontPixelHeight * 1.5 Layout.preferredHeight: ScreenTools.defaultFontPixelHeight * 1.5
onValueChanged: missionItem.gridAngle.value = value onValueChanged: _missionItem.gridAngle.value = value
Component.onCompleted: value = missionItem.gridAngle.value Component.onCompleted: value = _missionItem.gridAngle.value
updateValueWhileDragging: true updateValueWhileDragging: true
} }
...@@ -349,7 +351,7 @@ Rectangle { ...@@ -349,7 +351,7 @@ Rectangle {
Layout.columnSpan: 2 Layout.columnSpan: 2
Layout.fillWidth: true Layout.fillWidth: true
text: qsTr("Rotate Entry Point") text: qsTr("Rotate Entry Point")
onClicked: missionItem.rotateEntryPoint(); onClicked: _missionItem.rotateEntryPoint();
} }
} }
...@@ -372,7 +374,7 @@ Rectangle { ...@@ -372,7 +374,7 @@ Rectangle {
QGCViewDialog { QGCViewDialog {
function accept() { function accept() {
if (presetNameField.text != "") { if (presetNameField.text != "") {
missionItem.savePreset(presetNameField.text) _missionItem.savePreset(presetNameField.text)
hideDialog() hideDialog()
} }
} }
...@@ -407,9 +409,9 @@ Rectangle { ...@@ -407,9 +409,9 @@ Rectangle {
selectExisting: true selectExisting: true
onAcceptedForLoad: { onAcceptedForLoad: {
missionItem.surveyAreaPolygon.loadKMLOrSHPFile(file) _missionItem.surveyAreaPolygon.loadKMLOrSHPFile(file)
missionItem.resetState = false _missionItem.resetState = false
//editorMap.mapFitFunctions.fitMapViewportToMissionItems() //editorMap.mapFitFunctions.fitMapViewportTo_missionItems()
close() close()
} }
} }
......
...@@ -57,12 +57,12 @@ void TerrainProfile::_newVisualItems(void) ...@@ -57,12 +57,12 @@ void TerrainProfile::_newVisualItems(void)
emit _updateSignal(); emit _updateSignal();
} }
void TerrainProfile::_createGeometry(QSGGeometryNode*& geometryNode, QSGGeometry*& geometry, int vertices, QSGGeometry::DrawingMode drawingMode, const QColor& color) void TerrainProfile::_createGeometry(QSGGeometryNode*& geometryNode, QSGGeometry*& geometry, QSGGeometry::DrawingMode drawingMode, const QColor& color)
{ {
QSGFlatColorMaterial* terrainMaterial = new QSGFlatColorMaterial; QSGFlatColorMaterial* terrainMaterial = new QSGFlatColorMaterial;
terrainMaterial->setColor(color); terrainMaterial->setColor(color);
geometry = new QSGGeometry(QSGGeometry::defaultAttributes_Point2D(), vertices); geometry = new QSGGeometry(QSGGeometry::defaultAttributes_Point2D(), 0);
geometry->setDrawingMode(drawingMode); geometry->setDrawingMode(drawingMode);
geometry->setLineWidth(2); geometry->setLineWidth(2);
...@@ -74,12 +74,16 @@ void TerrainProfile::_createGeometry(QSGGeometryNode*& geometryNode, QSGGeometry ...@@ -74,12 +74,16 @@ void TerrainProfile::_createGeometry(QSGGeometryNode*& geometryNode, QSGGeometry
geometryNode->setGeometry(geometry); geometryNode->setGeometry(geometry);
} }
void TerrainProfile::_updateSegmentCounts(FlightPathSegment* segment, int& cTerrainPoints, int& cMissingTerrainSegments, int& cTerrainCollisionSegments, double& maxTerrainHeight) void TerrainProfile::_updateSegmentCounts(FlightPathSegment* segment, int& cFlightProfileSegments, int& cTerrainProfilePoints, int& cMissingTerrainSegments, int& cTerrainCollisionSegments, double& maxTerrainHeight)
{ {
if (segment->amslTerrainHeights().count() == 0 || qIsNaN(segment->coord1AMSLAlt()) || qIsNaN(segment->coord2AMSLAlt())) { if (_shouldAddFlightProfileSegment(segment)) {
cFlightProfileSegments++;
}
if (_shouldAddMissingTerrainSegment(segment)) {
cMissingTerrainSegments += 1; cMissingTerrainSegments += 1;
} else { } else {
cTerrainPoints += segment->amslTerrainHeights().count(); cTerrainProfilePoints += segment->amslTerrainHeights().count();
for (int i=0; i<segment->amslTerrainHeights().count(); i++) { for (int i=0; i<segment->amslTerrainHeights().count(); i++) {
maxTerrainHeight = qMax(maxTerrainHeight, segment->amslTerrainHeights()[i].value<double>()); maxTerrainHeight = qMax(maxTerrainHeight, segment->amslTerrainHeights()[i].value<double>());
} }
...@@ -89,7 +93,7 @@ void TerrainProfile::_updateSegmentCounts(FlightPathSegment* segment, int& cTerr ...@@ -89,7 +93,7 @@ void TerrainProfile::_updateSegmentCounts(FlightPathSegment* segment, int& cTerr
} }
} }
void TerrainProfile::_addTerrainProfileSegment(FlightPathSegment* segment, double currentDistance, double amslAltRange, QSGGeometry::Point2D* terrainVertices, int& terrainVertexIndex) void TerrainProfile::_addTerrainProfileSegment(FlightPathSegment* segment, double currentDistance, double amslAltRange, QSGGeometry::Point2D* terrainVertices, int& terrainProfileVertexIndex)
{ {
double terrainDistance = 0; double terrainDistance = 0;
for (int heightIndex=0; heightIndex<segment->amslTerrainHeights().count(); heightIndex++) { for (int heightIndex=0; heightIndex<segment->amslTerrainHeights().count(); heightIndex++) {
...@@ -110,17 +114,17 @@ void TerrainProfile::_addTerrainProfileSegment(FlightPathSegment* segment, doubl ...@@ -110,17 +114,17 @@ void TerrainProfile::_addTerrainProfileSegment(FlightPathSegment* segment, doubl
float x = (currentDistance + terrainDistance) * _pixelsPerMeter; float x = (currentDistance + terrainDistance) * _pixelsPerMeter;
float y = _availableHeight() - (terrainHeightPercent * _availableHeight()); float y = _availableHeight() - (terrainHeightPercent * _availableHeight());
_setVertex(terrainVertices[terrainVertexIndex++], x, y); _setVertex(terrainVertices[terrainProfileVertexIndex++], x, y);
} }
} }
void TerrainProfile::_addMissingTerrainSegment(FlightPathSegment* segment, double currentDistance, QSGGeometry::Point2D* missingTerrainVertices, int& missingTerrainVertexIndex) void TerrainProfile::_addMissingTerrainSegment(FlightPathSegment* segment, double currentDistance, QSGGeometry::Point2D* missingTerrainVertices, int& missingterrainProfileVertexIndex)
{ {
if (segment->amslTerrainHeights().count() == 0) { if (_shouldAddMissingTerrainSegment(segment)) {
float x = currentDistance * _pixelsPerMeter; float x = currentDistance * _pixelsPerMeter;
float y = _availableHeight(); float y = _availableHeight();
_setVertex(missingTerrainVertices[missingTerrainVertexIndex++], x, y); _setVertex(missingTerrainVertices[missingterrainProfileVertexIndex++], x, y);
_setVertex(missingTerrainVertices[missingTerrainVertexIndex++], x + (segment->totalDistance() * _pixelsPerMeter), y); _setVertex(missingTerrainVertices[missingterrainProfileVertexIndex++], x + (segment->totalDistance() * _pixelsPerMeter), y);
} }
} }
...@@ -146,15 +150,15 @@ void TerrainProfile::_addTerrainCollisionSegment(FlightPathSegment* segment, dou ...@@ -146,15 +150,15 @@ void TerrainProfile::_addTerrainCollisionSegment(FlightPathSegment* segment, dou
void TerrainProfile::_addFlightProfileSegment(FlightPathSegment* segment, double currentDistance, double amslAltRange, QSGGeometry::Point2D* flightProfileVertices, int& flightProfileVertexIndex) void TerrainProfile::_addFlightProfileSegment(FlightPathSegment* segment, double currentDistance, double amslAltRange, QSGGeometry::Point2D* flightProfileVertices, int& flightProfileVertexIndex)
{ {
if (!_shouldAddFlightProfileSegment(segment)) {
return;
}
double amslCoord1Height = segment->coord1AMSLAlt(); double amslCoord1Height = segment->coord1AMSLAlt();
double amslCoord2Height = segment->coord2AMSLAlt(); double amslCoord2Height = segment->coord2AMSLAlt();
double coord1HeightPercent = qMax(((amslCoord1Height - _missionController->minAMSLAltitude()) / amslAltRange), 0.0); double coord1HeightPercent = qMax(((amslCoord1Height - _missionController->minAMSLAltitude()) / amslAltRange), 0.0);
double coord2HeightPercent = qMax(((amslCoord2Height - _missionController->minAMSLAltitude()) / amslAltRange), 0.0); double coord2HeightPercent = qMax(((amslCoord2Height - _missionController->minAMSLAltitude()) / amslAltRange), 0.0);
if (qIsNaN(amslCoord1Height) || qIsNaN(amslCoord2Height)) {
return;
}
float x = currentDistance * _pixelsPerMeter; float x = currentDistance * _pixelsPerMeter;
float y = _availableHeight() - (coord1HeightPercent * _availableHeight()); float y = _availableHeight() - (coord1HeightPercent * _availableHeight());
...@@ -173,16 +177,16 @@ QSGNode* TerrainProfile::updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePai ...@@ -173,16 +177,16 @@ QSGNode* TerrainProfile::updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePai
QSGGeometry* missingTerrainGeometry = nullptr; QSGGeometry* missingTerrainGeometry = nullptr;
QSGGeometry* flightProfileGeometry = nullptr; QSGGeometry* flightProfileGeometry = nullptr;
QSGGeometry* terrainCollisionGeometry = nullptr; QSGGeometry* terrainCollisionGeometry = nullptr;
int cTerrainPoints = 0; int cTerrainProfilePoints = 0;
int cMissingTerrainSegments = 0; int cMissingTerrainSegments = 0;
int cFlightPathSegments = 0; int cFlightProfileSegments = 0;
int cTerrainCollisionSegments = 0; int cTerrainCollisionSegments = 0;
double maxTerrainHeight = 0; double maxTerrainHeight = 0;
// First we need to determine: // First we need to determine:
// - how many terrain vertices we need // - how many terrain profile vertices we need
// - how many missing terrain segments there are // - how many missing terrain segments there are
// - how many flight path segments we need // - how many flight profile segments we need
// - how many terrain collision segments there are // - how many terrain collision segments there are
// - what is the total distance so we can calculate pixels per meter // - what is the total distance so we can calculate pixels per meter
...@@ -191,16 +195,14 @@ QSGNode* TerrainProfile::updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePai ...@@ -191,16 +195,14 @@ QSGNode* TerrainProfile::updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePai
ComplexMissionItem* complexItem = _visualItems->value<ComplexMissionItem*>(viIndex); ComplexMissionItem* complexItem = _visualItems->value<ComplexMissionItem*>(viIndex);
if (visualItem->simpleFlightPathSegment()) { if (visualItem->simpleFlightPathSegment()) {
cFlightPathSegments++;
FlightPathSegment* segment = visualItem->simpleFlightPathSegment(); FlightPathSegment* segment = visualItem->simpleFlightPathSegment();
_updateSegmentCounts(segment, cTerrainPoints, cMissingTerrainSegments, cTerrainCollisionSegments, maxTerrainHeight); _updateSegmentCounts(segment, cFlightProfileSegments, cTerrainProfilePoints, cMissingTerrainSegments, cTerrainCollisionSegments, maxTerrainHeight);
} }
if (complexItem) { if (complexItem) {
for (int segmentIndex=0; segmentIndex<complexItem->flightPathSegments()->count(); segmentIndex++) { for (int segmentIndex=0; segmentIndex<complexItem->flightPathSegments()->count(); segmentIndex++) {
cFlightPathSegments++;
FlightPathSegment* segment = complexItem->flightPathSegments()->value<FlightPathSegment*>(segmentIndex); FlightPathSegment* segment = complexItem->flightPathSegments()->value<FlightPathSegment*>(segmentIndex);
_updateSegmentCounts(segment, cTerrainPoints, cMissingTerrainSegments, cTerrainCollisionSegments, maxTerrainHeight); _updateSegmentCounts(segment, cFlightProfileSegments, cTerrainProfilePoints, cMissingTerrainSegments, cTerrainCollisionSegments, maxTerrainHeight);
} }
} }
} }
...@@ -209,12 +211,12 @@ QSGNode* TerrainProfile::updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePai ...@@ -209,12 +211,12 @@ QSGNode* TerrainProfile::updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePai
#if 0 #if 0
static int counter = 0; static int counter = 0;
qDebug() << "updatePaintNode" << counter++ << cFlightPathSegments << cTerrainPoints << cMissingTerrainSegments << cTerrainCollisionSegments; qDebug() << "updatePaintNode" << counter++ << cFlightProfileSegments << cTerrainProfilePoints << cMissingTerrainSegments << cTerrainCollisionSegments;
#endif #endif
_pixelsPerMeter = (_visibleWidth - (_horizontalMargin * 2)) / _missionController->missionDistance(); _pixelsPerMeter = (_visibleWidth - (_horizontalMargin * 2)) / _missionController->missionDistance();
// Instantiate nodes
if (!rootNode) { if (!rootNode) {
rootNode = new QSGNode; rootNode = new QSGNode;
...@@ -223,47 +225,50 @@ QSGNode* TerrainProfile::updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePai ...@@ -223,47 +225,50 @@ QSGNode* TerrainProfile::updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePai
QSGGeometryNode* flightProfileNode = nullptr; QSGGeometryNode* flightProfileNode = nullptr;
QSGGeometryNode* terrainCollisionNode = nullptr; QSGGeometryNode* terrainCollisionNode = nullptr;
_createGeometry(terrainProfileNode, terrainProfileGeometry, cTerrainPoints, QSGGeometry::DrawLineStrip, "green"); _createGeometry(terrainProfileNode, terrainProfileGeometry, QSGGeometry::DrawLineStrip, "green");
_createGeometry(missingTerrainNode, missingTerrainGeometry, cMissingTerrainSegments * 2, QSGGeometry::DrawLines, "yellow"); _createGeometry(missingTerrainNode, missingTerrainGeometry, QSGGeometry::DrawLines, "yellow");
_createGeometry(flightProfileNode, flightProfileGeometry, cFlightPathSegments * 2, QSGGeometry::DrawLines, "orange"); _createGeometry(flightProfileNode, flightProfileGeometry, QSGGeometry::DrawLines, "orange");
_createGeometry(terrainCollisionNode, terrainCollisionGeometry, cTerrainCollisionSegments * 2, QSGGeometry::DrawLines, "red"); _createGeometry(terrainCollisionNode, terrainCollisionGeometry, QSGGeometry::DrawLines, "red");
rootNode->appendChildNode(terrainProfileNode); rootNode->appendChildNode(terrainProfileNode);
rootNode->appendChildNode(missingTerrainNode); rootNode->appendChildNode(missingTerrainNode);
rootNode->appendChildNode(flightProfileNode); rootNode->appendChildNode(flightProfileNode);
rootNode->appendChildNode(terrainCollisionNode); rootNode->appendChildNode(terrainCollisionNode);
} else {
QSGNode* node = rootNode->childAtIndex(0);
terrainProfileGeometry = static_cast<QSGGeometryNode*>(node)->geometry();
terrainProfileGeometry->allocate(cTerrainPoints);
node->markDirty(QSGNode::DirtyGeometry);
node = rootNode->childAtIndex(1);
missingTerrainGeometry = static_cast<QSGGeometryNode*>(node)->geometry();
missingTerrainGeometry->allocate(cMissingTerrainSegments * 2);
node->markDirty(QSGNode::DirtyGeometry);
node = rootNode->childAtIndex(2);
flightProfileGeometry = static_cast<QSGGeometryNode*>(node)->geometry();
flightProfileGeometry->allocate(cFlightPathSegments * 2);
node->markDirty(QSGNode::DirtyGeometry);
node = rootNode->childAtIndex(3);
terrainCollisionGeometry = static_cast<QSGGeometryNode*>(node)->geometry();
terrainCollisionGeometry->allocate(cTerrainCollisionSegments * 2);
node->markDirty(QSGNode::DirtyGeometry);
} }
int flightProfileVertexIndex = 0; // Allocate space for the vertices
int terrainVertexIndex = 0;
int missingTerrainVertexIndex = 0; QSGNode* node = rootNode->childAtIndex(0);
int terrainCollisionVertexIndex = 0; terrainProfileGeometry = static_cast<QSGGeometryNode*>(node)->geometry();
double currentDistance = 0; terrainProfileGeometry->allocate(cTerrainProfilePoints);
QSGGeometry::Point2D* flightProfileVertices = flightProfileGeometry->vertexDataAsPoint2D(); node->markDirty(QSGNode::DirtyGeometry);
QSGGeometry::Point2D* terrainVertices = terrainProfileGeometry->vertexDataAsPoint2D();
QSGGeometry::Point2D* missingTerrainVertices = missingTerrainGeometry->vertexDataAsPoint2D(); node = rootNode->childAtIndex(1);
QSGGeometry::Point2D* terrainCollisionVertices = terrainCollisionGeometry->vertexDataAsPoint2D(); missingTerrainGeometry = static_cast<QSGGeometryNode*>(node)->geometry();
missingTerrainGeometry->allocate(cMissingTerrainSegments * 2);
node->markDirty(QSGNode::DirtyGeometry);
node = rootNode->childAtIndex(2);
flightProfileGeometry = static_cast<QSGGeometryNode*>(node)->geometry();
flightProfileGeometry->allocate(cFlightProfileSegments * 2);
node->markDirty(QSGNode::DirtyGeometry);
node = rootNode->childAtIndex(3);
terrainCollisionGeometry = static_cast<QSGGeometryNode*>(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++) { for (int viIndex=0; viIndex<_visualItems->count(); viIndex++) {
VisualMissionItem* visualItem = _visualItems->value<VisualMissionItem*>(viIndex); VisualMissionItem* visualItem = _visualItems->value<VisualMissionItem*>(viIndex);
ComplexMissionItem* complexItem = _visualItems->value<ComplexMissionItem*>(viIndex); ComplexMissionItem* complexItem = _visualItems->value<ComplexMissionItem*>(viIndex);
...@@ -276,8 +281,8 @@ QSGNode* TerrainProfile::updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePai ...@@ -276,8 +281,8 @@ QSGNode* TerrainProfile::updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePai
FlightPathSegment* segment = complexItem->flightPathSegments()->value<FlightPathSegment*>(segmentIndex); FlightPathSegment* segment = complexItem->flightPathSegments()->value<FlightPathSegment*>(segmentIndex);
_addFlightProfileSegment (segment, currentDistance, amslAltRange, flightProfileVertices, flightProfileVertexIndex); _addFlightProfileSegment (segment, currentDistance, amslAltRange, flightProfileVertices, flightProfileVertexIndex);
_addTerrainProfileSegment (segment, currentDistance, amslAltRange, terrainVertices, terrainVertexIndex); _addTerrainProfileSegment (segment, currentDistance, amslAltRange, terrainProfileVertices, terrainProfileVertexIndex);
_addMissingTerrainSegment (segment, currentDistance, missingTerrainVertices, missingTerrainVertexIndex); _addMissingTerrainSegment (segment, currentDistance, missingTerrainVertices, missingterrainProfileVertexIndex);
_addTerrainCollisionSegment (segment, currentDistance, amslAltRange, terrainCollisionVertices, terrainCollisionVertexIndex); _addTerrainCollisionSegment (segment, currentDistance, amslAltRange, terrainCollisionVertices, terrainCollisionVertexIndex);
currentDistance += segment->totalDistance(); currentDistance += segment->totalDistance();
...@@ -289,8 +294,8 @@ QSGNode* TerrainProfile::updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePai ...@@ -289,8 +294,8 @@ QSGNode* TerrainProfile::updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePai
FlightPathSegment* segment = visualItem->simpleFlightPathSegment(); FlightPathSegment* segment = visualItem->simpleFlightPathSegment();
_addFlightProfileSegment (segment, currentDistance, amslAltRange, flightProfileVertices, flightProfileVertexIndex); _addFlightProfileSegment (segment, currentDistance, amslAltRange, flightProfileVertices, flightProfileVertexIndex);
_addTerrainProfileSegment (segment, currentDistance, amslAltRange, terrainVertices, terrainVertexIndex); _addTerrainProfileSegment (segment, currentDistance, amslAltRange, terrainProfileVertices, terrainProfileVertexIndex);
_addMissingTerrainSegment (segment, currentDistance, missingTerrainVertices, missingTerrainVertexIndex); _addMissingTerrainSegment (segment, currentDistance, missingTerrainVertices, missingterrainProfileVertexIndex);
_addTerrainCollisionSegment (segment, currentDistance, amslAltRange, terrainCollisionVertices, terrainCollisionVertexIndex); _addTerrainCollisionSegment (segment, currentDistance, amslAltRange, terrainCollisionVertices, terrainCollisionVertexIndex);
currentDistance += segment->totalDistance(); currentDistance += segment->totalDistance();
...@@ -326,3 +331,13 @@ void TerrainProfile::_setVertex(QSGGeometry::Point2D& vertex, double x, double y ...@@ -326,3 +331,13 @@ void TerrainProfile::_setVertex(QSGGeometry::Point2D& vertex, double x, double y
{ {
vertex.set(x + _horizontalMargin, y + _verticalMargin); vertex.set(x + _horizontalMargin, y + _verticalMargin);
} }
bool TerrainProfile::_shouldAddFlightProfileSegment (FlightPathSegment* segment)
{
return !qIsNaN(segment->coord1AMSLAlt()) && !qIsNaN(segment->coord2AMSLAlt());
}
bool TerrainProfile::_shouldAddMissingTerrainSegment (FlightPathSegment* segment)
{
return segment->amslTerrainHeights().count() == 0;
}
...@@ -57,14 +57,16 @@ private slots: ...@@ -57,14 +57,16 @@ private slots:
void _newVisualItems (void); void _newVisualItems (void);
private: private:
void _createGeometry (QSGGeometryNode*& geometryNode, QSGGeometry*& geometry, int vertices, QSGGeometry::DrawingMode drawingMode, const QColor& color); void _createGeometry (QSGGeometryNode*& geometryNode, QSGGeometry*& geometry, QSGGeometry::DrawingMode drawingMode, const QColor& color);
void _updateSegmentCounts (FlightPathSegment* segment, int& cTerrainPoints, int& cMissingTerrainSegments, int& cTerrainCollisionSegments, double& maxTerrainHeight); void _updateSegmentCounts (FlightPathSegment* segment, int& cFlightProfileSegments, int& cTerrainPoints, int& cMissingTerrainSegments, int& cTerrainCollisionSegments, double& maxTerrainHeight);
void _addTerrainProfileSegment (FlightPathSegment* segment, double currentDistance, double amslAltRange, QSGGeometry::Point2D* terrainVertices, int& terrainVertexIndex); 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 _addMissingTerrainSegment (FlightPathSegment* segment, double currentDistance, QSGGeometry::Point2D* missingTerrainVertices, int& missingTerrainVertexIndex);
void _addTerrainCollisionSegment (FlightPathSegment* segment, double currentDistance, double amslAltRange, QSGGeometry::Point2D* terrainCollisionVertices, int& terrainCollisionVertexIndex); 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 _addFlightProfileSegment (FlightPathSegment* segment, double currentDistance, double amslAltRange, QSGGeometry::Point2D* flightProfileVertices, int& flightProfileVertexIndex);
double _availableHeight (void) const; double _availableHeight (void) const;
void _setVertex (QSGGeometry::Point2D& vertex, double x, double y); void _setVertex (QSGGeometry::Point2D& vertex, double x, double y);
bool _shouldAddFlightProfileSegment (FlightPathSegment* segment);
bool _shouldAddMissingTerrainSegment (FlightPathSegment* segment);
MissionController* _missionController = nullptr; MissionController* _missionController = nullptr;
QmlObjectListModel* _visualItems = nullptr; QmlObjectListModel* _visualItems = nullptr;
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment