QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
TerrainProfile.cc
Go to the documentation of this file.
1#include "TerrainProfile.h"
2#include "MissionController.h"
4#include "FlightPathSegment.h"
7#include "QGCApplication.h"
8
9#include <QtQuick/QSGFlatColorMaterial>
10
11QGC_LOGGING_CATEGORY(TerrainProfileLog, "Terrain.TerrainProfile")
12
13TerrainProfile::TerrainProfile(QQuickItem* parent)
14 : QQuickItem(parent)
15{
16 setFlag(QQuickItem::ItemHasContents, true);
17
18 connect(this, &QQuickItem::heightChanged, this, &QQuickItem::update);
19 connect(this, &TerrainProfile::visibleWidthChanged, this, &QQuickItem::update);
20
21 // This collapse multiple _updateSignals in a row to a single update
22 connect(this, &TerrainProfile::_updateSignal, this, &QQuickItem::update, Qt::QueuedConnection);
23 qgcApp()->addCompressedSignal(QMetaMethod::fromSignal(&TerrainProfile::_updateSignal));
24}
25
27{
28 QQuickItem::componentComplete();
29}
30
32{
33 if (missionController != _missionController) {
34 _missionController = missionController;
35 _visualItems = _missionController->visualItems();
36
38
39 connect(_missionController, &MissionController::visualItemsChanged, this, &TerrainProfile::_newVisualItems);
40
41 connect(this, &TerrainProfile::visibleWidthChanged, this, &TerrainProfile::_updateSignal, Qt::QueuedConnection);
42 connect(_missionController, &MissionController::recalcTerrainProfile, this, &TerrainProfile::_updateSignal, Qt::QueuedConnection);
43 }
44}
45
46void TerrainProfile::_newVisualItems(void)
47{
48 _visualItems = _missionController->visualItems();
49 emit _updateSignal();
50}
51
52void TerrainProfile::_createGeometry(QSGGeometryNode*& geometryNode, QSGGeometry*& geometry, QSGGeometry::DrawingMode drawingMode, const QColor& color)
53{
54 QSGFlatColorMaterial* terrainMaterial = new QSGFlatColorMaterial;
55 terrainMaterial->setColor(color);
56
57 geometry = new QSGGeometry(QSGGeometry::defaultAttributes_Point2D(), 0);
58 geometry->setDrawingMode(drawingMode);
59 geometry->setLineWidth(2);
60
61 geometryNode = new QSGGeometryNode;
62 geometryNode->setFlag(QSGNode::OwnsGeometry);
63 geometryNode->setFlag(QSGNode::OwnsMaterial);
64 geometryNode->setFlag(QSGNode::OwnedByParent);
65 geometryNode->setMaterial(terrainMaterial);
66 geometryNode->setGeometry(geometry);
67}
68
69void TerrainProfile::_updateSegmentCounts(FlightPathSegment* segment, int& cFlightProfileSegments, int& cTerrainProfilePoints, int& cMissingTerrainSegments, int& cTerrainCollisionSegments, double& minTerrainHeight, double& maxTerrainHeight)
70{
71 if (_shouldAddFlightProfileSegment(segment)) {
73 // We show a full above terrain profile for flight segment
74 cFlightProfileSegments += segment->amslTerrainHeights().count() - 1;
75 } else {
76 cFlightProfileSegments++;
77 }
78 }
79
80 if (_shouldAddMissingTerrainSegment(segment)) {
81 cMissingTerrainSegments += 1;
82 } else {
83 cTerrainProfilePoints += segment->amslTerrainHeights().count();
84 for (int i=0; i<segment->amslTerrainHeights().count(); i++) {
85 minTerrainHeight = std::fmin(minTerrainHeight, segment->amslTerrainHeights()[i].value<double>());
86 maxTerrainHeight = std::fmax(maxTerrainHeight, segment->amslTerrainHeights()[i].value<double>());
87 }
88 }
89 if (segment->terrainCollision()) {
90 cTerrainCollisionSegments++;
91 }
92}
93
94void TerrainProfile::_addTerrainProfileSegment(FlightPathSegment* segment, double currentDistance, double amslAltRange, QSGGeometry::Point2D* terrainVertices, int& terrainProfileVertexIndex)
95{
96 double terrainDistance = 0;
97 for (int heightIndex=0; heightIndex<segment->amslTerrainHeights().count(); heightIndex++) {
98 // Move along the x axis which is distance
99 if (heightIndex == 0) {
100 // The first point in the segment is at the position of the last point. So nothing to do here.
101 } else if (heightIndex == segment->amslTerrainHeights().count() - 2) {
102 // The distance between the last two heights differs with each terrain query
103 terrainDistance += segment->finalDistanceBetween();
104 } else {
105 // The distance between all terrain heights except for the last is the same
106 terrainDistance += segment->distanceBetween();
107 }
108
109 // Move along the y axis which is a view or terrain height as a percentage between the min/max AMSL altitude for all segments
110 double amslTerrainHeight = segment->amslTerrainHeights()[heightIndex].value<double>();
111 double terrainHeightPercent = (amslTerrainHeight - _minAMSLAlt) / amslAltRange;
112
113 float x = (currentDistance + terrainDistance) * _pixelsPerMeter;
114 float y = height() - (terrainHeightPercent * height());
115 terrainVertices[terrainProfileVertexIndex++].set(x, y);
116 }
117}
118
119void TerrainProfile::_addMissingTerrainSegment(FlightPathSegment* segment, double currentDistance, QSGGeometry::Point2D* missingTerrainVertices, int& missingterrainProfileVertexIndex)
120{
121 if (_shouldAddMissingTerrainSegment(segment)) {
122 float x = currentDistance * _pixelsPerMeter;
123 float y = height();
124 missingTerrainVertices[missingterrainProfileVertexIndex++].set(x, y);
125 missingTerrainVertices[missingterrainProfileVertexIndex++].set(x + (segment->totalDistance() * _pixelsPerMeter), y);
126 }
127}
128
129void TerrainProfile::_addTerrainCollisionSegment(FlightPathSegment* segment, double currentDistance, double amslAltRange, QSGGeometry::Point2D* terrainCollisionVertices, int& terrainCollisionVertexIndex)
130{
131 if (segment->terrainCollision()) {
132 double amslCoord1Height = segment->coord1AMSLAlt();
133 double amslCoord2Height = segment->coord2AMSLAlt();
134 double coord1HeightPercent = (amslCoord1Height - _minAMSLAlt) / amslAltRange;
135 double coord2HeightPercent = (amslCoord2Height - _minAMSLAlt) / amslAltRange;
136
137 float x = currentDistance * _pixelsPerMeter;
138 float y = height() - (coord1HeightPercent * height());
139
140 terrainCollisionVertices[terrainCollisionVertexIndex++].set(x, y);
141
142 x += segment->totalDistance() * _pixelsPerMeter;
143 y = height() - (coord2HeightPercent * height());
144
145 terrainCollisionVertices[terrainCollisionVertexIndex++].set(x, y);
146 }
147}
148
149void TerrainProfile::_addFlightProfileSegment(FlightPathSegment* segment, double currentDistance, double amslAltRange, QSGGeometry::Point2D* flightProfileVertices, int& flightProfileVertexIndex)
150{
151 if (!_shouldAddFlightProfileSegment(segment)) {
152 return;
153 }
154
156 double terrainDistance = 0;
157 double distanceToSurface = segment->coord1AMSLAlt() - segment->amslTerrainHeights().first().value<double>();
158 for (int heightIndex=0; heightIndex<segment->amslTerrainHeights().count(); heightIndex++) {
159 // Move along the x axis which is distance
160 if (heightIndex == 0) {
161 // The first point in the segment is at the position of the last point. So nothing to do here.
162 } else if (heightIndex == segment->amslTerrainHeights().count() - 2) {
163 // The distance between the last two heights differs with each terrain query
164 terrainDistance += segment->finalDistanceBetween();
165 } else {
166 // The distance between all terrain heights except for the last is the same
167 terrainDistance += segment->distanceBetween();
168 }
169
170 if (heightIndex > 1) {
171 // Add first coord of segment
172 auto previousVertex = flightProfileVertices[flightProfileVertexIndex-1];
173 flightProfileVertices[flightProfileVertexIndex++].set(previousVertex.x, previousVertex.y);
174 }
175
176 // Add second coord of segment (or very first one)
177 double amslTerrainHeight = segment->amslTerrainHeights()[heightIndex].value<double>() + distanceToSurface;
178 double terrainHeightPercent = (amslTerrainHeight - _minAMSLAlt) / amslAltRange;
179
180 float x = (currentDistance + terrainDistance) * _pixelsPerMeter;
181 float y = height() - (terrainHeightPercent * height());
182 flightProfileVertices[flightProfileVertexIndex++].set(x, y);
183
184 }
185 } else {
186 double amslCoord1Height = segment->coord1AMSLAlt();
187 double amslCoord2Height = segment->coord2AMSLAlt();
188 double coord1HeightPercent = (amslCoord1Height - _minAMSLAlt) / amslAltRange;
189 double coord2HeightPercent = (amslCoord2Height - _minAMSLAlt) / amslAltRange;
190
191 float x = currentDistance * _pixelsPerMeter;
192 float y = height() - (coord1HeightPercent * height());
193
194 flightProfileVertices[flightProfileVertexIndex++].set(x, y);
195
196 x += segment->totalDistance() * _pixelsPerMeter;
197 y = height() - (coord2HeightPercent * height());
198
199 flightProfileVertices[flightProfileVertexIndex++].set(x, y);
200 }
201}
202
203QSGNode* TerrainProfile::updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePaintNodeData* /*updatePaintNodeData*/)
204{
205 QSGNode* rootNode = static_cast<QSGNode *>(oldNode);
206 QSGGeometry* terrainProfileGeometry = nullptr;
207 QSGGeometry* missingTerrainGeometry = nullptr;
208 QSGGeometry* flightProfileGeometry = nullptr;
209 QSGGeometry* terrainCollisionGeometry = nullptr;
210 int cTerrainProfilePoints = 0;
211 int cMissingTerrainSegments = 0;
212 int cFlightProfileSegments = 0;
213 int cTerrainCollisionSegments = 0;
214 double minTerrainHeight = qQNaN();
215 double maxTerrainHeight = qQNaN();
216
217 // First we need to determine:
218 // - how many terrain profile vertices we need
219 // - how many missing terrain segments there are
220 // - how many flight profile segments we need
221 // - how many terrain collision segments there are
222 // - what is the total distance so we can calculate pixels per meter
223
224 for (int viIndex=0; viIndex<_visualItems->count(); viIndex++) {
225 VisualMissionItem* visualItem = _visualItems->value<VisualMissionItem*>(viIndex);
226 ComplexMissionItem* complexItem = _visualItems->value<ComplexMissionItem*>(viIndex);
227
228 if (visualItem->simpleFlightPathSegment()) {
229 FlightPathSegment* segment = visualItem->simpleFlightPathSegment();
230 _updateSegmentCounts(segment, cFlightProfileSegments, cTerrainProfilePoints, cMissingTerrainSegments, cTerrainCollisionSegments, minTerrainHeight, maxTerrainHeight);
231 }
232
233 if (complexItem) {
234 for (int segmentIndex=0; segmentIndex<complexItem->flightPathSegments()->count(); segmentIndex++) {
235 FlightPathSegment* segment = complexItem->flightPathSegments()->value<FlightPathSegment*>(segmentIndex);
236 _updateSegmentCounts(segment, cFlightProfileSegments, cTerrainProfilePoints, cMissingTerrainSegments, cTerrainCollisionSegments, minTerrainHeight, maxTerrainHeight);
237 }
238 }
239 }
240
241 // The profile view min/max is setup to include a full terrain profile as well as the flight path segments.
242 _minAMSLAlt = std::fmin(_missionController->minAMSLAltitude(), minTerrainHeight);
243 _maxAMSLAlt = std::fmax(_missionController->maxAMSLAltitude(), maxTerrainHeight);
244
245 // We add a buffer to the min/max alts such that the visuals don't draw lines right at the edges of the display
246 double amslAltRange = _maxAMSLAlt - _minAMSLAlt;
247 double amslAltRangeBuffer = amslAltRange * 0.1;
248 _maxAMSLAlt += amslAltRangeBuffer;
249 if (_minAMSLAlt > 0.0) {
250 _minAMSLAlt -= amslAltRangeBuffer;
251 _minAMSLAlt = std::fmax(_minAMSLAlt, 0.0);
252 }
253 amslAltRange = _maxAMSLAlt - _minAMSLAlt;
254
255 static int counter = 0;
256 qCDebug(TerrainProfileLog) << "missionController min/max" << _missionController->minAMSLAltitude() << _missionController->maxAMSLAltitude();
257 qCDebug(TerrainProfileLog) << QStringLiteral("updatePaintNode counter:%1 cFlightProfileSegments:%2 cTerrainProfilePoints:%3 cMissingTerrainSegments:%4 cTerrainCollisionSegments:%5 _minAMSLAlt:%6 _maxAMSLAlt:%7 maxTerrainHeight:%8")
258 .arg(counter++).arg(cFlightProfileSegments).arg(cTerrainProfilePoints).arg(cMissingTerrainSegments).arg(cTerrainCollisionSegments).arg(_minAMSLAlt).arg(_maxAMSLAlt).arg(maxTerrainHeight);
259
260 _pixelsPerMeter = _visibleWidth / _missionController->missionTotalDistance();
261
262 // Instantiate nodes
263 if (!rootNode) {
264 rootNode = new QSGNode;
265
266 QSGGeometryNode* terrainProfileNode = nullptr;
267 QSGGeometryNode* missingTerrainNode = nullptr;
268 QSGGeometryNode* flightProfileNode = nullptr;
269 QSGGeometryNode* terrainCollisionNode = nullptr;
270
271 _createGeometry(terrainProfileNode, terrainProfileGeometry, QSGGeometry::DrawLineStrip, "green");
272 _createGeometry(missingTerrainNode, missingTerrainGeometry, QSGGeometry::DrawLines, "yellow");
273 _createGeometry(flightProfileNode, flightProfileGeometry, QSGGeometry::DrawLines, "orange");
274 _createGeometry(terrainCollisionNode, terrainCollisionGeometry, QSGGeometry::DrawLines, "red");
275
276 rootNode->appendChildNode(terrainProfileNode);
277 rootNode->appendChildNode(missingTerrainNode);
278 rootNode->appendChildNode(flightProfileNode);
279 rootNode->appendChildNode(terrainCollisionNode);
280 }
281
282 // Allocate space for the vertices
283
284 QSGNode* node = rootNode->childAtIndex(0);
285 terrainProfileGeometry = static_cast<QSGGeometryNode*>(node)->geometry();
286 terrainProfileGeometry->allocate(cTerrainProfilePoints);
287 node->markDirty(QSGNode::DirtyGeometry);
288
289 node = rootNode->childAtIndex(1);
290 missingTerrainGeometry = static_cast<QSGGeometryNode*>(node)->geometry();
291 missingTerrainGeometry->allocate(cMissingTerrainSegments * 2);
292 node->markDirty(QSGNode::DirtyGeometry);
293
294 node = rootNode->childAtIndex(2);
295 flightProfileGeometry = static_cast<QSGGeometryNode*>(node)->geometry();
296 flightProfileGeometry->allocate(cFlightProfileSegments * 2);
297 node->markDirty(QSGNode::DirtyGeometry);
298
299 node = rootNode->childAtIndex(3);
300 terrainCollisionGeometry = static_cast<QSGGeometryNode*>(node)->geometry();
301 terrainCollisionGeometry->allocate(cTerrainCollisionSegments * 2);
302 node->markDirty(QSGNode::DirtyGeometry);
303
304 int flightProfileVertexIndex = 0;
305 int terrainProfileVertexIndex = 0;
306 int missingterrainProfileVertexIndex = 0;
307 int terrainCollisionVertexIndex = 0;
308 double currentDistance = 0;
309 QSGGeometry::Point2D* flightProfileVertices = flightProfileGeometry->vertexDataAsPoint2D();
310 QSGGeometry::Point2D* terrainProfileVertices = terrainProfileGeometry->vertexDataAsPoint2D();
311 QSGGeometry::Point2D* missingTerrainVertices = missingTerrainGeometry->vertexDataAsPoint2D();
312 QSGGeometry::Point2D* terrainCollisionVertices = terrainCollisionGeometry->vertexDataAsPoint2D();
313
314 // This step places the vertices for display into the nodes
315 for (int viIndex=0; viIndex<_visualItems->count(); viIndex++) {
316 VisualMissionItem* visualItem = _visualItems->value<VisualMissionItem*>(viIndex);
317 ComplexMissionItem* complexItem = _visualItems->value<ComplexMissionItem*>(viIndex);
318
319 if (complexItem) {
320 if (complexItem->flightPathSegments()->count() == 0) {
321 currentDistance += complexItem->complexDistance();
322 } else {
323 for (int segmentIndex=0; segmentIndex<complexItem->flightPathSegments()->count(); segmentIndex++) {
324 FlightPathSegment* segment = complexItem->flightPathSegments()->value<FlightPathSegment*>(segmentIndex);
325
326 _addFlightProfileSegment (segment, currentDistance, amslAltRange, flightProfileVertices, flightProfileVertexIndex);
327 _addTerrainProfileSegment (segment, currentDistance, amslAltRange, terrainProfileVertices, terrainProfileVertexIndex);
328 _addMissingTerrainSegment (segment, currentDistance, missingTerrainVertices, missingterrainProfileVertexIndex);
329 _addTerrainCollisionSegment (segment, currentDistance, amslAltRange, terrainCollisionVertices, terrainCollisionVertexIndex);
330
331 currentDistance += segment->totalDistance();
332 }
333 }
334 }
335
336 if (visualItem->simpleFlightPathSegment()) {
337 FlightPathSegment* segment = visualItem->simpleFlightPathSegment();
338
339 _addFlightProfileSegment (segment, currentDistance, amslAltRange, flightProfileVertices, flightProfileVertexIndex);
340 _addTerrainProfileSegment (segment, currentDistance, amslAltRange, terrainProfileVertices, terrainProfileVertexIndex);
341 _addMissingTerrainSegment (segment, currentDistance, missingTerrainVertices, missingterrainProfileVertexIndex);
342 _addTerrainCollisionSegment (segment, currentDistance, amslAltRange, terrainCollisionVertices, terrainCollisionVertexIndex);
343
344 currentDistance += segment->totalDistance();
345 }
346 }
347
348 setImplicitWidth(_visibleWidth/*(_totalDistance * pixelsPerMeter) + (_horizontalMargin * 2)*/);
349 setWidth(implicitWidth());
350
351 emit implicitWidthChanged();
352 emit widthChanged();
354 emit minAMSLAltChanged();
355 emit maxAMSLAltChanged();
356
357 return rootNode;
358}
359
360bool TerrainProfile::_shouldAddFlightProfileSegment(FlightPathSegment* segment)
361{
362 bool shouldAdd = !qIsNaN(segment->coord1AMSLAlt()) && !qIsNaN(segment->coord2AMSLAlt());
364 shouldAdd &= segment->amslTerrainHeights().count() != 0;
365 }
366 return shouldAdd;
367}
368
369bool TerrainProfile::_shouldAddMissingTerrainSegment(FlightPathSegment* segment)
370{
371 return segment->amslTerrainHeights().count() == 0;
372}
#define qgcApp()
#define QGC_LOGGING_CATEGORY(name, categoryStr)
virtual double complexDistance(void) const =0
double distanceBetween(void) const
SegmentType segmentType(void) const
const QVariantList & amslTerrainHeights(void) const
double finalDistanceBetween(void) const
bool terrainCollision(void) const
double totalDistance(void) const
double coord2AMSLAlt(void) const
double coord1AMSLAlt(void) const
void visualItemsChanged(void)
double minAMSLAltitude(void) const
double maxAMSLAltitude(void) const
void recalcTerrainProfile(void)
double missionTotalDistance(void) const
QmlObjectListModel * visualItems(void)
T value(int index) const
int count() const override final
void componentComplete(void) final
void setMissionController(MissionController *missionController)
void pixelsPerMeterChanged(void)
void _updateSignal(void)
void visibleWidthChanged(void)
void minAMSLAltChanged(void)
void maxAMSLAltChanged(void)
QSGNode * updatePaintNode(QSGNode *oldNode, QQuickItem::UpdatePaintNodeData *updatePaintNodeData)
void missionControllerChanged(void)
FlightPathSegment * simpleFlightPathSegment(void)