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
9QGC_LOGGING_CATEGORY(TerrainProfileLog, "Terrain.TerrainProfile")
10
11TerrainProfile::TerrainProfile(QQuickItem* parent)
12 : QQuickItem(parent)
13{
14 connect(this, &QQuickItem::heightChanged, this, &TerrainProfile::_updateProfile);
15
16 connect(this, &TerrainProfile::_updateSignal, this, &TerrainProfile::_updateProfile, Qt::QueuedConnection);
17 qgcApp()->addCompressedSignal(QMetaMethod::fromSignal(&TerrainProfile::_updateSignal));
18}
19
20void TerrainProfile::setVisibleWidth(double visibleWidth)
21{
22 if (qFuzzyCompare(_visibleWidth, visibleWidth)) {
23 return;
24 }
25 _visibleWidth = visibleWidth;
27}
28
30{
31 QQuickItem::componentComplete();
32}
33
35{
36 if (missionController != _missionController) {
37 _missionController = missionController;
38 _visualItems = _missionController->visualItems();
39
41
42 connect(_missionController, &MissionController::visualItemsReset, this, &TerrainProfile::_newVisualItems);
43 connect(this, &TerrainProfile::visibleWidthChanged, this, &TerrainProfile::_updateSignal, Qt::QueuedConnection);
44 connect(_missionController, &MissionController::recalcTerrainProfile, this, &TerrainProfile::_updateSignal, Qt::QueuedConnection);
45
46 emit _updateSignal();
47 }
48}
49
50void TerrainProfile::_newVisualItems(void)
51{
52 _visualItems = _missionController->visualItems();
53 emit _updateSignal();
54}
55
56void TerrainProfile::_updateSegmentCounts(FlightPathSegment* segment, int& cFlightProfileSegments, int& cTerrainProfilePoints, int& cMissingTerrainSegments, int& cTerrainCollisionSegments, double& minTerrainHeight, double& maxTerrainHeight)
57{
58 if (_shouldAddFlightProfileSegment(segment)) {
60 cFlightProfileSegments += segment->amslTerrainHeights().count() - 1;
61 } else {
62 cFlightProfileSegments++;
63 }
64 }
65
66 if (_shouldAddMissingTerrainSegment(segment)) {
67 cMissingTerrainSegments += 1;
68 } else {
69 cTerrainProfilePoints += segment->amslTerrainHeights().count();
70 for (int i=0; i<segment->amslTerrainHeights().count(); i++) {
71 minTerrainHeight = std::fmin(minTerrainHeight, segment->amslTerrainHeights()[i].value<double>());
72 maxTerrainHeight = std::fmax(maxTerrainHeight, segment->amslTerrainHeights()[i].value<double>());
73 }
74 }
75 if (segment->terrainCollision()) {
76 cTerrainCollisionSegments++;
77 }
78}
79
80void TerrainProfile::_updateProfile(void)
81{
82 if (!_missionController || !_visualItems) {
83 return;
84 }
85
86 int cTerrainProfilePoints = 0;
87 int cMissingTerrainSegments = 0;
88 int cFlightProfileSegments = 0;
89 int cTerrainCollisionSegments = 0;
90 double minTerrainHeight = qQNaN();
91 double maxTerrainHeight = qQNaN();
92
93 for (int viIndex=0; viIndex<_visualItems->count(); viIndex++) {
94 VisualMissionItem* visualItem = _visualItems->value<VisualMissionItem*>(viIndex);
95 ComplexMissionItem* complexItem = _visualItems->value<ComplexMissionItem*>(viIndex);
96
97 if (visualItem->simpleFlightPathSegment()) {
98 FlightPathSegment* segment = visualItem->simpleFlightPathSegment();
99 _updateSegmentCounts(segment, cFlightProfileSegments, cTerrainProfilePoints, cMissingTerrainSegments, cTerrainCollisionSegments, minTerrainHeight, maxTerrainHeight);
100 }
101
102 if (complexItem) {
103 for (int segmentIndex=0; segmentIndex<complexItem->flightPathSegments()->count(); segmentIndex++) {
104 FlightPathSegment* segment = complexItem->flightPathSegments()->value<FlightPathSegment*>(segmentIndex);
105 _updateSegmentCounts(segment, cFlightProfileSegments, cTerrainProfilePoints, cMissingTerrainSegments, cTerrainCollisionSegments, minTerrainHeight, maxTerrainHeight);
106 }
107 }
108 }
109
110 _minAMSLAlt = std::fmin(_missionController->minAMSLAltitude(), minTerrainHeight);
111 _maxAMSLAlt = std::fmax(_missionController->maxAMSLAltitude(), maxTerrainHeight);
112
113 double amslAltRange = _maxAMSLAlt - _minAMSLAlt;
114 double amslAltRangeBuffer = amslAltRange * 0.1;
115 _maxAMSLAlt += amslAltRangeBuffer;
116 if (_minAMSLAlt > 0.0) {
117 _minAMSLAlt -= amslAltRangeBuffer;
118 _minAMSLAlt = std::fmax(_minAMSLAlt, 0.0);
119 }
120
121 const double missionTotalDistance = _missionController->missionTotalDistance();
122 _pixelsPerMeter = (missionTotalDistance > 0.0) ? (_visibleWidth / missionTotalDistance) : 0.0;
123
124 static int counter = 0;
125 qCDebug(TerrainProfileLog).noquote() << "counter" << counter++ <<
126 "\n\tmissionController minAMSLAltitude" << _missionController->minAMSLAltitude() <<
127 "\n\tmissionController maxAMSLAltitude" << _missionController->maxAMSLAltitude() <<
128 "\n\tcFlightProfileSegments" << cFlightProfileSegments <<
129 "\n\tcTerrainProfilePoints" << cTerrainProfilePoints <<
130 "\n\tcMissingTerrainSegments" << cMissingTerrainSegments <<
131 "\n\tcTerrainCollisionSegments" << cTerrainCollisionSegments <<
132 "\n\t_minAMSLAlt" << _minAMSLAlt <<
133 "\n\t_maxAMSLAlt" << _maxAMSLAlt <<
134 "\n\tmaxTerrainHeight" << maxTerrainHeight;
135
136 setImplicitWidth(_visibleWidth);
137 setWidth(implicitWidth());
138
140 emit minAMSLAltChanged();
141 emit maxAMSLAltChanged();
142 emit profileChanged();
143}
144
145void TerrainProfile::updateSeries(QXYSeries* terrainSeries, QXYSeries* flightSeries, QXYSeries* missingSeries, QXYSeries* collisionSeries)
146{
147 if (!_missionController || !_visualItems) {
148 return;
149 }
150
151 QList<QPointF> terrainPoints;
152 QList<QPointF> flightPoints;
153 QList<QPointF> missingPoints;
154 QList<QPointF> collisionPoints;
155
156 double currentDistance = 0;
157
158 for (int viIndex=0; viIndex<_visualItems->count(); viIndex++) {
159 VisualMissionItem* visualItem = _visualItems->value<VisualMissionItem*>(viIndex);
160 ComplexMissionItem* complexItem = _visualItems->value<ComplexMissionItem*>(viIndex);
161
162 if (complexItem) {
163 if (complexItem->flightPathSegments()->count() == 0) {
164 currentDistance += complexItem->complexDistance();
165 } else {
166 for (int segmentIndex=0; segmentIndex<complexItem->flightPathSegments()->count(); segmentIndex++) {
167 FlightPathSegment* segment = complexItem->flightPathSegments()->value<FlightPathSegment*>(segmentIndex);
168
169 _addTerrainPoints (segment, currentDistance, terrainPoints);
170 _addFlightPoints (segment, currentDistance, flightPoints);
171 _addMissingPoints (segment, currentDistance, missingPoints);
172 _addCollisionPoints (segment, currentDistance, collisionPoints);
173
174 currentDistance += segment->totalDistance();
175 }
176 }
177 }
178
179 if (visualItem->simpleFlightPathSegment()) {
180 FlightPathSegment* segment = visualItem->simpleFlightPathSegment();
181
182 _addTerrainPoints (segment, currentDistance, terrainPoints);
183 _addFlightPoints (segment, currentDistance, flightPoints);
184 _addMissingPoints (segment, currentDistance, missingPoints);
185 _addCollisionPoints (segment, currentDistance, collisionPoints);
186
187 currentDistance += segment->totalDistance();
188 }
189 }
190
191 // Using clear/append instead of replace works around bugs in QtGraphs where you end up with parts of old series data showing.
192 if (terrainSeries) {
193 terrainSeries->clear();
194 terrainSeries->append(terrainPoints);
195 }
196 if (flightSeries) {
197 flightSeries->clear();
198 flightSeries->append(flightPoints);
199 }
200 if (missingSeries) {
201 missingSeries->clear();
202 missingSeries->append(missingPoints);
203 }
204 if (collisionSeries) {
205 collisionSeries->clear();
206 collisionSeries->append(collisionPoints);
207 }
208
209 qCDebug(TerrainProfileLog).noquote() << QStringLiteral("updateSeries terrainPoints:%1 flightPoints:%2 missingPoints:%3 collisionPoints:%4")
210 .arg(terrainPoints.count()).arg(flightPoints.count()).arg(missingPoints.count()).arg(collisionPoints.count());
211}
212
213void TerrainProfile::_addTerrainPoints(FlightPathSegment* segment, double currentDistance, QList<QPointF>& points)
214{
215 if (_shouldAddMissingTerrainSegment(segment)) {
216 if (!points.isEmpty()) {
217 points.append(QPointF(qQNaN(), qQNaN()));
218 }
219 return;
220 }
221
222 double terrainDistance = 0;
223 for (int heightIndex=0; heightIndex<segment->amslTerrainHeights().count(); heightIndex++) {
224 if (heightIndex == 0) {
225 // First point at start of segment
226 } else if (heightIndex == segment->amslTerrainHeights().count() - 2) {
227 terrainDistance += segment->finalDistanceBetween();
228 } else {
229 terrainDistance += segment->distanceBetween();
230 }
231
232 const double amslTerrainHeight = segment->amslTerrainHeights()[heightIndex].value<double>() * _verticalScale;
233 points.append(QPointF((currentDistance + terrainDistance) * _horizontalScale, amslTerrainHeight));
234 }
235}
236
237void TerrainProfile::_addFlightPoints(FlightPathSegment* segment, double currentDistance, QList<QPointF>& points)
238{
239 if (!_shouldAddFlightProfileSegment(segment)) {
240 if (!points.isEmpty()) {
241 points.append(QPointF(currentDistance * _horizontalScale, qQNaN()));
242 }
243 return;
244 }
245
247 double terrainDistance = 0;
248 double distanceToSurface = segment->coord1AMSLAlt() - segment->amslTerrainHeights().first().value<double>();
249 for (int heightIndex=0; heightIndex<segment->amslTerrainHeights().count(); heightIndex++) {
250 if (heightIndex == 0) {
251 // First point
252 } else if (heightIndex == segment->amslTerrainHeights().count() - 2) {
253 terrainDistance += segment->finalDistanceBetween();
254 } else {
255 terrainDistance += segment->distanceBetween();
256 }
257
258 const double amslTerrainHeight = (segment->amslTerrainHeights()[heightIndex].value<double>() + distanceToSurface) * _verticalScale;
259 points.append(QPointF((currentDistance + terrainDistance) * _horizontalScale, amslTerrainHeight));
260 }
261 } else {
262 points.append(QPointF(currentDistance * _horizontalScale, segment->coord1AMSLAlt() * _verticalScale));
263 points.append(QPointF((currentDistance + segment->totalDistance()) * _horizontalScale, segment->coord2AMSLAlt() * _verticalScale));
264 }
265}
266
267void TerrainProfile::_addMissingPoints(FlightPathSegment* segment, double currentDistance, QList<QPointF>& points)
268{
269 if (_shouldAddMissingTerrainSegment(segment)) {
270 if (!points.isEmpty()) {
271 points.append(QPointF(currentDistance * _horizontalScale, qQNaN()));
272 }
273 const double minAlt = _minAMSLAlt * _verticalScale;
274 points.append(QPointF(currentDistance * _horizontalScale, minAlt));
275 points.append(QPointF((currentDistance + segment->totalDistance()) * _horizontalScale, minAlt));
276 }
277}
278
279void TerrainProfile::_addCollisionPoints(FlightPathSegment* segment, double currentDistance, QList<QPointF>& points)
280{
281 if (segment->terrainCollision()) {
282 if (!points.isEmpty()) {
283 points.append(QPointF(currentDistance * _horizontalScale, qQNaN()));
284 }
285 points.append(QPointF(currentDistance * _horizontalScale, segment->coord1AMSLAlt() * _verticalScale));
286 points.append(QPointF((currentDistance + segment->totalDistance()) * _horizontalScale, segment->coord2AMSLAlt() * _verticalScale));
287 }
288}
289
290bool TerrainProfile::_shouldAddFlightProfileSegment(FlightPathSegment* segment)
291{
292 bool shouldAdd = !qIsNaN(segment->coord1AMSLAlt()) && !qIsNaN(segment->coord2AMSLAlt());
294 shouldAdd &= segment->amslTerrainHeights().count() != 0;
295 }
296 return shouldAdd;
297}
298
299bool TerrainProfile::_shouldAddMissingTerrainSegment(FlightPathSegment* segment)
300{
301 return segment->amslTerrainHeights().count() == 0;
302}
#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
double minAMSLAltitude(void) const
double maxAMSLAltitude(void) const
void recalcTerrainProfile(void)
void visualItemsReset(void)
double missionTotalDistance(void) const
QmlObjectListModel * visualItems(void)
T value(int index) const
int count() const override final
void profileChanged(void)
void componentComplete(void) final
void setMissionController(MissionController *missionController)
double visibleWidth(void) const
void pixelsPerMeterChanged(void)
Q_INVOKABLE void updateSeries(QXYSeries *terrainSeries, QXYSeries *flightSeries, QXYSeries *missingSeries, QXYSeries *collisionSeries)
void _updateSignal(void)
void visibleWidthChanged(void)
MissionController * missionController(void)
void setVisibleWidth(double visibleWidth)
void minAMSLAltChanged(void)
void maxAMSLAltChanged(void)
void missionControllerChanged(void)
FlightPathSegment * simpleFlightPathSegment(void)