QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
TransectStyleComplexItem.cc
Go to the documentation of this file.
2#include "GeoJsonHelper.h"
3#include "JsonParsing.h"
4#include "MissionController.h"
5#include "QGCApplication.h"
7#include "FlightPathSegment.h"
10#include "AppMessages.h"
11#include "QGCMath.h"
12#include "FirmwarePlugin.h"
13#include "KMLPlanDomDocument.h"
14#include "Vehicle.h"
15#include "QGCLoggingCategory.h"
16
17#include <QtCore/QJsonArray>
18
19QGC_LOGGING_CATEGORY(TransectStyleComplexItemLog, "Plan.TransectStyleComplexItem")
20
21TransectStyleComplexItem::TransectStyleComplexItem(PlanMasterController* masterController, bool flyView, QString settingsGroup)
22 : ComplexMissionItem (masterController, flyView)
23 , _cameraCalc (masterController, settingsGroup)
24 , _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/TransectStyle.SettingsGroup.json"), this))
25 , _turnAroundDistanceFact (settingsGroup, _metaDataMap[_controllerVehicle->multiRotor() ? turnAroundDistanceMultiRotorName : turnAroundDistanceName])
26 , _cameraTriggerInTurnAroundFact (settingsGroup, _metaDataMap[cameraTriggerInTurnAroundName])
27 , _hoverAndCaptureFact (settingsGroup, _metaDataMap[hoverAndCaptureName])
28 , _refly90DegreesFact (settingsGroup, _metaDataMap[refly90DegreesName])
29 , _terrainAdjustToleranceFact (settingsGroup, _metaDataMap[terrainAdjustToleranceName])
30 , _terrainAdjustMaxClimbRateFact (settingsGroup, _metaDataMap[terrainAdjustMaxClimbRateName])
31 , _terrainAdjustMaxDescentRateFact (settingsGroup, _metaDataMap[terrainAdjustMaxDescentRateName])
32{
33 _terrainPolyPathQueryTimer.setInterval(QGC::runningUnitTests() ? 10 : _terrainQueryTimeoutMsecs);
34 _terrainPolyPathQueryTimer.setSingleShot(true);
35 connect(&_terrainPolyPathQueryTimer, &QTimer::timeout, this, &TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo);
36
37 // The follow is used to compress multiple recalc calls in a row to into a single call.
38 connect(this, &TransectStyleComplexItem::_updateFlightPathSegmentsSignal, this, &TransectStyleComplexItem::_updateFlightPathSegmentsDontCallDirectly, Qt::QueuedConnection);
39 qgcApp()->addCompressedSignal(QMetaMethod::fromSignal(&TransectStyleComplexItem::_updateFlightPathSegmentsSignal));
40
41 connect(&_turnAroundDistanceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
42 connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
43 connect(&_refly90DegreesFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
44 connect(&_terrainAdjustMaxClimbRateFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
45 connect(&_terrainAdjustMaxDescentRateFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
46 connect(&_terrainAdjustToleranceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
48 connect(&_cameraTriggerInTurnAroundFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
49 connect(_cameraCalc.adjustedFootprintSide(), &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
50 connect(_cameraCalc.adjustedFootprintFrontal(), &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
51 connect(_cameraCalc.distanceToSurface(), &Fact::rawValueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
53
54 connect(&_turnAroundDistanceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::complexDistanceChanged);
55 connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &TransectStyleComplexItem::complexDistanceChanged);
56 connect(&_refly90DegreesFact, &Fact::valueChanged, this, &TransectStyleComplexItem::complexDistanceChanged);
58
59 connect(&_turnAroundDistanceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::greatestDistanceToChanged);
60 connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &TransectStyleComplexItem::greatestDistanceToChanged);
61 connect(&_refly90DegreesFact, &Fact::valueChanged, this, &TransectStyleComplexItem::greatestDistanceToChanged);
63
64 connect(&_turnAroundDistanceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_setDirty);
65 connect(&_cameraTriggerInTurnAroundFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_setDirty);
66 connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_setDirty);
67 connect(&_refly90DegreesFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_setDirty);
68 connect(&_terrainAdjustMaxClimbRateFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_setDirty);
69 connect(&_terrainAdjustMaxDescentRateFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_setDirty);
70 connect(&_terrainAdjustToleranceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_setDirty);
71 connect(&_surveyAreaPolygon, &QGCMapPolygon::pathChanged, this, &TransectStyleComplexItem::_setDirty);
72
73 connect(&_surveyAreaPolygon, &QGCMapPolygon::dirtyChanged, this, &TransectStyleComplexItem::_setIfDirty);
75
77
78 connect(_cameraCalc.distanceToSurface(), &Fact::rawValueChanged, this, &TransectStyleComplexItem::_amslEntryAltChanged);
79 connect(_cameraCalc.distanceToSurface(), &Fact::rawValueChanged, this, &TransectStyleComplexItem::_amslExitAltChanged);
80 connect(_cameraCalc.distanceToSurface(), &Fact::rawValueChanged, this, &TransectStyleComplexItem::minAMSLAltitudeChanged);
81 connect(_cameraCalc.distanceToSurface(), &Fact::rawValueChanged, this, &TransectStyleComplexItem::maxAMSLAltitudeChanged);
87 connect(&_cameraCalc, &CameraCalc::distanceModeChanged, this, &TransectStyleComplexItem::_distanceModeChanged);
88 connect(&_cameraCalc, &CameraCalc::distanceModeChanged, _missionController, &MissionController::recalcTerrainProfile);
89
90 connect(&_hoverAndCaptureFact, &Fact::rawValueChanged, this, &TransectStyleComplexItem::_handleHoverAndCaptureEnabled);
91
92 // The main coordinate is aliased to the entry
94
98
99
101
102 setDirty(false);
103}
104
106{
107 if (_cameraShots != cameraShots) {
109 emit cameraShotsChanged();
110 }
111}
112
114{
115 if (!dirty) {
117 _cameraCalc.setDirty(false);
118 }
119 if (_dirty != dirty) {
120 _dirty = dirty;
121 emit dirtyChanged(_dirty);
122 }
123}
124
125void TransectStyleComplexItem::setCoordinate(const QGeoCoordinate& coordinate)
126{
127 if (!coordinate.isValid() || !_entryCoordinate.isValid() || _surveyAreaPolygon.count() < 3) {
128 return;
129 }
130
131 const double distanceMeters = _entryCoordinate.distanceTo(coordinate);
132 const double azimuthDegrees = _entryCoordinate.azimuthTo(coordinate);
133 const QList<QGeoCoordinate> vertices = _surveyAreaPolygon.coordinateList();
134
135 QList<QGeoCoordinate> translatedVertices;
136 translatedVertices.reserve(vertices.count());
137 for (const QGeoCoordinate& vertex: vertices) {
138 translatedVertices.append(vertex.atDistanceAndAzimuth(distanceMeters, azimuthDegrees));
139 }
140
141 _surveyAreaPolygon.setPath(translatedVertices);
142}
143
144void TransectStyleComplexItem::_save(QJsonObject& complexObject)
145{
146 QJsonObject innerObject;
147
148 innerObject[JsonParsing::jsonVersionKey] = 2;
149 innerObject[turnAroundDistanceName] = _turnAroundDistanceFact.rawValue().toDouble();
151 innerObject[hoverAndCaptureName] = _hoverAndCaptureFact.rawValue().toBool();
152 innerObject[refly90DegreesName] = _refly90DegreesFact.rawValue().toBool();
153 innerObject[_jsonCameraShotsKey] = _cameraShots;
154
160 }
161
162 QJsonObject cameraCalcObject;
163 _cameraCalc.save(cameraCalcObject);
164 innerObject[_jsonCameraCalcKey] = cameraCalcObject;
165
166 QJsonValue transectPointsJson;
167
168 // Save transects polyline
169 GeoJsonHelper::saveGeoCoordinateArray(_visualTransectPoints, false /* writeAltitude */, transectPointsJson);
170 innerObject[_jsonVisualTransectPointsKey] = transectPointsJson;
171
172 // Save the interal mission items
173 QJsonArray missionItemsJsonArray;
174 QObject* missionItemParent = new QObject();
175 QList<MissionItem*> missionItems;
176 appendMissionItems(missionItems, missionItemParent);
177 for (const MissionItem* missionItem: missionItems) {
178 QJsonObject missionItemJsonObject;
179 missionItem->save(missionItemJsonObject);
180 missionItemsJsonArray.append(missionItemJsonObject);
181 }
182 missionItemParent->deleteLater();
183 innerObject[_jsonItemsKey] = missionItemsJsonArray;
184
185 complexObject[_jsonTransectStyleComplexItemKey] = innerObject;
186}
187
196
197bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, bool forPresets, QString& errorString)
198{
199 QList<JsonParsing::KeyValidateInfo> keyInfoList = {
200 { _jsonTransectStyleComplexItemKey, QJsonValue::Object, true },
201 };
202 if (!JsonParsing::validateKeys(complexObject, keyInfoList, errorString)) {
203 return false;
204 }
205
206 // The TransectStyleComplexItem is a sub-object of the main complex item object
207 QJsonObject innerObject = complexObject[_jsonTransectStyleComplexItemKey].toObject();
208
209 int version = 0;
210 bool v1FollowTerrain = false;
211 if (innerObject.contains(JsonParsing::jsonVersionKey)) {
212 version = innerObject[JsonParsing::jsonVersionKey].toInt();
213 }
214 if (version == 0) {
215 // There are really old versions without version stamp
216 version = 1;
217 }
218 if (version == 1) {
219 // Version 1->2 differences
220 // - _jsonCameraShotsKey was optional in V1 since is was added later
221 // - _jsonTerrainFollowKeyDeprecated replaced by CameraCalc::distanceMode
222 if (!innerObject.contains(_jsonCameraShotsKey)) {
223 innerObject[_jsonCameraShotsKey] = 0;
224 }
225 v1FollowTerrain = innerObject[_jsonTerrainFollowKeyDeprecated].toBool();
226 innerObject.remove(_jsonTerrainFollowKeyDeprecated);
227 version = 2;
228 }
229 if (version != 2) {
230 errorString = tr("TransectStyleComplexItem version %2 not supported").arg(version);
231 return false;
232 }
233
234 QList<JsonParsing::KeyValidateInfo> innerKeyInfoList = {
235 { JsonParsing::jsonVersionKey, QJsonValue::Double, true },
236 { turnAroundDistanceName, QJsonValue::Double, true },
237 { cameraTriggerInTurnAroundName, QJsonValue::Bool, true },
238 { hoverAndCaptureName, QJsonValue::Bool, true },
239 { refly90DegreesName, QJsonValue::Bool, true },
240 { _jsonCameraCalcKey, QJsonValue::Object, true },
241 { _jsonVisualTransectPointsKey, QJsonValue::Array, !forPresets },
242 { _jsonItemsKey, QJsonValue::Array, !forPresets },
243 { _jsonCameraShotsKey, QJsonValue::Double, true },
244 };
245 if (!JsonParsing::validateKeys(innerObject, innerKeyInfoList, errorString)) {
246 return false;
247 }
248
249 if (!forPresets) {
250 // Load visual transect points
252 return false;
253 }
254 _entryCoordinate = _visualTransectPoints.count() ? _visualTransectPoints.first().value<QGeoCoordinate>() : QGeoCoordinate();
255 _exitCoordinate = _visualTransectPoints.count() ? _visualTransectPoints.last().value<QGeoCoordinate>() : QGeoCoordinate();
256 _isIncomplete = false;
257
258 // Load generated mission items
259 _loadedMissionItemsParent = new QObject(this);
260 QJsonArray missionItemsJsonArray = innerObject[_jsonItemsKey].toArray();
261 for (const QJsonValue missionItemJson: missionItemsJsonArray) {
263 if (!missionItem->load(missionItemJson.toObject(), 0 /* sequenceNumber */, errorString)) {
264 _loadedMissionItemsParent->deleteLater();
266 return false;
267 }
268 _loadedMissionItems.append(missionItem);
269 }
270 }
271
272 // Load CameraCalc data
273 if (!_cameraCalc.load(innerObject[_jsonCameraCalcKey].toObject(), v1FollowTerrain, errorString, forPresets)) {
274 return false;
275 }
276
277 // Load TransectStyleComplexItem individual values
281 _refly90DegreesFact.setRawValue (innerObject[refly90DegreesName].toBool());
282
283 // These two keys where not included in initial implementation so they are optional. Without them the values will be
284 // incorrect when loaded though.
285 if (innerObject.contains(_jsonCameraShotsKey)) {
286 _cameraShots = innerObject[_jsonCameraShotsKey].toInt();
287 }
288
290 QList<JsonParsing::KeyValidateInfo> followTerrainKeyInfoList = {
291 { terrainAdjustToleranceName, QJsonValue::Double, true },
292 { terrainAdjustMaxClimbRateName, QJsonValue::Double, true },
293 { terrainAdjustMaxDescentRateName, QJsonValue::Double, true },
294 { _jsonTerrainFlightSpeed, QJsonValue::Double, false }, // Not required since it was missing from initial implementation
295 };
296 if (!JsonParsing::validateKeys(innerObject, followTerrainKeyInfoList, errorString)) {
297 return false;
298 }
299
303 if (innerObject.contains(_jsonTerrainFlightSpeed)) {
304 _vehicleSpeed = innerObject[_jsonTerrainFlightSpeed].toDouble();
305 }
306
307 if (!forPresets) {
308 // We have to grovel through mission items to determine min/max alt
309 _minAMSLAltitude = qQNaN();
310 _maxAMSLAltitude = qQNaN();
311 for (const MissionItem* missionItem: _loadedMissionItems) {
313 if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) {
314 _minAMSLAltitude = std::fmin(_minAMSLAltitude, missionItem->param7());
315 _maxAMSLAltitude = std::fmax(_maxAMSLAltitude, missionItem->param7());
316 }
317 }
318 }
319 }
320
321 if (!forPresets) {
323 // Terrain frame requires terrain data in order to know AMSL coordinate heights for each mission item
324 _queryMissionItemCoordHeights();
325 } else {
331 }
332 }
333
334 return true;
335}
336
337double TransectStyleComplexItem::greatestDistanceTo(const QGeoCoordinate &other) const
338{
339 double greatestDistance = 0.0;
340 for (int i=0; i<_visualTransectPoints.count(); i++) {
341 QGeoCoordinate vertex = _visualTransectPoints[i].value<QGeoCoordinate>();
342 double distance = vertex.distanceTo(other);
343 if (distance > greatestDistance) {
344 greatestDistance = distance;
345 }
346 }
347
348 return greatestDistance;
349}
350
352{
354 if (!QGC::fuzzyCompare(_vehicleSpeed, missionFlightStatus.vehicleSpeed)) {
355 _vehicleSpeed = missionFlightStatus.vehicleSpeed;
356 // Vehicle speed change affects max climb/descent rates calcs for terrain so we need to re-adjust
359 }
360}
361
363{
364 setDirty(true);
365}
366
368{
369 if (dirty) {
370 setDirty(true);
371 }
372}
373
379
381{
382 return _surveyAreaPolygon.area();
383}
384
386{
387 return _turnAroundDistance() > 0;
388}
389
391{
392 return _turnAroundDistanceFact.rawValue().toDouble();
393}
394
399
401{
402 if (_ignoreRecalc) {
403 return;
404 }
405
406 _transects.clear();
407 _rgPathHeightInfo.clear();
409
411
413
414 switch (_cameraCalc.distanceMode()) {
417 qCWarning(TransectStyleComplexItemLog) << "Internal Error: _rebuildTransects - invalid _cameraCalc.distanceMode()" << _cameraCalc.distanceMode();
418 return;
422 // Terrain height not needed to calculate path, as TerrainFrame specifies a fixed altitude over terrain, doesn't need to know the actual terrain height
423 // so vehicle is responsible for having or not this altitude calculation, so we can build the flight path right away.
424 _buildFlightPathCoordInfoFromTransects();
425 break;
427 // Query the terrain data. Once available flight path will be calculated, as on this mode QGC actually calculates the individual altitude for each waypoint
428 // having into account terrain data.
429 _queryTransectsPathHeightInfo();
430 break;
431 }
432
433 // Calc bounding cube
434 double north = 0.0;
435 double south = 180.0;
436 double east = 0.0;
437 double west = 360.0;
438 double bottom = 100000.;
439 double top = 0.;
440 // Generate the visuals transect representation
441 _visualTransectPoints.clear();
442 for (const QList<CoordInfo_t>& transect: _transects) {
443 for (const CoordInfo_t& coordInfo: transect) {
444 _visualTransectPoints.append(QVariant::fromValue(coordInfo.coord));
445 double lat = coordInfo.coord.latitude() + 90.0;
446 double lon = coordInfo.coord.longitude() + 180.0;
447 north = fmax(north, lat);
448 south = fmin(south, lat);
449 east = fmax(east, lon);
450 west = fmin(west, lon);
451 bottom = fmin(bottom, coordInfo.coord.altitude());
452 top = fmax(top, coordInfo.coord.altitude());
453 }
454 }
455 //-- Update bounding cube for airspace management control
457 QGeoCoordinate(north - 90.0, west - 180.0, bottom),
458 QGeoCoordinate(south - 90.0, east - 180.0, top)));
460
461 _entryCoordinate = _visualTransectPoints.count() ? _visualTransectPoints.first().value<QGeoCoordinate>() : QGeoCoordinate();
462 _exitCoordinate = _visualTransectPoints.count() ? _visualTransectPoints.last().value<QGeoCoordinate>() : QGeoCoordinate();
464
465 if (_isIncomplete) {
466 _isIncomplete = false;
467 emit isIncompleteChanged();
468 }
469
472
476
479
483}
484
485void TransectStyleComplexItem::_segmentTerrainCollisionChanged(bool terrainCollision)
486{
489}
490
491// Never call this method directly. If you want to update the flight segments you emit _updateFlightPathSegmentsSignal()
492void TransectStyleComplexItem::_updateFlightPathSegmentsDontCallDirectly(void)
493{
496 emit terrainCollisionChanged(false);
498 }
499
502
503 switch (_cameraCalc.distanceMode()) {
506 qCWarning(TransectStyleComplexItemLog) << "Internal Error: _updateFlightPathSegmentsDontCallDirectly - invalid _cameraCalc.distanceMode()" << _cameraCalc.distanceMode();
507 return;
510 {
511 // Since we aren't following terrain all the transects are at the same height. We can use _visualTransectPoints to build the
512 // flight path segments.
513 QGeoCoordinate prevCoord;
514 double surveyAlt = amslEntryAlt();
515 for (const QVariant& varCoord: _visualTransectPoints) {
516 QGeoCoordinate thisCoord = varCoord.value<QGeoCoordinate>();
517 if (prevCoord.isValid()) {
518 _appendFlightPathSegment(FlightPathSegment::SegmentTypeGeneric, prevCoord, surveyAlt, thisCoord, surveyAlt);
519 }
520 prevCoord = thisCoord;
521 }
522 }
523 break;
527 // Build segments from loaded mission item data
528 QGeoCoordinate prevCoord = QGeoCoordinate();
529 double prevAlt = 0;
530 for (const MissionItem* missionItem: _loadedMissionItems) {
531 if (missionItem->command() == MAV_CMD_NAV_WAYPOINT || missionItem->command() == MAV_CMD_CONDITION_GATE) {
532 if (prevCoord.isValid()) {
533 _appendFlightPathSegment(FlightPathSegment::SegmentTypeGeneric, prevCoord, prevAlt, missionItem->coordinate(), missionItem->param7());
534 }
535 prevCoord = missionItem->coordinate();
536 prevAlt = missionItem->param7();
537 }
538 }
539 } else {
540 // We are either:
541 // - Working from live transect data of an interactive editing session
542 // - Working from loaded mission items which have had terrain heights queried for
543 // In both cases _rgFlightPathCoordInfo will be set up for use
544 if (_rgFlightPathCoordInfo.count()) {
546 for (int i=0; i<_rgFlightPathCoordInfo.count() - 1; i++) {
547 const QGeoCoordinate& fromCoord = _rgFlightPathCoordInfo[i].coord;
548 const QGeoCoordinate& toCoord = _rgFlightPathCoordInfo[i+1].coord;
549 _appendFlightPathSegment(segmentType, fromCoord, fromCoord.altitude(), toCoord, toCoord.altitude());
550 }
551 }
552 }
553 break;
554 }
555
557
559 emit terrainCollisionChanged(true);
561 }
562
564}
565
566void TransectStyleComplexItem::_queryTransectsPathHeightInfo(void)
567{
568 _rgPathHeightInfo.clear();
570
571 if (_transects.count()) {
572 // We don't actually send the query until this timer times out. This way we only send
573 // the latest request if we get a bunch in a row.
574 _terrainPolyPathQueryTimer.start();
575 }
576}
577
578void TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo(void)
579{
580 qCDebug(TransectStyleComplexItemLog) << "_reallyQueryTransectsPathHeightInfo";
581
582 // Clear any previous queries
583 if (_currentTerrainPolyPathQuery) {
584 disconnect(_currentTerrainPolyPathQuery);
585 _currentTerrainPolyPathQuery = nullptr;
586 }
587 if (_currentTerrainAtCoordinateQuery) {
588 disconnect(_currentTerrainAtCoordinateQuery);
589 _currentTerrainAtCoordinateQuery = nullptr;
590 }
591
592 // Append all transects into a single PolyPath query
593 QList<QGeoCoordinate> transectPoints;
594 for (const QList<CoordInfo_t>& transect: _transects) {
595 for (const CoordInfo_t& coordInfo: transect) {
596 transectPoints.append(coordInfo.coord);
597 }
598 }
599
600 if (transectPoints.count() > 1) {
601 _currentTerrainPolyPathQuery = new TerrainPolyPathQuery(true /* autoDelete */);
603 _currentTerrainPolyPathQuery->requestData(transectPoints);
604 }
605}
606
607void TransectStyleComplexItem::_queryMissionItemCoordHeights(void)
608{
609 qCDebug(TransectStyleComplexItemLog) << "_queryMissionItemCoordHeights";
610
612
613 if (_currentTerrainAtCoordinateQuery) {
614 qCWarning(TransectStyleComplexItemLog) << "Internal error: _queryMissionItemCoordHeights called multiple times";
615 // We are already waiting on another query. We don't care about those results any more.
616 disconnect(_currentTerrainPolyPathQuery);
617 _currentTerrainPolyPathQuery = nullptr;
618 }
619
620 // We need terrain heights below each mission item we fly through which is terrain frame
621 for (const MissionItem* missionItem: _loadedMissionItems) {
622 if (missionItem->frame() == MAV_FRAME_GLOBAL_TERRAIN_ALT) {
624 if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) {
625 _rgFlyThroughMissionItemCoords.append(missionItem->coordinate());
626 }
627 }
628 }
629
630 if (_rgFlyThroughMissionItemCoords.count()) {
631 _currentTerrainAtCoordinateQuery = new TerrainAtCoordinateQuery(true /* autoDelete */);
633 _currentTerrainAtCoordinateQuery->requestData(_rgFlyThroughMissionItemCoords);
634 }
635}
636
637void TransectStyleComplexItem::_polyPathTerrainData(bool success, const QList<TerrainPathQuery::PathHeightInfo_t>& rgPathHeightInfo)
638{
639 qCDebug(TransectStyleComplexItemLog) << "_polyPathTerrainData" << success;
640
641 _rgPathHeightInfo.clear();
643
644 if (success) {
645 // Now that we have terrain data we can adjust
646 _rgPathHeightInfo = rgPathHeightInfo;
647 _adjustForAvailableTerrainData();
649 }
650 _currentTerrainPolyPathQuery = nullptr;
651}
652
653void TransectStyleComplexItem::_missionItemCoordTerrainData(bool success, QList<double> heights)
654{
655 qCDebug(TransectStyleComplexItemLog) << "_polyPathTerrainData" << success;
656
657 _rgPathHeightInfo.clear();
659
660 if (success) {
661 // Now that we have terrain data we can adjust
663 _adjustForAvailableTerrainData();
665 }
666 _currentTerrainPolyPathQuery = nullptr;
667}
668
670{
671 bool terrainReady = false;
673 if (_loadedMissionItems.count()) {
674 // We have loaded mission items. Everything is ready to go.
675 terrainReady = true;
676 } else {
677 // Survey is currently being designed. We aren't ready if we don't have terrain heights yet.
678 terrainReady = _rgPathHeightInfo.count();
679 }
680 } else {
681 // Not following terrain so always ready on terrain
682 terrainReady = true;
683 }
684 bool polygonNotReady = !_surveyAreaPolygon.isValid();
685 return (polygonNotReady || _wizardMode) ?
687 (terrainReady ? ReadyForSave : NotReadyForSaveTerrain);
688}
689
690void TransectStyleComplexItem::_adjustForAvailableTerrainData(void)
691{
692 switch (_cameraCalc.distanceMode()) {
695 qCWarning(TransectStyleComplexItemLog) << "Internal Error: _adjustForAvailableTerrainData - invalid _cameraCalc.distanceMode()" << _cameraCalc.distanceMode();
696 return;
699 // No additional work needed
700 return;
702 _buildFlightPathCoordInfoFromPathHeightInfoForCalcAboveTerrain();
703 _adjustForMaxRates();
704 _adjustForTolerance();
705 _minAMSLAltitude = qQNaN();
706 _maxAMSLAltitude = qQNaN();
707 for (const CoordInfo_t& coordInfo: _rgFlightPathCoordInfo) {
708 _minAMSLAltitude = std::fmin(_minAMSLAltitude, coordInfo.coord.altitude());
709 _maxAMSLAltitude = std::fmax(_maxAMSLAltitude, coordInfo.coord.altitude());
710 }
712 break;
714 if (_loadedMissionItems.count()) {
715 _buildFlightPathCoordInfoFromMissionItems();
716 } else {
717 _buildFlightPathCoordInfoFromPathHeightInfoForTerrainFrame();
718 }
719 break;
720 }
721
727}
728
731double TransectStyleComplexItem::_altitudeBetweenCoords(const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord, double percentTowardsTo)
732{
733 double fromAlt = fromCoord.altitude();
734 double toAlt = toCoord.altitude();
735 double altDiff = toAlt - fromAlt;
736 return fromAlt + (altDiff * percentTowardsTo);
737}
738
744int TransectStyleComplexItem::_maxPathHeight(const TerrainPathQuery::PathHeightInfo_t& pathHeightInfo, int fromIndex, int toIndex, double& maxHeight)
745{
746 maxHeight = qQNaN();
747
748 if (toIndex - fromIndex < 2) {
749 return -1;
750 }
751
752 fromIndex++;
753 toIndex--;
754
755 int maxIndex = fromIndex;
756 maxHeight = pathHeightInfo.heights[fromIndex];
757
758 for (int i=fromIndex; i<=toIndex; i++) {
759 if (pathHeightInfo.heights[i] > maxHeight) {
760 maxIndex = i;
761 maxHeight = pathHeightInfo.heights[i];
762 }
763 }
764
765 return maxIndex;
766}
767
768void TransectStyleComplexItem::_adjustForMaxRates(void)
769{
770 double maxClimbRate = _terrainAdjustMaxClimbRateFact.rawValue().toDouble();
771 double maxDescentRate = _terrainAdjustMaxDescentRateFact.rawValue().toDouble();
772 double flightSpeed = _vehicleSpeed;
773
774 if (qIsNaN(flightSpeed) || (maxClimbRate == 0 && maxDescentRate == 0)) {
775 if (qIsNaN(flightSpeed)) {
776 qWarning() << "TransectStyleComplexItem::_adjustForMaxRates called with flightSpeed = NaN";
777 }
778 return;
779 }
780 if (maxClimbRate <= 0 && maxDescentRate <= 0) {
781 return;
782 }
783
784 if (maxClimbRate > 0) {
785 bool climbRateAdjusted;
786 do {
787 //qDebug() << "climb rate pass";
788 climbRateAdjusted = false;
789 for (int i=0; i<_rgFlightPathCoordInfo.count() - 1; i++) {
790 QGeoCoordinate& fromCoord = _rgFlightPathCoordInfo[i].coord;
791 QGeoCoordinate& toCoord = _rgFlightPathCoordInfo[i+1].coord;
792
793 double altDifference = toCoord.altitude() - fromCoord.altitude();
794 double distance = fromCoord.distanceTo(toCoord);
795 double seconds = distance / flightSpeed;
796 double climbRate = altDifference / seconds;
797
798 //qDebug() << QString("Index:%1 altDifference:%2 distance:%3 seconds:%4 climbRate:%5").arg(i).arg(altDifference).arg(distance).arg(seconds).arg(climbRate);
799
800 if (climbRate > 0 && climbRate - maxClimbRate > 0.1) {
801 double maxAltitudeDelta = maxClimbRate * seconds;
802 fromCoord.setAltitude(toCoord.altitude() - maxAltitudeDelta);
803 //qDebug() << "Adjusting";
804 climbRateAdjusted = true;
805 }
806 }
807 } while (climbRateAdjusted);
808 }
809
810 if (maxDescentRate > 0) {
811 bool descentRateAdjusted;
812 maxDescentRate = -maxDescentRate;
813 do {
814 //qDebug() << "descent rate pass";
815 descentRateAdjusted = false;
816 for (int i=0; i<_rgFlightPathCoordInfo.count() - 1; i++) {
817 QGeoCoordinate& fromCoord = _rgFlightPathCoordInfo[i].coord;
818 QGeoCoordinate& toCoord = _rgFlightPathCoordInfo[i+1].coord;
819
820 double altDifference = toCoord.altitude() - fromCoord.altitude();
821 double distance = fromCoord.distanceTo(toCoord);
822 double seconds = distance / flightSpeed;
823 double descentRate = altDifference / seconds;
824
825 //qDebug() << QString("Index:%1 altDifference:%2 distance:%3 seconds:%4 descentRate:%5").arg(i).arg(altDifference).arg(distance).arg(seconds).arg(descentRate);
826
827 if (descentRate < 0 && descentRate - maxDescentRate < -0.1) {
828 double maxAltitudeDelta = maxDescentRate * seconds;
829 toCoord.setAltitude(fromCoord.altitude() + maxAltitudeDelta);
830 //qDebug() << "Adjusting";
831 descentRateAdjusted = true;
832 }
833 }
834 } while (descentRateAdjusted);
835 }
836}
837
838void TransectStyleComplexItem::_adjustForTolerance(void)
839{
840 QList<CoordInfo_t> adjustedFlightPath;
841 double tolerance = _terrainAdjustToleranceFact.rawValue().toDouble();
842 CoordInfo_t& lastCoordInfo = _rgFlightPathCoordInfo.first();
843
844 adjustedFlightPath.append(lastCoordInfo);
845
846 int coordIndex = 1;
847 while (coordIndex < _rgFlightPathCoordInfo.count()) {
848 // Walk forward until we fall out of tolerence. When we fall out of tolerance add that point.
849 // We always add non-interstitial points no matter what.
850 const CoordInfo_t& nextCoordInfo = _rgFlightPathCoordInfo[coordIndex];
851 if (nextCoordInfo.coordType != CoordTypeInteriorTerrainAdded || qAbs(lastCoordInfo.coord.altitude() - nextCoordInfo.coord.altitude()) > tolerance) {
852 adjustedFlightPath.append(nextCoordInfo);
853 lastCoordInfo = nextCoordInfo;
854 }
855 coordIndex++;
856 }
857
858 _rgFlightPathCoordInfo = adjustedFlightPath;
859}
860
861void TransectStyleComplexItem::_buildFlightPathCoordInfoFromTransects(void)
862{
864
865 double distanceToSurface = _cameraCalc.distanceToSurface()->rawValue().toDouble();
866
868 for (int transectIndex=0; transectIndex<_transects.count(); transectIndex++) {
869 const QList<CoordInfo_t>& transect = _transects[transectIndex];
870
871 for (int transectCoordIndex=0; transectCoordIndex<transect.count() - 1; transectCoordIndex++) {
872 CoordInfo_t fromCoordInfo = transect[transectCoordIndex];
873 CoordInfo_t toCoordInfo = transect[transectCoordIndex+1];
874
875 fromCoordInfo.coord.setAltitude(distanceToSurface);
876 toCoordInfo.coord.setAltitude(distanceToSurface);
877
878 if (transectCoordIndex == 0) {
879 _rgFlightPathCoordInfo.append(fromCoordInfo);
880 }
881 _rgFlightPathCoordInfo.append(toCoordInfo);
882 }
883 }
884}
885
886void TransectStyleComplexItem::_buildFlightPathCoordInfoFromPathHeightInfoForCalcAboveTerrain(void)
887{
889
890 if (_rgPathHeightInfo.count() == 0) {
891 qCWarning(TransectStyleComplexItemLog) << "TransectStyleComplexItem::_buildFlightPathCoordInfoFromPathHeightInfo terrain height needed but _rgPathHeightInfo.count() == 0";
892 return;
893 }
894
895 double distanceToSurface = _cameraCalc.distanceToSurface()->rawValue().toDouble();
896
898 int pathHeightIndex = 0;
899 for (int transectIndex=0; transectIndex<_transects.count(); transectIndex++) {
900 const QList<CoordInfo_t>& transect = _transects[transectIndex];
901
902 // Build flight path for transect
903 for (int transectCoordIndex=0; transectCoordIndex<transect.count() - 1; transectCoordIndex++) {
904 CoordInfo_t fromCoordInfo = transect[transectCoordIndex];
905 CoordInfo_t toCoordInfo = transect[transectCoordIndex+1];
906
907 const auto& pathHeightInfo = _rgPathHeightInfo[pathHeightIndex++];
908
909 fromCoordInfo.coord.setAltitude(distanceToSurface + pathHeightInfo.heights.first());
910 toCoordInfo.coord.setAltitude(distanceToSurface + pathHeightInfo.heights.last());
911
912 if (transectCoordIndex == 0) {
913 _rgFlightPathCoordInfo.append(fromCoordInfo);
914 }
915
916 // Add interstitial points at max resolution of our terrain data
917 int cHeights = pathHeightInfo.heights.count();
918
919 double azimuth = fromCoordInfo.coord.azimuthTo(toCoordInfo.coord);
920 double distance = fromCoordInfo.coord.distanceTo(toCoordInfo.coord);
921
922 for (int interstitialIndex=1; interstitialIndex<cHeights - 1; interstitialIndex++) {
923 double interstitialTerrainHeight = pathHeightInfo.heights[interstitialIndex];
924 double percentTowardsTo = (1.0 / (cHeights - 1)) * interstitialIndex;
925
926 CoordInfo_t interstitialCoordInfo;
927 interstitialCoordInfo.coordType = CoordTypeInteriorTerrainAdded;
928 interstitialCoordInfo.coord = fromCoordInfo.coord.atDistanceAndAzimuth(distance * percentTowardsTo, azimuth);
929 interstitialCoordInfo.coord.setAltitude(interstitialTerrainHeight + distanceToSurface);
930
931 _rgFlightPathCoordInfo.append(interstitialCoordInfo);
932 }
933
934 _rgFlightPathCoordInfo.append(toCoordInfo);
935 }
936
937 // Build flight path for turnaround
938 // Add terrain interstitial points to the turn segment if not the last transect
939 if (transectIndex != _transects.count() - 1) {
940 const auto& pathHeightInfo = _rgPathHeightInfo[pathHeightIndex++];
941
942 int cHeights = pathHeightInfo.heights.count();
943
944 CoordInfo_t fromCoordInfo = _transects[transectIndex].last();
945 CoordInfo_t toCoordInfo = _transects[transectIndex+1].first();
946
947 double azimuth = fromCoordInfo.coord.azimuthTo(toCoordInfo.coord);
948 double distance = fromCoordInfo.coord.distanceTo(toCoordInfo.coord);
949
950 for (int interstitialIndex=1; interstitialIndex<cHeights - 1; interstitialIndex++) {
951 double interstitialTerrainHeight = pathHeightInfo.heights[interstitialIndex];
952 double percentTowardsTo = (1.0 / (cHeights - 1)) * interstitialIndex;
953
954 CoordInfo_t interstitialCoordInfo;
955 interstitialCoordInfo.coordType = CoordTypeInteriorTerrainAdded;
956 interstitialCoordInfo.coord = fromCoordInfo.coord.atDistanceAndAzimuth(distance * percentTowardsTo, azimuth);
957 interstitialCoordInfo.coord.setAltitude(interstitialTerrainHeight + distanceToSurface);
958
959 _rgFlightPathCoordInfo.append(interstitialCoordInfo);
960 }
961 }
962 }
963}
964
965void TransectStyleComplexItem::_buildFlightPathCoordInfoFromPathHeightInfoForTerrainFrame(void)
966{
968
969 if (_rgPathHeightInfo.count() == 0) {
970 qCWarning(TransectStyleComplexItemLog) << "TransectStyleComplexItem::_buildFlightPathCoordInfoFromPathHeightInfoForTerrainFrame terrain height needed but _rgPathHeightInfo.count() == 0";
971 return;
972 }
973
974 double distanceToSurface = _cameraCalc.distanceToSurface()->rawValue().toDouble();
975
977 int pathHeightIndex = 0;
978 for (int transectIndex=0; transectIndex<_transects.count(); transectIndex++) {
979 const QList<CoordInfo_t>& transect = _transects[transectIndex];
980
981 // Build flight path for transect
982 for (int transectCoordIndex=0; transectCoordIndex<transect.count() - 1; transectCoordIndex++) {
983 CoordInfo_t fromCoordInfo = transect[transectCoordIndex];
984 CoordInfo_t toCoordInfo = transect[transectCoordIndex+1];
985
986 const auto& pathHeightInfo = _rgPathHeightInfo[pathHeightIndex++];
987
988 fromCoordInfo.coord.setAltitude(distanceToSurface + pathHeightInfo.heights.first());
989 toCoordInfo.coord.setAltitude(distanceToSurface + pathHeightInfo.heights.last());
990
991 if (transectCoordIndex == 0) {
992 _rgFlightPathCoordInfo.append(fromCoordInfo);
993 }
994 _rgFlightPathCoordInfo.append(toCoordInfo);
995 }
996
997 // Even though we don't use it we still have path heights for the turnaround segment
998 pathHeightIndex++;
999 }
1000}
1001
1002void TransectStyleComplexItem::_buildFlightPathCoordInfoFromMissionItems(void)
1003{
1005
1007 qCWarning(TransectStyleComplexItemLog) << "_buildFlightPathCoordInfoFromMissionItems - terrain height needed but _rgFlyThroughMissionItemCoordsTerrainHeights.count() == 0";
1008 return;
1009 }
1011 qCWarning(TransectStyleComplexItemLog) << "_buildFlightPathCoordInfoFromMissionItems - _rgFlyThroughMissionItemCoordsTerrainHeights.count() != _rgFlyThroughMissionItemCoords.count()";
1012 return;
1013 }
1014 if (_rgFlyThroughMissionItemCoords.count() < 2) {
1015 qCWarning(TransectStyleComplexItemLog) << "_buildFlightPathCoordInfoFromMissionItems - rgFlyThroughMissionItemCoords.count() < 2";
1016 return;
1017 }
1018
1019 _rgFlightPathCoordInfo.clear();
1020 for (int i=0; i<_rgFlyThroughMissionItemCoords.count() - 1; i++) {
1021 double heightAtCoord = _rgFlyThroughMissionItemCoordsTerrainHeights[i];
1022
1023 // Since we are working from loading mission items the CoordInfo_t.coordType doesn't really matter
1024 CoordInfo_t fromCoordInfo = { _rgFlyThroughMissionItemCoords[i], CoordTypeInterior };
1025 CoordInfo_t toCoordInfo = { _rgFlyThroughMissionItemCoords[i+1], CoordTypeInterior };
1026
1027 fromCoordInfo.coord.setAltitude(fromCoordInfo.coord.altitude() + heightAtCoord);
1028 toCoordInfo.coord.setAltitude(toCoordInfo.coord.altitude() + heightAtCoord);
1029
1030 _rgFlightPathCoordInfo.append(fromCoordInfo);
1031 }
1032}
1033
1035{
1036 if (_loadedMissionItems.count()) {
1037 // We have stored mission items, just use those
1038 return _sequenceNumber + _loadedMissionItems.count() - 1;
1039 } else if (_transects.count() == 0) {
1040 // Polygon has not yet been set so we just return back a one item complex item for now
1041 return _sequenceNumber;
1042 } else if (_rgFlightPathCoordInfo.count()) {
1043 int itemCount = 0;
1044 BuildMissionItemsState_t buildState = _buildMissionItemsState();
1045
1046 // Important Note: This code should match the logic in _buildAndAppendMissionItems
1047 for (int coordIndex=0; coordIndex<_rgFlightPathCoordInfo.count(); coordIndex++) {
1048 const CoordInfo_t& coordInfo = _rgFlightPathCoordInfo[coordIndex];
1049 switch (coordInfo.coordType) {
1050 case CoordTypeInterior:
1052 itemCount++; // Waypoint only
1053 break;
1055 {
1056 bool firstEntryTurnaround = coordIndex == 0;
1057 bool lastExitTurnaround = coordIndex == _rgFlightPathCoordInfo.count() - 1;
1058 if (buildState.addTriggerAtFirstAndLastPoint && (firstEntryTurnaround || lastExitTurnaround)) {
1059 itemCount += 2; // Waypoint + camera trigger
1060 } else {
1061 itemCount++; // Waypoint only
1062 }
1063 }
1064 break;
1066 itemCount += 2; // Waypoint + camera trigger
1067 break;
1069 if (triggerCamera()) {
1070 itemCount += 2; // Waypoint + camera trigger
1071 } else {
1072 itemCount++; // Waypoint only
1073 }
1074 break;
1076 bool lastSurveyExit = coordIndex == _rgFlightPathCoordInfo.count() - 1;
1077 if (triggerCamera()) {
1078 if (hoverAndCaptureEnabled()) {
1079 itemCount += 2; // Waypoint + camera trigger
1080 } else if (buildState.addTriggerAtFirstAndLastPoint && !buildState.hasTurnarounds && lastSurveyExit) {
1081 itemCount += 2; // Waypoint + camera trigger
1082 } else if (buildState.imagesInTurnaround) {
1083 itemCount++; // Waypoint only
1084 } else {
1085 itemCount += 2; // Waypoint + camera trigger
1086 }
1087 } else {
1088 itemCount++; // Waypoint only
1089 }
1090 break;
1091 }
1092 }
1093
1094 return _sequenceNumber + itemCount - 1;
1095 } else {
1096 // 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
1097 // we know the real one.
1098 int itemCount = 0;
1099
1100 for (const QList<CoordInfo_t>& rgCoordInfo: _transects) {
1101 itemCount += rgCoordInfo.count();
1102 }
1103
1104 return _sequenceNumber + itemCount - 1;
1105 }
1106}
1107
1108void TransectStyleComplexItem::_distanceModeChanged(int distanceMode)
1109{
1113 }
1114}
1115
1116void TransectStyleComplexItem::_handleHoverAndCaptureEnabled(QVariant enabled)
1117{
1118 if (enabled.toBool() && _cameraTriggerInTurnAroundFact.rawValue().toBool()) {
1120 }
1121}
1122
1123void TransectStyleComplexItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
1124{
1125 if (_loadedMissionItems.count()) {
1126 // We have mission items from the loaded plan, use those
1127 _appendLoadedMissionItems(items, missionItemParent);
1128 } else {
1129 // Build the mission items on the fly
1130 _buildAndAppendMissionItems(items, missionItemParent);
1131 }
1132}
1133
1134void TransectStyleComplexItem::_appendWaypoint(QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum, MAV_FRAME mavFrame, float holdTime, const QGeoCoordinate& coordinate)
1135{
1137
1138 MissionItem* item = new MissionItem(seqNum++,
1139 MAV_CMD_NAV_WAYPOINT,
1140 mavFrame,
1141 holdTime,
1142 0.0, // No acceptance radius specified
1143 0.0, // Pass through waypoint
1144 std::numeric_limits<double>::quiet_NaN(), // Yaw unchanged
1145 coordinate.latitude(),
1146 coordinate.longitude(),
1147 altitude,
1148 true, // autoContinue
1149 false, // isCurrentItem
1150 missionItemParent);
1151 items.append(item);
1152}
1153
1154void TransectStyleComplexItem::_appendSinglePhotoCapture(QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum)
1155{
1156 MissionItem* item = new MissionItem(seqNum++,
1157 MAV_CMD_IMAGE_START_CAPTURE,
1158 MAV_FRAME_MISSION,
1159 0, // Reserved (Set to 0)
1160 0, // Interval (none)
1161 1, // Take 1 photo
1162 0, // No sequence number specified
1163 qQNaN(), qQNaN(), qQNaN(), // param 5-7 reserved
1164 true, // autoContinue
1165 false, // isCurrentItem
1166 missionItemParent);
1167 items.append(item);
1168}
1169
1170void TransectStyleComplexItem::_appendConditionGate(QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum, MAV_FRAME mavFrame, const QGeoCoordinate& coordinate)
1171{
1173
1174 MissionItem* item = new MissionItem(seqNum++,
1175 MAV_CMD_CONDITION_GATE,
1176 mavFrame,
1177 0, // Gate is orthogonal to path
1178 1, // Use altitude
1179 0, 0, // Param 3-4 ignored
1180 coordinate.latitude(),
1181 coordinate.longitude(),
1182 altitude,
1183 true, // autoContinue
1184 false, // isCurrentItem
1185 missionItemParent);
1186 items.append(item);
1187}
1188
1189void TransectStyleComplexItem::_appendCameraTriggerDistance(QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum, float triggerDistance)
1190{
1191 MissionItem* item = new MissionItem(seqNum++,
1192 MAV_CMD_DO_SET_CAM_TRIGG_DIST,
1193 MAV_FRAME_MISSION,
1195 0, // shutter integration (ignore)
1196 1, // 1 - trigger one image immediately, both and entry and exit to get full coverage
1197 0, 0, 0, 0, // param 4-7 unused
1198 true, // autoContinue
1199 false, // isCurrentItem
1200 missionItemParent);
1201 items.append(item);
1202}
1203
1204void TransectStyleComplexItem::_appendCameraTriggerDistanceUpdatePoint(QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum, MAV_FRAME mavFrame, const QGeoCoordinate& coordinate, bool useConditionGate, float triggerDistance)
1205{
1206 if (useConditionGate) {
1207 _appendConditionGate(items, missionItemParent, seqNum, mavFrame, coordinate);
1208 } else {
1209 _appendWaypoint(items, missionItemParent, seqNum, mavFrame, 0 /* holdTime */, coordinate);
1210 }
1211 _appendCameraTriggerDistance(items, missionItemParent, seqNum, triggerDistance);
1212}
1213
1214TransectStyleComplexItem::BuildMissionItemsState_t TransectStyleComplexItem::_buildMissionItemsState(void) const
1215{
1216 BuildMissionItemsState_t state;
1217
1218 state.imagesInTurnaround = _cameraTriggerInTurnAroundFact.rawValue().toBool();
1219 state.hasTurnarounds = _turnAroundDistance() != 0;
1220 state.addTriggerAtFirstAndLastPoint = !hoverAndCaptureEnabled() && state.imagesInTurnaround && triggerCamera();
1221 state.useConditionGate = _controllerVehicle->firmwarePlugin()->supportedMissionCommands(QGCMAVLink::VehicleClassGeneric).contains(MAV_CMD_CONDITION_GATE) &&
1222 triggerCamera() &&
1224
1225 return state;
1226}
1227
1228void TransectStyleComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
1229{
1230 int seqNum = _sequenceNumber;
1231 BuildMissionItemsState_t buildState = _buildMissionItemsState();
1232 MAV_FRAME mavFrame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
1233
1234 qCDebug(TransectStyleComplexItemLog) << "_buildAndAppendMissionItems";
1235
1236 switch (_cameraCalc.distanceMode()) {
1238 mavFrame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
1239 break;
1242 mavFrame = MAV_FRAME_GLOBAL;
1243 break;
1245 mavFrame = MAV_FRAME_GLOBAL_TERRAIN_ALT;
1246 break;
1249 qCWarning(TransectStyleComplexItemLog) << "Internal Error: _buildAndAppendMissionItems incorrect _cameraCalc.distanceMode" << _cameraCalc.distanceMode();
1250 mavFrame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
1251 break;
1252 }
1253
1254 // Note: The code below is written to be understable as opposed to being compact and/or remove all duplicate code
1255 for (int coordIndex=0; coordIndex<_rgFlightPathCoordInfo.count(); coordIndex++) {
1256 const CoordInfo_t& coordInfo = _rgFlightPathCoordInfo[coordIndex];
1257 switch (coordInfo.coordType) {
1258 case CoordTypeInterior:
1260 _appendWaypoint(items, missionItemParent, seqNum, mavFrame, 0 /* holdTime */, coordInfo.coord);
1261 break;
1263 {
1264 bool firstEntryTurnaround = coordIndex == 0;
1265 bool lastExitTurnaround = coordIndex == _rgFlightPathCoordInfo.count() - 1;
1266 if (buildState.addTriggerAtFirstAndLastPoint && (firstEntryTurnaround || lastExitTurnaround)) {
1267 _appendCameraTriggerDistanceUpdatePoint(items, missionItemParent, seqNum, mavFrame, coordInfo.coord, buildState.useConditionGate, firstEntryTurnaround ? triggerDistance() : 0);
1268 } else {
1269 _appendWaypoint(items, missionItemParent, seqNum, mavFrame, 0 /* holdTime */, coordInfo.coord);
1270 }
1271 }
1272 break;
1274 _appendWaypoint(items, missionItemParent, seqNum, mavFrame, _hoverAndCaptureDelaySeconds, coordInfo.coord);
1275 _appendSinglePhotoCapture(items, missionItemParent, seqNum);
1276 break;
1278 if (triggerCamera()) {
1279 if (hoverAndCaptureEnabled()) {
1280 _appendWaypoint(items, missionItemParent, seqNum, mavFrame, _hoverAndCaptureDelaySeconds, coordInfo.coord);
1281 _appendSinglePhotoCapture(items, missionItemParent, seqNum);
1282 } else {
1283 // We always add a trigger start to survey entry. Even for imagesInTurnaround = true. This allows you to resume a mission and refly a transect
1284 _appendCameraTriggerDistanceUpdatePoint(items, missionItemParent, seqNum, mavFrame, coordInfo.coord, buildState.useConditionGate, triggerDistance());
1285 }
1286 } else {
1287 _appendWaypoint(items, missionItemParent, seqNum, mavFrame, 0 /* holdTime */, coordInfo.coord);
1288 }
1289 break;
1291 bool lastSurveyExit = coordIndex == _rgFlightPathCoordInfo.count() - 1;
1292 if (triggerCamera()) {
1293 if (hoverAndCaptureEnabled()) {
1294 _appendWaypoint(items, missionItemParent, seqNum, mavFrame, _hoverAndCaptureDelaySeconds, coordInfo.coord);
1295 _appendSinglePhotoCapture(items, missionItemParent, seqNum);
1296 } else if (buildState.addTriggerAtFirstAndLastPoint && !buildState.hasTurnarounds && lastSurveyExit) {
1297 _appendCameraTriggerDistanceUpdatePoint(items, missionItemParent, seqNum, mavFrame, coordInfo.coord, buildState.useConditionGate, 0 /* triggerDistance */);
1298 } else if (buildState.imagesInTurnaround) {
1299 _appendWaypoint(items, missionItemParent, seqNum, mavFrame, 0 /* holdTime */, coordInfo.coord);
1300 } else {
1301 // If we get this far it means the camera is triggering start/stop for each transect
1302 _appendCameraTriggerDistanceUpdatePoint(items, missionItemParent, seqNum, mavFrame, coordInfo.coord, buildState.useConditionGate, 0 /* triggerDistance */);
1303 }
1304 } else {
1305 _appendWaypoint(items, missionItemParent, seqNum, mavFrame, 0 /* holdTime */, coordInfo.coord);
1306 }
1307 break;
1308 }
1309 }
1310}
1311
1312void TransectStyleComplexItem::_appendLoadedMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
1313{
1314 qCDebug(TransectStyleComplexItemLog) << "_appendLoadedMissionItems";
1315
1316 int seqNum = _sequenceNumber;
1317
1318 for (const MissionItem* loadedMissionItem: _loadedMissionItems) {
1319 MissionItem* item = new MissionItem(*loadedMissionItem, missionItemParent);
1320 item->setSequenceNumber(seqNum++);
1321 items.append(item);
1322 }
1323}
1324
1326{
1327 // We add the survey area polygon as a Placemark
1328
1329 QDomElement placemarkElement = domDocument.addPlacemark(QStringLiteral("Survey Area"), true);
1330 QDomElement polygonElement = _surveyAreaPolygon.kmlPolygonElement(domDocument);
1331
1332 placemarkElement.appendChild(polygonElement);
1333 domDocument.addTextElement(placemarkElement, "styleUrl", QStringLiteral("#%1").arg(domDocument.surveyPolygonStyleName));
1334 domDocument.appendChildToRoot(placemarkElement);
1335}
1336
1338{
1339 _complexDistance = 0;
1340 for (int i=0; i<_visualTransectPoints.count() - 1; i++) {
1341 _complexDistance += _visualTransectPoints[i].value<QGeoCoordinate>().distanceTo(_visualTransectPoints[i+1].value<QGeoCoordinate>());
1342 }
1344}
1345
1347{
1348 return _cameraCalc.distanceToSurface()->rawValue().toDouble();
1349}
1350
1352{
1353 double alt = qQNaN();
1354 double distanceToSurface = _cameraCalc.distanceToSurface()->rawValue().toDouble();
1355
1356 switch (_cameraCalc.distanceMode()) {
1358 alt = distanceToSurface + _missionController->plannedHomePosition().altitude();
1359 break;
1361 alt = distanceToSurface;
1362 break;
1365 if (_loadedMissionItems.count()) {
1366 // The first item might not be a waypoint we have to find it.
1367 for (int i=0; i<_loadedMissionItems.count(); i++) {
1370 if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) {
1372 // AltitudeFrameCalcAboveTerrain has AMSL alt in param 7
1373 alt = item->param7();
1374 } else {
1375 // AltitudeFrameTerrain has terrain frame relative alt in param 7. So we need terrain heights to calc AMSL.
1376 if (_rgPathHeightInfo.count()) {
1377 alt = item->param7() + _rgPathHeightInfo.first().heights.first();
1378 }
1379 }
1380 break;
1381 }
1382 }
1383 } else {
1384 if (_rgFlightPathCoordInfo.count() != 0) {
1385 alt = _rgFlightPathCoordInfo.first().coord.altitude();
1386 }
1387 }
1388 break;
1391 qCWarning(TransectStyleComplexItemLog) << "Internal Error: amslEntryAlt incorrect _cameraCalc.distanceMode" << _cameraCalc.distanceMode();
1392 break;
1393 }
1394
1395 return alt;
1396}
1397
1399{
1400 double alt = qQNaN();
1401
1402 switch (_cameraCalc.distanceMode()) {
1405 alt = amslEntryAlt();
1406 break;
1409 if (_loadedMissionItems.count()) {
1410 // The last item might not be a waypoint we have to find it.
1411 for (int i=_loadedMissionItems.count()-1; i>0; i--) {
1414 if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) {
1416 // AltitudeFrameCalcAboveTerrain has AMSL alt in param 7
1417 alt = item->param7();
1418 } else {
1419 // AltitudeFrameTerrain has terrain frame relative alt in param 7. So we need terrain heights to calc AMSL.
1420 if (_rgPathHeightInfo.count()) {
1421 alt = item->param7() + _rgPathHeightInfo.last().heights.last();
1422 }
1423 }
1424 break;
1425 }
1426 }
1427 } else {
1428 if (_rgFlightPathCoordInfo.count() != 0) {
1429 alt = _rgFlightPathCoordInfo.last().coord.altitude();
1430 }
1431 }
1432 break;
1435 qCWarning(TransectStyleComplexItemLog) << "Internal Error: amslExitAlt incorrect _cameraCalc.distanceMode" << _cameraCalc.distanceMode();
1436 break;
1437 }
1438
1439 return alt;
1440}
1441
1447
1449{
1450 // FIXME: What about terrain frame
1451
1453 return _minAMSLAltitude;
1454 } else {
1456 }
1457}
1458
1460{
1461 // FIXME: What about terrain frame
1462
1464 return _maxAMSLAltitude;
1465 } else {
1467 }
1468}
#define qgcApp()
QString errorString
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void save(QJsonObject &json) const
void distanceModeChanged(int altFrame)
Fact * distanceToSurface(void)
Definition CameraCalc.h:53
bool load(const QJsonObject &json, bool deprecatedFollowTerrain, QString &errorString, bool forPresets)
QGroundControlQmlGlobal::AltitudeFrame 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)
Holds the meta data associated with a Fact.
void rawValueChanged(const QVariant &value)
void setRawValue(const QVariant &value)
Definition Fact.cc:128
QVariant rawValue() const
Value after translation.
Definition Fact.h:85
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(QGCMAVLinkTypes::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)
UI Information associated with a mission command (MAV_CMD)
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.
Provides access to group of settings.
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.
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 setMissionFlightStatus(MissionFlightStatus_t &missionFlightStatus) 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:1763
bool multiRotor() const
Definition Vehicle.cc:1758
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
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)
virtual void setMissionFlightStatus(MissionFlightStatus_t &missionFlightStatus)
double azimuth(void) const
bool loadGeoCoordinateArray(const QJsonValue &jsonValue, bool altitudeRequired, QVariantList &rgVarPoints, QString &errorString)
Loads a list of QGeoCoordinates (QGC plan format) from a json array.
void saveGeoCoordinateArray(const QVariantList &rgVarPoints, bool writeAltitude, QJsonValue &jsonValue)
Saves a list of QGeoCoordinates (QGC plan format) to a json array.
bool validateKeys(const QJsonObject &jsonObject, const QList< KeyValidateInfo > &keyInfo, QString &errorString)
Validates that all required keys are present and that listed keys have the expected type.
constexpr const char * jsonVersionKey
Definition JsonParsing.h:12
bool runningUnitTests()
bool fuzzyCompare(double value1, double value2)
Returns true if the two values are equal or close. Correctly handles 0 and NaN values.
Definition QGCMath.cc:109
double vehicleSpeed
Either cruise or hover speed based on vehicle type and vtol state.
static constexpr VehicleClass_t VehicleClassGeneric
QList< double > heights
Terrain heights along path.