QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
TransectStyleComplexItem.cc
Go to the documentation of this file.
2#include "JsonHelper.h"
3#include "MissionController.h"
4#include "QGCApplication.h"
6#include "FlightPathSegment.h"
9#include "QGC.h"
10#include "FirmwarePlugin.h"
11#include "KMLPlanDomDocument.h"
12#include "Vehicle.h"
13#include "QGCLoggingCategory.h"
14
15#include <QtCore/QJsonArray>
16
17QGC_LOGGING_CATEGORY(TransectStyleComplexItemLog, "Plan.TransectStyleComplexItem")
18
19TransectStyleComplexItem::TransectStyleComplexItem(PlanMasterController* masterController, bool flyView, QString settingsGroup)
20 : ComplexMissionItem (masterController, flyView)
21 , _cameraCalc (masterController, settingsGroup)
22 , _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/TransectStyle.SettingsGroup.json"), this))
23 , _turnAroundDistanceFact (settingsGroup, _metaDataMap[_controllerVehicle->multiRotor() ? turnAroundDistanceMultiRotorName : turnAroundDistanceName])
24 , _cameraTriggerInTurnAroundFact (settingsGroup, _metaDataMap[cameraTriggerInTurnAroundName])
25 , _hoverAndCaptureFact (settingsGroup, _metaDataMap[hoverAndCaptureName])
26 , _refly90DegreesFact (settingsGroup, _metaDataMap[refly90DegreesName])
27 , _terrainAdjustToleranceFact (settingsGroup, _metaDataMap[terrainAdjustToleranceName])
28 , _terrainAdjustMaxClimbRateFact (settingsGroup, _metaDataMap[terrainAdjustMaxClimbRateName])
29 , _terrainAdjustMaxDescentRateFact (settingsGroup, _metaDataMap[terrainAdjustMaxDescentRateName])
30{
31 _terrainPolyPathQueryTimer.setInterval(qgcApp()->runningUnitTests() ? 10 : _terrainQueryTimeoutMsecs);
32 _terrainPolyPathQueryTimer.setSingleShot(true);
33 connect(&_terrainPolyPathQueryTimer, &QTimer::timeout, this, &TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo);
34
35 // The follow is used to compress multiple recalc calls in a row to into a single call.
36 connect(this, &TransectStyleComplexItem::_updateFlightPathSegmentsSignal, this, &TransectStyleComplexItem::_updateFlightPathSegmentsDontCallDirectly, Qt::QueuedConnection);
37 qgcApp()->addCompressedSignal(QMetaMethod::fromSignal(&TransectStyleComplexItem::_updateFlightPathSegmentsSignal));
38
39 connect(&_turnAroundDistanceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
40 connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
41 connect(&_refly90DegreesFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
42 connect(&_terrainAdjustMaxClimbRateFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
43 connect(&_terrainAdjustMaxDescentRateFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
44 connect(&_terrainAdjustToleranceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
46 connect(&_cameraTriggerInTurnAroundFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
47 connect(_cameraCalc.adjustedFootprintSide(), &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
48 connect(_cameraCalc.adjustedFootprintFrontal(), &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
49 connect(_cameraCalc.distanceToSurface(), &Fact::rawValueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
51
52 connect(&_turnAroundDistanceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::complexDistanceChanged);
53 connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &TransectStyleComplexItem::complexDistanceChanged);
54 connect(&_refly90DegreesFact, &Fact::valueChanged, this, &TransectStyleComplexItem::complexDistanceChanged);
56
57 connect(&_turnAroundDistanceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::greatestDistanceToChanged);
58 connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &TransectStyleComplexItem::greatestDistanceToChanged);
59 connect(&_refly90DegreesFact, &Fact::valueChanged, this, &TransectStyleComplexItem::greatestDistanceToChanged);
61
62 connect(&_turnAroundDistanceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_setDirty);
63 connect(&_cameraTriggerInTurnAroundFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_setDirty);
64 connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_setDirty);
65 connect(&_refly90DegreesFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_setDirty);
66 connect(&_terrainAdjustMaxClimbRateFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_setDirty);
67 connect(&_terrainAdjustMaxDescentRateFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_setDirty);
68 connect(&_terrainAdjustToleranceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_setDirty);
69 connect(&_surveyAreaPolygon, &QGCMapPolygon::pathChanged, this, &TransectStyleComplexItem::_setDirty);
70
71 connect(&_surveyAreaPolygon, &QGCMapPolygon::dirtyChanged, this, &TransectStyleComplexItem::_setIfDirty);
73
75
76 connect(_cameraCalc.distanceToSurface(), &Fact::rawValueChanged, this, &TransectStyleComplexItem::_amslEntryAltChanged);
77 connect(_cameraCalc.distanceToSurface(), &Fact::rawValueChanged, this, &TransectStyleComplexItem::_amslExitAltChanged);
78 connect(_cameraCalc.distanceToSurface(), &Fact::rawValueChanged, this, &TransectStyleComplexItem::minAMSLAltitudeChanged);
79 connect(_cameraCalc.distanceToSurface(), &Fact::rawValueChanged, this, &TransectStyleComplexItem::maxAMSLAltitudeChanged);
85 connect(&_cameraCalc, &CameraCalc::distanceModeChanged, this, &TransectStyleComplexItem::_distanceModeChanged);
86 connect(&_cameraCalc, &CameraCalc::distanceModeChanged, _missionController, &MissionController::recalcTerrainProfile);
87
88 connect(&_hoverAndCaptureFact, &Fact::rawValueChanged, this, &TransectStyleComplexItem::_handleHoverAndCaptureEnabled);
89
90 // The main coordinate is aliased to the entry
92
96
97
99
100 setDirty(false);
101}
102
104{
105 if (_cameraShots != cameraShots) {
107 emit cameraShotsChanged();
108 }
109}
110
112{
113 if (!dirty) {
115 _cameraCalc.setDirty(false);
116 }
117 if (_dirty != dirty) {
118 _dirty = dirty;
119 emit dirtyChanged(_dirty);
120 }
121}
122
123void TransectStyleComplexItem::setCoordinate(const QGeoCoordinate& coordinate)
124{
125 if (!coordinate.isValid() || !_entryCoordinate.isValid() || _surveyAreaPolygon.count() < 3) {
126 return;
127 }
128
129 const double distanceMeters = _entryCoordinate.distanceTo(coordinate);
130 const double azimuthDegrees = _entryCoordinate.azimuthTo(coordinate);
131 const QList<QGeoCoordinate> vertices = _surveyAreaPolygon.coordinateList();
132
133 QList<QGeoCoordinate> translatedVertices;
134 translatedVertices.reserve(vertices.count());
135 for (const QGeoCoordinate& vertex: vertices) {
136 translatedVertices.append(vertex.atDistanceAndAzimuth(distanceMeters, azimuthDegrees));
137 }
138
139 _surveyAreaPolygon.setPath(translatedVertices);
140}
141
142void TransectStyleComplexItem::_save(QJsonObject& complexObject)
143{
144 QJsonObject innerObject;
145
146 innerObject[JsonHelper::jsonVersionKey] = 2;
147 innerObject[turnAroundDistanceName] = _turnAroundDistanceFact.rawValue().toDouble();
148 innerObject[cameraTriggerInTurnAroundName] = _cameraTriggerInTurnAroundFact.rawValue().toBool();
149 innerObject[hoverAndCaptureName] = _hoverAndCaptureFact.rawValue().toBool();
150 innerObject[refly90DegreesName] = _refly90DegreesFact.rawValue().toBool();
151 innerObject[_jsonCameraShotsKey] = _cameraShots;
152
154 innerObject[terrainAdjustToleranceName] = _terrainAdjustToleranceFact.rawValue().toDouble();
155 innerObject[terrainAdjustMaxClimbRateName] = _terrainAdjustMaxClimbRateFact.rawValue().toDouble();
156 innerObject[terrainAdjustMaxDescentRateName] = _terrainAdjustMaxDescentRateFact.rawValue().toDouble();
158 }
159
160 QJsonObject cameraCalcObject;
161 _cameraCalc.save(cameraCalcObject);
162 innerObject[_jsonCameraCalcKey] = cameraCalcObject;
163
164 QJsonValue transectPointsJson;
165
166 // Save transects polyline
167 JsonHelper::saveGeoCoordinateArray(_visualTransectPoints, false /* writeAltitude */, transectPointsJson);
168 innerObject[_jsonVisualTransectPointsKey] = transectPointsJson;
169
170 // Save the interal mission items
171 QJsonArray missionItemsJsonArray;
172 QObject* missionItemParent = new QObject();
173 QList<MissionItem*> missionItems;
174 appendMissionItems(missionItems, missionItemParent);
175 for (const MissionItem* missionItem: missionItems) {
176 QJsonObject missionItemJsonObject;
177 missionItem->save(missionItemJsonObject);
178 missionItemsJsonArray.append(missionItemJsonObject);
179 }
180 missionItemParent->deleteLater();
181 innerObject[_jsonItemsKey] = missionItemsJsonArray;
182
183 complexObject[_jsonTransectStyleComplexItemKey] = innerObject;
184}
185
194
195bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, bool forPresets, QString& errorString)
196{
197 QList<JsonHelper::KeyValidateInfo> keyInfoList = {
198 { _jsonTransectStyleComplexItemKey, QJsonValue::Object, true },
199 };
200 if (!JsonHelper::validateKeys(complexObject, keyInfoList, errorString)) {
201 return false;
202 }
203
204 // The TransectStyleComplexItem is a sub-object of the main complex item object
205 QJsonObject innerObject = complexObject[_jsonTransectStyleComplexItemKey].toObject();
206
207 int version = 0;
208 bool v1FollowTerrain = false;
209 if (innerObject.contains(JsonHelper::jsonVersionKey)) {
210 version = innerObject[JsonHelper::jsonVersionKey].toInt();
211 }
212 if (version == 0) {
213 // There are really old versions without version stamp
214 version = 1;
215 }
216 if (version == 1) {
217 // Version 1->2 differences
218 // - _jsonCameraShotsKey was optional in V1 since is was added later
219 // - _jsonTerrainFollowKeyDeprecated replaced by CameraCalc::distanceMode
220 if (!innerObject.contains(_jsonCameraShotsKey)) {
221 innerObject[_jsonCameraShotsKey] = 0;
222 }
223 v1FollowTerrain = innerObject[_jsonTerrainFollowKeyDeprecated].toBool();
224 innerObject.remove(_jsonTerrainFollowKeyDeprecated);
225 version = 2;
226 }
227 if (version != 2) {
228 errorString = tr("TransectStyleComplexItem version %2 not supported").arg(version);
229 return false;
230 }
231
232 QList<JsonHelper::KeyValidateInfo> innerKeyInfoList = {
233 { JsonHelper::jsonVersionKey, QJsonValue::Double, true },
234 { turnAroundDistanceName, QJsonValue::Double, true },
235 { cameraTriggerInTurnAroundName, QJsonValue::Bool, true },
236 { hoverAndCaptureName, QJsonValue::Bool, true },
237 { refly90DegreesName, QJsonValue::Bool, true },
238 { _jsonCameraCalcKey, QJsonValue::Object, true },
239 { _jsonVisualTransectPointsKey, QJsonValue::Array, !forPresets },
240 { _jsonItemsKey, QJsonValue::Array, !forPresets },
241 { _jsonCameraShotsKey, QJsonValue::Double, true },
242 };
243 if (!JsonHelper::validateKeys(innerObject, innerKeyInfoList, errorString)) {
244 return false;
245 }
246
247 if (!forPresets) {
248 // Load visual transect points
250 return false;
251 }
252 _entryCoordinate = _visualTransectPoints.count() ? _visualTransectPoints.first().value<QGeoCoordinate>() : QGeoCoordinate();
253 _exitCoordinate = _visualTransectPoints.count() ? _visualTransectPoints.last().value<QGeoCoordinate>() : QGeoCoordinate();
254 _isIncomplete = false;
255
256 // Load generated mission items
257 _loadedMissionItemsParent = new QObject(this);
258 QJsonArray missionItemsJsonArray = innerObject[_jsonItemsKey].toArray();
259 for (const QJsonValue missionItemJson: missionItemsJsonArray) {
261 if (!missionItem->load(missionItemJson.toObject(), 0 /* sequenceNumber */, errorString)) {
262 _loadedMissionItemsParent->deleteLater();
264 return false;
265 }
266 _loadedMissionItems.append(missionItem);
267 }
268 }
269
270 // Load CameraCalc data
271 if (!_cameraCalc.load(innerObject[_jsonCameraCalcKey].toObject(), v1FollowTerrain, errorString, forPresets)) {
272 return false;
273 }
274
275 // Load TransectStyleComplexItem individual values
276 _turnAroundDistanceFact.setRawValue (innerObject[turnAroundDistanceName].toDouble());
277 _cameraTriggerInTurnAroundFact.setRawValue (innerObject[cameraTriggerInTurnAroundName].toBool());
278 _hoverAndCaptureFact.setRawValue (innerObject[hoverAndCaptureName].toBool());
279 _refly90DegreesFact.setRawValue (innerObject[refly90DegreesName].toBool());
280
281 // These two keys where not included in initial implementation so they are optional. Without them the values will be
282 // incorrect when loaded though.
283 if (innerObject.contains(_jsonCameraShotsKey)) {
284 _cameraShots = innerObject[_jsonCameraShotsKey].toInt();
285 }
286
288 QList<JsonHelper::KeyValidateInfo> followTerrainKeyInfoList = {
289 { terrainAdjustToleranceName, QJsonValue::Double, true },
290 { terrainAdjustMaxClimbRateName, QJsonValue::Double, true },
291 { terrainAdjustMaxDescentRateName, QJsonValue::Double, true },
292 { _jsonTerrainFlightSpeed, QJsonValue::Double, false }, // Not required since it was missing from initial implementation
293 };
294 if (!JsonHelper::validateKeys(innerObject, followTerrainKeyInfoList, errorString)) {
295 return false;
296 }
297
298 _terrainAdjustToleranceFact.setRawValue (innerObject[terrainAdjustToleranceName].toDouble());
299 _terrainAdjustMaxClimbRateFact.setRawValue (innerObject[terrainAdjustMaxClimbRateName].toDouble());
300 _terrainAdjustMaxDescentRateFact.setRawValue (innerObject[terrainAdjustMaxDescentRateName].toDouble());
301 if (innerObject.contains(_jsonTerrainFlightSpeed)) {
302 _vehicleSpeed = innerObject[_jsonTerrainFlightSpeed].toDouble();
303 }
304
305 if (!forPresets) {
306 // We have to grovel through mission items to determine min/max alt
307 _minAMSLAltitude = qQNaN();
308 _maxAMSLAltitude = qQNaN();
309 for (const MissionItem* missionItem: _loadedMissionItems) {
311 if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) {
312 _minAMSLAltitude = std::fmin(_minAMSLAltitude, missionItem->param7());
313 _maxAMSLAltitude = std::fmax(_maxAMSLAltitude, missionItem->param7());
314 }
315 }
316 }
317 }
318
319 if (!forPresets) {
321 // Terrain frame requires terrain data in order to know AMSL coordinate heights for each mission item
322 _queryMissionItemCoordHeights();
323 } else {
329 }
330 }
331
332 return true;
333}
334
335double TransectStyleComplexItem::greatestDistanceTo(const QGeoCoordinate &other) const
336{
337 double greatestDistance = 0.0;
338 for (int i=0; i<_visualTransectPoints.count(); i++) {
339 QGeoCoordinate vertex = _visualTransectPoints[i].value<QGeoCoordinate>();
340 double distance = vertex.distanceTo(other);
341 if (distance > greatestDistance) {
342 greatestDistance = distance;
343 }
344 }
345
346 return greatestDistance;
347}
348
350{
352 if (!QGC::fuzzyCompare(_vehicleSpeed, missionFlightStatus.vehicleSpeed)) {
353 _vehicleSpeed = missionFlightStatus.vehicleSpeed;
354 // Vehicle speed change affects max climb/descent rates calcs for terrain so we need to re-adjust
357 }
358}
359
361{
362 setDirty(true);
363}
364
366{
367 if (dirty) {
368 setDirty(true);
369 }
370}
371
377
379{
380 return _surveyAreaPolygon.area();
381}
382
384{
385 return _turnAroundDistance() > 0;
386}
387
389{
390 return _turnAroundDistanceFact.rawValue().toDouble();
391}
392
397
399{
400 if (_ignoreRecalc) {
401 return;
402 }
403
404 _transects.clear();
405 _rgPathHeightInfo.clear();
407
409
411
412 switch (_cameraCalc.distanceMode()) {
415 qCWarning(TransectStyleComplexItemLog) << "Internal Error: _rebuildTransects - invalid _cameraCalc.distanceMode()" << _cameraCalc.distanceMode();
416 return;
420 // Terrain height not needed to calculate path, as TerrainFrame specifies a fixed altitude over terrain, doesn't need to know the actual terrain height
421 // so vehicle is responsible for having or not this altitude calculation, so we can build the flight path right away.
422 _buildFlightPathCoordInfoFromTransects();
423 break;
425 // Query the terrain data. Once available flight path will be calculated, as on this mode QGC actually calculates the individual altitude for each waypoint
426 // having into account terrain data.
427 _queryTransectsPathHeightInfo();
428 break;
429 }
430
431 // Calc bounding cube
432 double north = 0.0;
433 double south = 180.0;
434 double east = 0.0;
435 double west = 360.0;
436 double bottom = 100000.;
437 double top = 0.;
438 // Generate the visuals transect representation
439 _visualTransectPoints.clear();
440 for (const QList<CoordInfo_t>& transect: _transects) {
441 for (const CoordInfo_t& coordInfo: transect) {
442 _visualTransectPoints.append(QVariant::fromValue(coordInfo.coord));
443 double lat = coordInfo.coord.latitude() + 90.0;
444 double lon = coordInfo.coord.longitude() + 180.0;
445 north = fmax(north, lat);
446 south = fmin(south, lat);
447 east = fmax(east, lon);
448 west = fmin(west, lon);
449 bottom = fmin(bottom, coordInfo.coord.altitude());
450 top = fmax(top, coordInfo.coord.altitude());
451 }
452 }
453 //-- Update bounding cube for airspace management control
455 QGeoCoordinate(north - 90.0, west - 180.0, bottom),
456 QGeoCoordinate(south - 90.0, east - 180.0, top)));
458
459 _entryCoordinate = _visualTransectPoints.count() ? _visualTransectPoints.first().value<QGeoCoordinate>() : QGeoCoordinate();
460 _exitCoordinate = _visualTransectPoints.count() ? _visualTransectPoints.last().value<QGeoCoordinate>() : QGeoCoordinate();
462
463 if (_isIncomplete) {
464 _isIncomplete = false;
465 emit isIncompleteChanged();
466 }
467
470
474
477
481}
482
483void TransectStyleComplexItem::_segmentTerrainCollisionChanged(bool terrainCollision)
484{
487}
488
489// Never call this method directly. If you want to update the flight segments you emit _updateFlightPathSegmentsSignal()
490void TransectStyleComplexItem::_updateFlightPathSegmentsDontCallDirectly(void)
491{
494 emit terrainCollisionChanged(false);
496 }
497
500
501 switch (_cameraCalc.distanceMode()) {
504 qCWarning(TransectStyleComplexItemLog) << "Internal Error: _updateFlightPathSegmentsDontCallDirectly - invalid _cameraCalc.distanceMode()" << _cameraCalc.distanceMode();
505 return;
508 {
509 // Since we aren't following terrain all the transects are at the same height. We can use _visualTransectPoints to build the
510 // flight path segments.
511 QGeoCoordinate prevCoord;
512 double surveyAlt = amslEntryAlt();
513 for (const QVariant& varCoord: _visualTransectPoints) {
514 QGeoCoordinate thisCoord = varCoord.value<QGeoCoordinate>();
515 if (prevCoord.isValid()) {
516 _appendFlightPathSegment(FlightPathSegment::SegmentTypeGeneric, prevCoord, surveyAlt, thisCoord, surveyAlt);
517 }
518 prevCoord = thisCoord;
519 }
520 }
521 break;
525 // Build segments from loaded mission item data
526 QGeoCoordinate prevCoord = QGeoCoordinate();
527 double prevAlt = 0;
528 for (const MissionItem* missionItem: _loadedMissionItems) {
529 if (missionItem->command() == MAV_CMD_NAV_WAYPOINT || missionItem->command() == MAV_CMD_CONDITION_GATE) {
530 if (prevCoord.isValid()) {
531 _appendFlightPathSegment(FlightPathSegment::SegmentTypeGeneric, prevCoord, prevAlt, missionItem->coordinate(), missionItem->param7());
532 }
533 prevCoord = missionItem->coordinate();
534 prevAlt = missionItem->param7();
535 }
536 }
537 } else {
538 // We are either:
539 // - Working from live transect data of an interactive editing session
540 // - Working from loaded mission items which have had terrain heights queried for
541 // In both cases _rgFlightPathCoordInfo will be set up for use
542 if (_rgFlightPathCoordInfo.count()) {
544 for (int i=0; i<_rgFlightPathCoordInfo.count() - 1; i++) {
545 const QGeoCoordinate& fromCoord = _rgFlightPathCoordInfo[i].coord;
546 const QGeoCoordinate& toCoord = _rgFlightPathCoordInfo[i+1].coord;
547 _appendFlightPathSegment(segmentType, fromCoord, fromCoord.altitude(), toCoord, toCoord.altitude());
548 }
549 }
550 }
551 break;
552 }
553
555
557 emit terrainCollisionChanged(true);
559 }
560
562}
563
564void TransectStyleComplexItem::_queryTransectsPathHeightInfo(void)
565{
566 _rgPathHeightInfo.clear();
568
569 if (_transects.count()) {
570 // We don't actually send the query until this timer times out. This way we only send
571 // the latest request if we get a bunch in a row.
572 _terrainPolyPathQueryTimer.start();
573 }
574}
575
576void TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo(void)
577{
578 qCDebug(TransectStyleComplexItemLog) << "_reallyQueryTransectsPathHeightInfo";
579
580 // Clear any previous queries
581 if (_currentTerrainPolyPathQuery) {
582 disconnect(_currentTerrainPolyPathQuery);
583 _currentTerrainPolyPathQuery = nullptr;
584 }
585 if (_currentTerrainAtCoordinateQuery) {
586 disconnect(_currentTerrainAtCoordinateQuery);
587 _currentTerrainAtCoordinateQuery = nullptr;
588 }
589
590 // Append all transects into a single PolyPath query
591 QList<QGeoCoordinate> transectPoints;
592 for (const QList<CoordInfo_t>& transect: _transects) {
593 for (const CoordInfo_t& coordInfo: transect) {
594 transectPoints.append(coordInfo.coord);
595 }
596 }
597
598 if (transectPoints.count() > 1) {
599 _currentTerrainPolyPathQuery = new TerrainPolyPathQuery(true /* autoDelete */);
601 _currentTerrainPolyPathQuery->requestData(transectPoints);
602 }
603}
604
605void TransectStyleComplexItem::_queryMissionItemCoordHeights(void)
606{
607 qCDebug(TransectStyleComplexItemLog) << "_queryMissionItemCoordHeights";
608
610
611 if (_currentTerrainAtCoordinateQuery) {
612 qCWarning(TransectStyleComplexItemLog) << "Internal error: _queryMissionItemCoordHeights called multiple times";
613 // We are already waiting on another query. We don't care about those results any more.
614 disconnect(_currentTerrainPolyPathQuery);
615 _currentTerrainPolyPathQuery = nullptr;
616 }
617
618 // We need terrain heights below each mission item we fly through which is terrain frame
619 for (const MissionItem* missionItem: _loadedMissionItems) {
620 if (missionItem->frame() == MAV_FRAME_GLOBAL_TERRAIN_ALT) {
622 if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) {
623 _rgFlyThroughMissionItemCoords.append(missionItem->coordinate());
624 }
625 }
626 }
627
628 if (_rgFlyThroughMissionItemCoords.count()) {
629 _currentTerrainAtCoordinateQuery = new TerrainAtCoordinateQuery(true /* autoDelete */);
631 _currentTerrainAtCoordinateQuery->requestData(_rgFlyThroughMissionItemCoords);
632 }
633}
634
635void TransectStyleComplexItem::_polyPathTerrainData(bool success, const QList<TerrainPathQuery::PathHeightInfo_t>& rgPathHeightInfo)
636{
637 qCDebug(TransectStyleComplexItemLog) << "_polyPathTerrainData" << success;
638
639 _rgPathHeightInfo.clear();
641
642 if (success) {
643 // Now that we have terrain data we can adjust
644 _rgPathHeightInfo = rgPathHeightInfo;
645 _adjustForAvailableTerrainData();
647 }
648 _currentTerrainPolyPathQuery = nullptr;
649}
650
651void TransectStyleComplexItem::_missionItemCoordTerrainData(bool success, QList<double> heights)
652{
653 qCDebug(TransectStyleComplexItemLog) << "_polyPathTerrainData" << success;
654
655 _rgPathHeightInfo.clear();
657
658 if (success) {
659 // Now that we have terrain data we can adjust
661 _adjustForAvailableTerrainData();
663 }
664 _currentTerrainPolyPathQuery = nullptr;
665}
666
668{
669 bool terrainReady = false;
671 if (_loadedMissionItems.count()) {
672 // We have loaded mission items. Everything is ready to go.
673 terrainReady = true;
674 } else {
675 // Survey is currently being designed. We aren't ready if we don't have terrain heights yet.
676 terrainReady = _rgPathHeightInfo.count();
677 }
678 } else {
679 // Not following terrain so always ready on terrain
680 terrainReady = true;
681 }
682 bool polygonNotReady = !_surveyAreaPolygon.isValid();
683 return (polygonNotReady || _wizardMode) ?
685 (terrainReady ? ReadyForSave : NotReadyForSaveTerrain);
686}
687
688void TransectStyleComplexItem::_adjustForAvailableTerrainData(void)
689{
690 switch (_cameraCalc.distanceMode()) {
693 qCWarning(TransectStyleComplexItemLog) << "Internal Error: _adjustForAvailableTerrainData - invalid _cameraCalc.distanceMode()" << _cameraCalc.distanceMode();
694 return;
697 // No additional work needed
698 return;
700 _buildFlightPathCoordInfoFromPathHeightInfoForCalcAboveTerrain();
701 _adjustForMaxRates();
702 _adjustForTolerance();
703 _minAMSLAltitude = qQNaN();
704 _maxAMSLAltitude = qQNaN();
705 for (const CoordInfo_t& coordInfo: _rgFlightPathCoordInfo) {
706 _minAMSLAltitude = std::fmin(_minAMSLAltitude, coordInfo.coord.altitude());
707 _maxAMSLAltitude = std::fmax(_maxAMSLAltitude, coordInfo.coord.altitude());
708 }
710 break;
712 if (_loadedMissionItems.count()) {
713 _buildFlightPathCoordInfoFromMissionItems();
714 } else {
715 _buildFlightPathCoordInfoFromPathHeightInfoForTerrainFrame();
716 }
717 break;
718 }
719
725}
726
729double TransectStyleComplexItem::_altitudeBetweenCoords(const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord, double percentTowardsTo)
730{
731 double fromAlt = fromCoord.altitude();
732 double toAlt = toCoord.altitude();
733 double altDiff = toAlt - fromAlt;
734 return fromAlt + (altDiff * percentTowardsTo);
735}
736
742int TransectStyleComplexItem::_maxPathHeight(const TerrainPathQuery::PathHeightInfo_t& pathHeightInfo, int fromIndex, int toIndex, double& maxHeight)
743{
744 maxHeight = qQNaN();
745
746 if (toIndex - fromIndex < 2) {
747 return -1;
748 }
749
750 fromIndex++;
751 toIndex--;
752
753 int maxIndex = fromIndex;
754 maxHeight = pathHeightInfo.heights[fromIndex];
755
756 for (int i=fromIndex; i<=toIndex; i++) {
757 if (pathHeightInfo.heights[i] > maxHeight) {
758 maxIndex = i;
759 maxHeight = pathHeightInfo.heights[i];
760 }
761 }
762
763 return maxIndex;
764}
765
766void TransectStyleComplexItem::_adjustForMaxRates(void)
767{
768 double maxClimbRate = _terrainAdjustMaxClimbRateFact.rawValue().toDouble();
769 double maxDescentRate = _terrainAdjustMaxDescentRateFact.rawValue().toDouble();
770 double flightSpeed = _vehicleSpeed;
771
772 if (qIsNaN(flightSpeed) || (maxClimbRate == 0 && maxDescentRate == 0)) {
773 if (qIsNaN(flightSpeed)) {
774 qWarning() << "TransectStyleComplexItem::_adjustForMaxRates called with flightSpeed = NaN";
775 }
776 return;
777 }
778 if (maxClimbRate <= 0 && maxDescentRate <= 0) {
779 return;
780 }
781
782 if (maxClimbRate > 0) {
783 bool climbRateAdjusted;
784 do {
785 //qDebug() << "climb rate pass";
786 climbRateAdjusted = false;
787 for (int i=0; i<_rgFlightPathCoordInfo.count() - 1; i++) {
788 QGeoCoordinate& fromCoord = _rgFlightPathCoordInfo[i].coord;
789 QGeoCoordinate& toCoord = _rgFlightPathCoordInfo[i+1].coord;
790
791 double altDifference = toCoord.altitude() - fromCoord.altitude();
792 double distance = fromCoord.distanceTo(toCoord);
793 double seconds = distance / flightSpeed;
794 double climbRate = altDifference / seconds;
795
796 //qDebug() << QString("Index:%1 altDifference:%2 distance:%3 seconds:%4 climbRate:%5").arg(i).arg(altDifference).arg(distance).arg(seconds).arg(climbRate);
797
798 if (climbRate > 0 && climbRate - maxClimbRate > 0.1) {
799 double maxAltitudeDelta = maxClimbRate * seconds;
800 fromCoord.setAltitude(toCoord.altitude() - maxAltitudeDelta);
801 //qDebug() << "Adjusting";
802 climbRateAdjusted = true;
803 }
804 }
805 } while (climbRateAdjusted);
806 }
807
808 if (maxDescentRate > 0) {
809 bool descentRateAdjusted;
810 maxDescentRate = -maxDescentRate;
811 do {
812 //qDebug() << "descent rate pass";
813 descentRateAdjusted = false;
814 for (int i=0; i<_rgFlightPathCoordInfo.count() - 1; i++) {
815 QGeoCoordinate& fromCoord = _rgFlightPathCoordInfo[i].coord;
816 QGeoCoordinate& toCoord = _rgFlightPathCoordInfo[i+1].coord;
817
818 double altDifference = toCoord.altitude() - fromCoord.altitude();
819 double distance = fromCoord.distanceTo(toCoord);
820 double seconds = distance / flightSpeed;
821 double descentRate = altDifference / seconds;
822
823 //qDebug() << QString("Index:%1 altDifference:%2 distance:%3 seconds:%4 descentRate:%5").arg(i).arg(altDifference).arg(distance).arg(seconds).arg(descentRate);
824
825 if (descentRate < 0 && descentRate - maxDescentRate < -0.1) {
826 double maxAltitudeDelta = maxDescentRate * seconds;
827 toCoord.setAltitude(fromCoord.altitude() + maxAltitudeDelta);
828 //qDebug() << "Adjusting";
829 descentRateAdjusted = true;
830 }
831 }
832 } while (descentRateAdjusted);
833 }
834}
835
836void TransectStyleComplexItem::_adjustForTolerance(void)
837{
838 QList<CoordInfo_t> adjustedFlightPath;
839 double tolerance = _terrainAdjustToleranceFact.rawValue().toDouble();
840 CoordInfo_t& lastCoordInfo = _rgFlightPathCoordInfo.first();
841
842 adjustedFlightPath.append(lastCoordInfo);
843
844 int coordIndex = 1;
845 while (coordIndex < _rgFlightPathCoordInfo.count()) {
846 // Walk forward until we fall out of tolerence. When we fall out of tolerance add that point.
847 // We always add non-interstitial points no matter what.
848 const CoordInfo_t& nextCoordInfo = _rgFlightPathCoordInfo[coordIndex];
849 if (nextCoordInfo.coordType != CoordTypeInteriorTerrainAdded || qAbs(lastCoordInfo.coord.altitude() - nextCoordInfo.coord.altitude()) > tolerance) {
850 adjustedFlightPath.append(nextCoordInfo);
851 lastCoordInfo = nextCoordInfo;
852 }
853 coordIndex++;
854 }
855
856 _rgFlightPathCoordInfo = adjustedFlightPath;
857}
858
859void TransectStyleComplexItem::_buildFlightPathCoordInfoFromTransects(void)
860{
862
863 double distanceToSurface = _cameraCalc.distanceToSurface()->rawValue().toDouble();
864
866 for (int transectIndex=0; transectIndex<_transects.count(); transectIndex++) {
867 const QList<CoordInfo_t>& transect = _transects[transectIndex];
868
869 for (int transectCoordIndex=0; transectCoordIndex<transect.count() - 1; transectCoordIndex++) {
870 CoordInfo_t fromCoordInfo = transect[transectCoordIndex];
871 CoordInfo_t toCoordInfo = transect[transectCoordIndex+1];
872
873 fromCoordInfo.coord.setAltitude(distanceToSurface);
874 toCoordInfo.coord.setAltitude(distanceToSurface);
875
876 if (transectCoordIndex == 0) {
877 _rgFlightPathCoordInfo.append(fromCoordInfo);
878 }
879 _rgFlightPathCoordInfo.append(toCoordInfo);
880 }
881 }
882}
883
884void TransectStyleComplexItem::_buildFlightPathCoordInfoFromPathHeightInfoForCalcAboveTerrain(void)
885{
887
888 if (_rgPathHeightInfo.count() == 0) {
889 qCWarning(TransectStyleComplexItemLog) << "TransectStyleComplexItem::_buildFlightPathCoordInfoFromPathHeightInfo terrain height needed but _rgPathHeightInfo.count() == 0";
890 return;
891 }
892
893 double distanceToSurface = _cameraCalc.distanceToSurface()->rawValue().toDouble();
894
896 int pathHeightIndex = 0;
897 for (int transectIndex=0; transectIndex<_transects.count(); transectIndex++) {
898 const QList<CoordInfo_t>& transect = _transects[transectIndex];
899
900 // Build flight path for transect
901 for (int transectCoordIndex=0; transectCoordIndex<transect.count() - 1; transectCoordIndex++) {
902 CoordInfo_t fromCoordInfo = transect[transectCoordIndex];
903 CoordInfo_t toCoordInfo = transect[transectCoordIndex+1];
904
905 const auto& pathHeightInfo = _rgPathHeightInfo[pathHeightIndex++];
906
907 fromCoordInfo.coord.setAltitude(distanceToSurface + pathHeightInfo.heights.first());
908 toCoordInfo.coord.setAltitude(distanceToSurface + pathHeightInfo.heights.last());
909
910 if (transectCoordIndex == 0) {
911 _rgFlightPathCoordInfo.append(fromCoordInfo);
912 }
913
914 // Add interstitial points at max resolution of our terrain data
915 int cHeights = pathHeightInfo.heights.count();
916
917 double azimuth = fromCoordInfo.coord.azimuthTo(toCoordInfo.coord);
918 double distance = fromCoordInfo.coord.distanceTo(toCoordInfo.coord);
919
920 for (int interstitialIndex=1; interstitialIndex<cHeights - 1; interstitialIndex++) {
921 double interstitialTerrainHeight = pathHeightInfo.heights[interstitialIndex];
922 double percentTowardsTo = (1.0 / (cHeights - 1)) * interstitialIndex;
923
924 CoordInfo_t interstitialCoordInfo;
925 interstitialCoordInfo.coordType = CoordTypeInteriorTerrainAdded;
926 interstitialCoordInfo.coord = fromCoordInfo.coord.atDistanceAndAzimuth(distance * percentTowardsTo, azimuth);
927 interstitialCoordInfo.coord.setAltitude(interstitialTerrainHeight + distanceToSurface);
928
929 _rgFlightPathCoordInfo.append(interstitialCoordInfo);
930 }
931
932 _rgFlightPathCoordInfo.append(toCoordInfo);
933 }
934
935 // Build flight path for turnaround
936 // Add terrain interstitial points to the turn segment if not the last transect
937 if (transectIndex != _transects.count() - 1) {
938 const auto& pathHeightInfo = _rgPathHeightInfo[pathHeightIndex++];
939
940 int cHeights = pathHeightInfo.heights.count();
941
942 CoordInfo_t fromCoordInfo = _transects[transectIndex].last();
943 CoordInfo_t toCoordInfo = _transects[transectIndex+1].first();
944
945 double azimuth = fromCoordInfo.coord.azimuthTo(toCoordInfo.coord);
946 double distance = fromCoordInfo.coord.distanceTo(toCoordInfo.coord);
947
948 for (int interstitialIndex=1; interstitialIndex<cHeights - 1; interstitialIndex++) {
949 double interstitialTerrainHeight = pathHeightInfo.heights[interstitialIndex];
950 double percentTowardsTo = (1.0 / (cHeights - 1)) * interstitialIndex;
951
952 CoordInfo_t interstitialCoordInfo;
953 interstitialCoordInfo.coordType = CoordTypeInteriorTerrainAdded;
954 interstitialCoordInfo.coord = fromCoordInfo.coord.atDistanceAndAzimuth(distance * percentTowardsTo, azimuth);
955 interstitialCoordInfo.coord.setAltitude(interstitialTerrainHeight + distanceToSurface);
956
957 _rgFlightPathCoordInfo.append(interstitialCoordInfo);
958 }
959 }
960 }
961}
962
963void TransectStyleComplexItem::_buildFlightPathCoordInfoFromPathHeightInfoForTerrainFrame(void)
964{
966
967 if (_rgPathHeightInfo.count() == 0) {
968 qCWarning(TransectStyleComplexItemLog) << "TransectStyleComplexItem::_buildFlightPathCoordInfoFromPathHeightInfoForTerrainFrame terrain height needed but _rgPathHeightInfo.count() == 0";
969 return;
970 }
971
972 double distanceToSurface = _cameraCalc.distanceToSurface()->rawValue().toDouble();
973
975 int pathHeightIndex = 0;
976 for (int transectIndex=0; transectIndex<_transects.count(); transectIndex++) {
977 const QList<CoordInfo_t>& transect = _transects[transectIndex];
978
979 // Build flight path for transect
980 for (int transectCoordIndex=0; transectCoordIndex<transect.count() - 1; transectCoordIndex++) {
981 CoordInfo_t fromCoordInfo = transect[transectCoordIndex];
982 CoordInfo_t toCoordInfo = transect[transectCoordIndex+1];
983
984 const auto& pathHeightInfo = _rgPathHeightInfo[pathHeightIndex++];
985
986 fromCoordInfo.coord.setAltitude(distanceToSurface + pathHeightInfo.heights.first());
987 toCoordInfo.coord.setAltitude(distanceToSurface + pathHeightInfo.heights.last());
988
989 if (transectCoordIndex == 0) {
990 _rgFlightPathCoordInfo.append(fromCoordInfo);
991 }
992 _rgFlightPathCoordInfo.append(toCoordInfo);
993 }
994
995 // Even though we don't use it we still have path heights for the turnaround segment
996 pathHeightIndex++;
997 }
998}
999
1000void TransectStyleComplexItem::_buildFlightPathCoordInfoFromMissionItems(void)
1001{
1003
1005 qCWarning(TransectStyleComplexItemLog) << "_buildFlightPathCoordInfoFromMissionItems - terrain height needed but _rgFlyThroughMissionItemCoordsTerrainHeights.count() == 0";
1006 return;
1007 }
1009 qCWarning(TransectStyleComplexItemLog) << "_buildFlightPathCoordInfoFromMissionItems - _rgFlyThroughMissionItemCoordsTerrainHeights.count() != _rgFlyThroughMissionItemCoords.count()";
1010 return;
1011 }
1012 if (_rgFlyThroughMissionItemCoords.count() < 2) {
1013 qCWarning(TransectStyleComplexItemLog) << "_buildFlightPathCoordInfoFromMissionItems - rgFlyThroughMissionItemCoords.count() < 2";
1014 return;
1015 }
1016
1017 _rgFlightPathCoordInfo.clear();
1018 for (int i=0; i<_rgFlyThroughMissionItemCoords.count() - 1; i++) {
1019 double heightAtCoord = _rgFlyThroughMissionItemCoordsTerrainHeights[i];
1020
1021 // Since we are working from loading mission items the CoordInfo_t.coordType doesn't really matter
1022 CoordInfo_t fromCoordInfo = { _rgFlyThroughMissionItemCoords[i], CoordTypeInterior };
1023 CoordInfo_t toCoordInfo = { _rgFlyThroughMissionItemCoords[i+1], CoordTypeInterior };
1024
1025 fromCoordInfo.coord.setAltitude(fromCoordInfo.coord.altitude() + heightAtCoord);
1026 toCoordInfo.coord.setAltitude(toCoordInfo.coord.altitude() + heightAtCoord);
1027
1028 _rgFlightPathCoordInfo.append(fromCoordInfo);
1029 }
1030}
1031
1033{
1034 if (_loadedMissionItems.count()) {
1035 // We have stored mission items, just use those
1036 return _sequenceNumber + _loadedMissionItems.count() - 1;
1037 } else if (_transects.count() == 0) {
1038 // Polygon has not yet been set so we just return back a one item complex item for now
1039 return _sequenceNumber;
1040 } else if (_rgFlightPathCoordInfo.count()) {
1041 int itemCount = 0;
1042 BuildMissionItemsState_t buildState = _buildMissionItemsState();
1043
1044 // Important Note: This code should match the logic in _buildAndAppendMissionItems
1045 for (int coordIndex=0; coordIndex<_rgFlightPathCoordInfo.count(); coordIndex++) {
1046 const CoordInfo_t& coordInfo = _rgFlightPathCoordInfo[coordIndex];
1047 switch (coordInfo.coordType) {
1048 case CoordTypeInterior:
1050 itemCount++; // Waypoint only
1051 break;
1053 {
1054 bool firstEntryTurnaround = coordIndex == 0;
1055 bool lastExitTurnaround = coordIndex == _rgFlightPathCoordInfo.count() - 1;
1056 if (buildState.addTriggerAtFirstAndLastPoint && (firstEntryTurnaround || lastExitTurnaround)) {
1057 itemCount += 2; // Waypoint + camera trigger
1058 } else {
1059 itemCount++; // Waypoint only
1060 }
1061 }
1062 break;
1064 itemCount += 2; // Waypoint + camera trigger
1065 break;
1067 if (triggerCamera()) {
1068 itemCount += 2; // Waypoint + camera trigger
1069 } else {
1070 itemCount++; // Waypoint only
1071 }
1072 break;
1074 bool lastSurveyExit = coordIndex == _rgFlightPathCoordInfo.count() - 1;
1075 if (triggerCamera()) {
1076 if (hoverAndCaptureEnabled()) {
1077 itemCount += 2; // Waypoint + camera trigger
1078 } else if (buildState.addTriggerAtFirstAndLastPoint && !buildState.hasTurnarounds && lastSurveyExit) {
1079 itemCount += 2; // Waypoint + camera trigger
1080 } else if (buildState.imagesInTurnaround) {
1081 itemCount++; // Waypoint only
1082 } else {
1083 itemCount += 2; // Waypoint + camera trigger
1084 }
1085 } else {
1086 itemCount++; // Waypoint only
1087 }
1088 break;
1089 }
1090 }
1091
1092 return _sequenceNumber + itemCount - 1;
1093 } else {
1094 // We can end up hear if we are follow terrain and the flight path isn't ready yet. So we just return an inaccurate number until
1095 // we know the real one.
1096 int itemCount = 0;
1097
1098 for (const QList<CoordInfo_t>& rgCoordInfo: _transects) {
1099 itemCount += rgCoordInfo.count();
1100 }
1101
1102 return _sequenceNumber + itemCount - 1;
1103 }
1104}
1105
1106void TransectStyleComplexItem::_distanceModeChanged(int distanceMode)
1107{
1109 _refly90DegreesFact.setRawValue(false);
1110 _hoverAndCaptureFact.setRawValue(false);
1111 }
1112}
1113
1114void TransectStyleComplexItem::_handleHoverAndCaptureEnabled(QVariant enabled)
1115{
1116 if (enabled.toBool() && _cameraTriggerInTurnAroundFact.rawValue().toBool()) {
1117 _cameraTriggerInTurnAroundFact.setRawValue(false);
1118 }
1119}
1120
1121void TransectStyleComplexItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
1122{
1123 if (_loadedMissionItems.count()) {
1124 // We have mission items from the loaded plan, use those
1125 _appendLoadedMissionItems(items, missionItemParent);
1126 } else {
1127 // Build the mission items on the fly
1128 _buildAndAppendMissionItems(items, missionItemParent);
1129 }
1130}
1131
1132void TransectStyleComplexItem::_appendWaypoint(QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum, MAV_FRAME mavFrame, float holdTime, const QGeoCoordinate& coordinate)
1133{
1135
1136 MissionItem* item = new MissionItem(seqNum++,
1137 MAV_CMD_NAV_WAYPOINT,
1138 mavFrame,
1139 holdTime,
1140 0.0, // No acceptance radius specified
1141 0.0, // Pass through waypoint
1142 std::numeric_limits<double>::quiet_NaN(), // Yaw unchanged
1143 coordinate.latitude(),
1144 coordinate.longitude(),
1145 altitude,
1146 true, // autoContinue
1147 false, // isCurrentItem
1148 missionItemParent);
1149 items.append(item);
1150}
1151
1152void TransectStyleComplexItem::_appendSinglePhotoCapture(QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum)
1153{
1154 MissionItem* item = new MissionItem(seqNum++,
1155 MAV_CMD_IMAGE_START_CAPTURE,
1156 MAV_FRAME_MISSION,
1157 0, // Reserved (Set to 0)
1158 0, // Interval (none)
1159 1, // Take 1 photo
1160 0, // No sequence number specified
1161 qQNaN(), qQNaN(), qQNaN(), // param 5-7 reserved
1162 true, // autoContinue
1163 false, // isCurrentItem
1164 missionItemParent);
1165 items.append(item);
1166}
1167
1168void TransectStyleComplexItem::_appendConditionGate(QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum, MAV_FRAME mavFrame, const QGeoCoordinate& coordinate)
1169{
1171
1172 MissionItem* item = new MissionItem(seqNum++,
1173 MAV_CMD_CONDITION_GATE,
1174 mavFrame,
1175 0, // Gate is orthogonal to path
1176 1, // Use altitude
1177 0, 0, // Param 3-4 ignored
1178 coordinate.latitude(),
1179 coordinate.longitude(),
1180 altitude,
1181 true, // autoContinue
1182 false, // isCurrentItem
1183 missionItemParent);
1184 items.append(item);
1185}
1186
1187void TransectStyleComplexItem::_appendCameraTriggerDistance(QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum, float triggerDistance)
1188{
1189 MissionItem* item = new MissionItem(seqNum++,
1190 MAV_CMD_DO_SET_CAM_TRIGG_DIST,
1191 MAV_FRAME_MISSION,
1193 0, // shutter integration (ignore)
1194 1, // 1 - trigger one image immediately, both and entry and exit to get full coverage
1195 0, 0, 0, 0, // param 4-7 unused
1196 true, // autoContinue
1197 false, // isCurrentItem
1198 missionItemParent);
1199 items.append(item);
1200}
1201
1202void TransectStyleComplexItem::_appendCameraTriggerDistanceUpdatePoint(QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum, MAV_FRAME mavFrame, const QGeoCoordinate& coordinate, bool useConditionGate, float triggerDistance)
1203{
1204 if (useConditionGate) {
1205 _appendConditionGate(items, missionItemParent, seqNum, mavFrame, coordinate);
1206 } else {
1207 _appendWaypoint(items, missionItemParent, seqNum, mavFrame, 0 /* holdTime */, coordinate);
1208 }
1209 _appendCameraTriggerDistance(items, missionItemParent, seqNum, triggerDistance);
1210}
1211
1212TransectStyleComplexItem::BuildMissionItemsState_t TransectStyleComplexItem::_buildMissionItemsState(void) const
1213{
1214 BuildMissionItemsState_t state;
1215
1216 state.imagesInTurnaround = _cameraTriggerInTurnAroundFact.rawValue().toBool();
1217 state.hasTurnarounds = _turnAroundDistance() != 0;
1218 state.addTriggerAtFirstAndLastPoint = !hoverAndCaptureEnabled() && state.imagesInTurnaround && triggerCamera();
1219 state.useConditionGate = _controllerVehicle->firmwarePlugin()->supportedMissionCommands(QGCMAVLink::VehicleClassGeneric).contains(MAV_CMD_CONDITION_GATE) &&
1220 triggerCamera() &&
1222
1223 return state;
1224}
1225
1226void TransectStyleComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
1227{
1228 int seqNum = _sequenceNumber;
1229 BuildMissionItemsState_t buildState = _buildMissionItemsState();
1230 MAV_FRAME mavFrame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
1231
1232 qCDebug(TransectStyleComplexItemLog) << "_buildAndAppendMissionItems";
1233
1234 switch (_cameraCalc.distanceMode()) {
1236 mavFrame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
1237 break;
1240 mavFrame = MAV_FRAME_GLOBAL;
1241 break;
1243 mavFrame = MAV_FRAME_GLOBAL_TERRAIN_ALT;
1244 break;
1247 qCWarning(TransectStyleComplexItemLog) << "Internal Error: _buildAndAppendMissionItems incorrect _cameraCalc.distanceMode" << _cameraCalc.distanceMode();
1248 mavFrame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
1249 break;
1250 }
1251
1252 // Note: The code below is written to be understable as opposed to being compact and/or remove all duplicate code
1253 for (int coordIndex=0; coordIndex<_rgFlightPathCoordInfo.count(); coordIndex++) {
1254 const CoordInfo_t& coordInfo = _rgFlightPathCoordInfo[coordIndex];
1255 switch (coordInfo.coordType) {
1256 case CoordTypeInterior:
1258 _appendWaypoint(items, missionItemParent, seqNum, mavFrame, 0 /* holdTime */, coordInfo.coord);
1259 break;
1261 {
1262 bool firstEntryTurnaround = coordIndex == 0;
1263 bool lastExitTurnaround = coordIndex == _rgFlightPathCoordInfo.count() - 1;
1264 if (buildState.addTriggerAtFirstAndLastPoint && (firstEntryTurnaround || lastExitTurnaround)) {
1265 _appendCameraTriggerDistanceUpdatePoint(items, missionItemParent, seqNum, mavFrame, coordInfo.coord, buildState.useConditionGate, firstEntryTurnaround ? triggerDistance() : 0);
1266 } else {
1267 _appendWaypoint(items, missionItemParent, seqNum, mavFrame, 0 /* holdTime */, coordInfo.coord);
1268 }
1269 }
1270 break;
1272 _appendWaypoint(items, missionItemParent, seqNum, mavFrame, _hoverAndCaptureDelaySeconds, coordInfo.coord);
1273 _appendSinglePhotoCapture(items, missionItemParent, seqNum);
1274 break;
1276 if (triggerCamera()) {
1277 if (hoverAndCaptureEnabled()) {
1278 _appendWaypoint(items, missionItemParent, seqNum, mavFrame, _hoverAndCaptureDelaySeconds, coordInfo.coord);
1279 _appendSinglePhotoCapture(items, missionItemParent, seqNum);
1280 } else {
1281 // We always add a trigger start to survey entry. Even for imagesInTurnaround = true. This allows you to resume a mission and refly a transect
1282 _appendCameraTriggerDistanceUpdatePoint(items, missionItemParent, seqNum, mavFrame, coordInfo.coord, buildState.useConditionGate, triggerDistance());
1283 }
1284 } else {
1285 _appendWaypoint(items, missionItemParent, seqNum, mavFrame, 0 /* holdTime */, coordInfo.coord);
1286 }
1287 break;
1289 bool lastSurveyExit = coordIndex == _rgFlightPathCoordInfo.count() - 1;
1290 if (triggerCamera()) {
1291 if (hoverAndCaptureEnabled()) {
1292 _appendWaypoint(items, missionItemParent, seqNum, mavFrame, _hoverAndCaptureDelaySeconds, coordInfo.coord);
1293 _appendSinglePhotoCapture(items, missionItemParent, seqNum);
1294 } else if (buildState.addTriggerAtFirstAndLastPoint && !buildState.hasTurnarounds && lastSurveyExit) {
1295 _appendCameraTriggerDistanceUpdatePoint(items, missionItemParent, seqNum, mavFrame, coordInfo.coord, buildState.useConditionGate, 0 /* triggerDistance */);
1296 } else if (buildState.imagesInTurnaround) {
1297 _appendWaypoint(items, missionItemParent, seqNum, mavFrame, 0 /* holdTime */, coordInfo.coord);
1298 } else {
1299 // If we get this far it means the camera is triggering start/stop for each transect
1300 _appendCameraTriggerDistanceUpdatePoint(items, missionItemParent, seqNum, mavFrame, coordInfo.coord, buildState.useConditionGate, 0 /* triggerDistance */);
1301 }
1302 } else {
1303 _appendWaypoint(items, missionItemParent, seqNum, mavFrame, 0 /* holdTime */, coordInfo.coord);
1304 }
1305 break;
1306 }
1307 }
1308}
1309
1310void TransectStyleComplexItem::_appendLoadedMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
1311{
1312 qCDebug(TransectStyleComplexItemLog) << "_appendLoadedMissionItems";
1313
1314 int seqNum = _sequenceNumber;
1315
1316 for (const MissionItem* loadedMissionItem: _loadedMissionItems) {
1317 MissionItem* item = new MissionItem(*loadedMissionItem, missionItemParent);
1318 item->setSequenceNumber(seqNum++);
1319 items.append(item);
1320 }
1321}
1322
1324{
1325 // We add the survey area polygon as a Placemark
1326
1327 QDomElement placemarkElement = domDocument.addPlacemark(QStringLiteral("Survey Area"), true);
1328 QDomElement polygonElement = _surveyAreaPolygon.kmlPolygonElement(domDocument);
1329
1330 placemarkElement.appendChild(polygonElement);
1331 domDocument.addTextElement(placemarkElement, "styleUrl", QStringLiteral("#%1").arg(domDocument.surveyPolygonStyleName));
1332 domDocument.appendChildToRoot(placemarkElement);
1333}
1334
1336{
1337 _complexDistance = 0;
1338 for (int i=0; i<_visualTransectPoints.count() - 1; i++) {
1339 _complexDistance += _visualTransectPoints[i].value<QGeoCoordinate>().distanceTo(_visualTransectPoints[i+1].value<QGeoCoordinate>());
1340 }
1342}
1343
1345{
1346 return _cameraCalc.distanceToSurface()->rawValue().toDouble();
1347}
1348
1350{
1351 double alt = qQNaN();
1352 double distanceToSurface = _cameraCalc.distanceToSurface()->rawValue().toDouble();
1353
1354 switch (_cameraCalc.distanceMode()) {
1356 alt = distanceToSurface + _missionController->plannedHomePosition().altitude();
1357 break;
1359 alt = distanceToSurface;
1360 break;
1363 if (_loadedMissionItems.count()) {
1364 // The first item might not be a waypoint we have to find it.
1365 for (int i=0; i<_loadedMissionItems.count(); i++) {
1368 if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) {
1370 // AltitudeModeCalcAboveTerrain has AMSL alt in param 7
1371 alt = item->param7();
1372 } else {
1373 // AltitudeModeTerrainFrame has terrain frame relative alt in param 7. So we need terrain heights to calc AMSL.
1374 if (_rgPathHeightInfo.count()) {
1375 alt = item->param7() + _rgPathHeightInfo.first().heights.first();
1376 }
1377 }
1378 break;
1379 }
1380 }
1381 } else {
1382 if (_rgFlightPathCoordInfo.count() != 0) {
1383 alt = _rgFlightPathCoordInfo.first().coord.altitude();
1384 }
1385 }
1386 break;
1389 qCWarning(TransectStyleComplexItemLog) << "Internal Error: amslEntryAlt incorrect _cameraCalc.distanceMode" << _cameraCalc.distanceMode();
1390 break;
1391 }
1392
1393 return alt;
1394}
1395
1397{
1398 double alt = qQNaN();
1399
1400 switch (_cameraCalc.distanceMode()) {
1403 alt = amslEntryAlt();
1404 break;
1407 if (_loadedMissionItems.count()) {
1408 // The last item might not be a waypoint we have to find it.
1409 for (int i=_loadedMissionItems.count()-1; i>0; i--) {
1412 if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) {
1414 // AltitudeModeCalcAboveTerrain has AMSL alt in param 7
1415 alt = item->param7();
1416 } else {
1417 // AltitudeModeTerrainFrame has terrain frame relative alt in param 7. So we need terrain heights to calc AMSL.
1418 if (_rgPathHeightInfo.count()) {
1419 alt = item->param7() + _rgPathHeightInfo.last().heights.last();
1420 }
1421 }
1422 break;
1423 }
1424 }
1425 } else {
1426 if (_rgFlightPathCoordInfo.count() != 0) {
1427 alt = _rgFlightPathCoordInfo.last().coord.altitude();
1428 }
1429 }
1430 break;
1433 qCWarning(TransectStyleComplexItemLog) << "Internal Error: amslExitAlt incorrect _cameraCalc.distanceMode" << _cameraCalc.distanceMode();
1434 break;
1435 }
1436
1437 return alt;
1438}
1439
1441{
1442 _cameraCalc.valueSetIsDistance()->setRawValue(true);
1443 _cameraCalc.distanceToSurface()->setRawValue(newAltitude);
1444}
1445
1447{
1448 // FIXME: What about terrain frame
1449
1451 return _minAMSLAltitude;
1452 } else {
1454 }
1455}
1456
1458{
1459 // FIXME: What about terrain frame
1460
1462 return _maxAMSLAltitude;
1463 } else {
1465 }
1466}
#define qgcApp()
QString errorString
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void save(QJsonObject &json) const
void distanceModeChanged(int altMode)
Fact * distanceToSurface(void)
Definition CameraCalc.h:53
bool load(const QJsonObject &json, bool deprecatedFollowTerrain, QString &errorString, bool forPresets)
QGroundControlQmlGlobal::AltMode distanceMode(void) const
Definition CameraCalc.h:72
Fact * valueSetIsDistance(void)
Definition CameraCalc.h:52
void setDirty(bool dirty)
Definition CameraSpec.cc:36
void dirtyChanged(bool dirty)
void isIncompleteChanged(void)
void _appendFlightPathSegment(FlightPathSegment::SegmentType segmentType, const QGeoCoordinate &coord1, double coord1AMSLAlt, const QGeoCoordinate &coord2, double coord2AMSLAlt)
QmlObjectListModel _flightPathSegments
void greatestDistanceToChanged(void)
void maxAMSLAltitudeChanged(void)
virtual bool terrainCollision(void) const
void minAMSLAltitudeChanged(void)
void complexDistanceChanged(void)
void terrainCollisionChanged(bool terrainCollision)
virtual void _segmentTerrainCollisionChanged(bool terrainCollision)
void rawValueChanged(const QVariant &value)
void valueChanged(const QVariant &value)
This signal is only meant for use by the QT property system. It should not be connected to by client ...
virtual QList< MAV_CMD > supportedMissionCommands(QGCMAVLink::VehicleClass_t) const
List of supported mission commands. Empty list for all commands supported.
void appendChildToRoot(const QDomNode &child)
void addTextElement(QDomElement &parentElement, const QString &name, const QString &value)
QDomElement addPlacemark(const QString &name, bool visible)
Used to convert a Plan to a KML document.
static constexpr const char * surveyPolygonStyleName
static MissionCommandTree * instance()
const MissionCommandUIInfo * getUIInfo(Vehicle *vehicle, QGCMAVLink::VehicleClass_t vtolMode, MAV_CMD command)
bool specifiesCoordinate(void) const
bool isStandaloneCoordinate(void) const
void recalcTerrainProfile(void)
QGeoCoordinate plannedHomePosition(void) const
MAV_CMD command(void) const
Definition MissionItem.h:49
double param7(void) const
Definition MissionItem.h:60
void setSequenceNumber(int sequenceNumber)
bool load(QTextStream &loadStream)
void endResetModel()
Depth-counted endResetModel — only the outermost call has effect.
void beginResetModel()
Depth-counted beginResetModel — only the outermost call has effect.
Master controller for mission, fence, rally.
MissionController * missionController(void)
void dirtyChanged(bool dirty)
double area(void) const
Returns the area of the polygon in meters squared.
bool isValid(void) const
QList< QGeoCoordinate > coordinateList(void) const
Returns the path in a list of QGeoCoordinate's format.
void setDirty(bool dirty)
void setPath(const QList< QGeoCoordinate > &path)
QDomElement kmlPolygonElement(KMLDomDocument &domDocument)
bool isValidChanged(void)
void setShowAltColor(bool showAltColor)
void pathChanged(void)
int count(void) const
void clearAndDeleteContents() override final
Clears the list and calls deleteLater on each entry.
NOTE: TerrainAtCoordinateQuery is not thread safe. All instances/calls to ElevationProvider must be o...
void terrainDataReceived(bool success, const QList< double > &heights)
void requestData(const QList< QGeoCoordinate > &coordinates)
void requestData(const QVariantList &polyPath)
void terrainDataReceived(bool success, const QList< TerrainPathQuery::PathHeightInfo_t > &rgPathHeightInfo)
Signalled when terrain data comes back from server.
virtual void _rebuildTransectsPhase1(void)=0
Rebuilds the _transects array.
QObject * _loadedMissionItemsParent
Parent for all items in _loadedMissionItems for simpler delete.
static constexpr const char * _jsonTransectStyleComplexItemKey
QList< QList< CoordInfo_t > > _transects
QList< QGeoCoordinate > _rgFlyThroughMissionItemCoords
double minAMSLAltitude(void) const final
double editableAlt(void) const final
void _appendLoadedMissionItems(QList< MissionItem * > &items, QObject *missionItemParent)
static constexpr const char * cameraTriggerInTurnAroundName
static constexpr const char * terrainAdjustMaxDescentRateName
double amslExitAlt(void) const final
int lastSequenceNumber(void) const final
double maxAMSLAltitude(void) const final
void _appendSinglePhotoCapture(QList< MissionItem * > &items, QObject *missionItemParent, int &seqNum)
QList< MissionItem * > _loadedMissionItems
Mission items loaded from plan file.
void setMissionFlightStatus(MissionController::MissionFlightStatus_t &missionFlightStatus) final
static constexpr const char * _jsonVisualTransectPointsKey
void _buildAndAppendMissionItems(QList< MissionItem * > &items, QObject *missionItemParent)
static constexpr const char * _jsonItemsKey
static constexpr const char * _jsonTerrainFlightSpeed
void _updateFlightPathSegmentsSignal(void)
void setSequenceNumber(int sequenceNumber) final
static constexpr const char * terrainAdjustMaxClimbRateName
static constexpr const char * terrainAdjustToleranceName
void _setCameraShots(int cameraShots)
void _appendConditionGate(QList< MissionItem * > &items, QObject *missionItemParent, int &seqNum, MAV_FRAME mavFrame, const QGeoCoordinate &coordinate)
QGeoCoordinate coordinate(void) const final
double greatestDistanceTo(const QGeoCoordinate &other) const final
void applyNewAltitude(double newAltitude) final
Adjust the altitude of the item if appropriate to the new altitude.
void setCoordinate(const QGeoCoordinate &coordinate) override
int sequenceNumber(void) const final
void addKMLVisuals(KMLPlanDomDocument &domDocument) final
void _missionItemCoordTerrainData(bool success, QList< double > heights)
void _polyPathTerrainData(bool success, const QList< TerrainPathQuery::PathHeightInfo_t > &rgPathHeightInfo)
ReadyForSaveState readyForSaveState(void) const override
void _appendCameraTriggerDistanceUpdatePoint(QList< MissionItem * > &items, QObject *missionItemParent, int &seqNum, MAV_FRAME mavFrame, const QGeoCoordinate &coordinate, bool useConditionGate, float triggerDistance)
static constexpr const char * hoverAndCaptureName
static constexpr const char * refly90DegreesName
bool _load(const QJsonObject &complexObject, bool forPresets, QString &errorString)
void _appendCameraTriggerDistance(QList< MissionItem * > &items, QObject *missionItemParent, int &seqNum, float triggerDistance)
void _appendWaypoint(QList< MissionItem * > &items, QObject *missionItemParent, int &seqNum, MAV_FRAME mavFrame, float holdTime, const QGeoCoordinate &coordinate)
static constexpr const char * _jsonCameraCalcKey
static constexpr const char * _jsonCameraShotsKey
QList< TerrainPathQuery::PathHeightInfo_t > _rgPathHeightInfo
Path height for each segment includes turn segments.
static constexpr int _hoverAndCaptureDelaySeconds
QVariantList _visualTransectPoints
Used to draw the flight path visuals on the screen.
QList< double > _rgFlyThroughMissionItemCoordsTerrainHeights
QGeoCoordinate entryCoordinate(void) const final
void _save(QJsonObject &saveObject)
double amslEntryAlt(void) const final
void visualTransectPointsChanged(void)
QList< CoordInfo_t > _rgFlightPathCoordInfo
Fully calculated flight path (including terrain if needed)
virtual void _recalcCameraShots(void)=0
void timeBetweenShotsChanged(void)
QGeoCoordinate exitCoordinate(void) const final
static constexpr const char * turnAroundDistanceName
@ CoordTypeTurnaround
Turnaround extension waypoint.
@ CoordTypeSurveyExit
Waypoint at exit edge of survey polygon.
@ CoordTypeInterior
Interior waypoint for flight path only (example: interior corridor point)
@ CoordTypeInteriorTerrainAdded
Interior waypoint added for terrain.
@ CoordTypeInteriorHoverTrigger
Interior waypoint for hover and capture trigger.
@ CoordTypeSurveyEntry
Waypoint at entry edge of survey polygon.
void appendMissionItems(QList< MissionItem * > &items, QObject *missionItemParent) final
bool vtol() const
Definition Vehicle.cc:1869
bool multiRotor() const
Definition Vehicle.cc:1864
FirmwarePlugin * firmwarePlugin()
Provides access to the Firmware Plugin for this Vehicle.
Definition Vehicle.h:444
PlanMasterController * _masterController
void _setBoundingCube(QGCGeoBoundingCube bc)
double altDifference(void) const
void lastSequenceNumberChanged(int sequenceNumber)
void entryCoordinateChanged(const QGeoCoordinate &entryCoordinate)
void coordinateChanged(const QGeoCoordinate &coordinate)
void readyForSaveStateChanged(void)
MissionController * _missionController
double distance(void) const
virtual void setMissionFlightStatus(MissionController::MissionFlightStatus_t &missionFlightStatus)
bool _wizardMode
true: Item editor is showing wizard completion panel
void _amslEntryAltChanged(void)
void dirtyChanged(bool dirty)
void sequenceNumberChanged(int sequenceNumber)
void exitCoordinateChanged(const QGeoCoordinate &exitCoordinate)
void additionalTimeDelayChanged(void)
void wizardModeChanged(bool wizardMode)
double azimuth(void) const
void saveGeoCoordinateArray(const QVariantList &rgVarPoints, bool writeAltitude, QJsonValue &jsonValue)
Saves a list of QGeoCoordinates to a json array.
bool loadGeoCoordinateArray(const QJsonValue &jsonValue, bool altitudeRequired, QVariantList &rgVarPoints, QString &errorString)
returned error string if load failure
constexpr const char * jsonVersionKey
Definition JsonHelper.h:109
bool validateKeys(const QJsonObject &jsonObject, const QList< KeyValidateInfo > &keyInfo, QString &errorString)
bool fuzzyCompare(double value1, double value2)
Returns true if the two values are equal or close. Correctly handles 0 and NaN values.
Definition QGC.cc:106
double vehicleSpeed
Either cruise or hover speed based on vehicle type and vtol state.
QList< double > heights
Terrain heights along path.