15#include <QtCore/QJsonArray>
21 , _cameraCalc (masterController, settingsGroup)
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])
31 _terrainPolyPathQueryTimer.setInterval(
qgcApp()->runningUnitTests() ? 10 : _terrainQueryTimeoutMsecs);
32 _terrainPolyPathQueryTimer.setSingleShot(
true);
33 connect(&_terrainPolyPathQueryTimer, &QTimer::timeout,
this, &TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo);
88 connect(&_hoverAndCaptureFact, &
Fact::rawValueChanged,
this, &TransectStyleComplexItem::_handleHoverAndCaptureEnabled);
133 QList<QGeoCoordinate> translatedVertices;
134 translatedVertices.reserve(vertices.count());
135 for (
const QGeoCoordinate& vertex: vertices) {
136 translatedVertices.append(vertex.atDistanceAndAzimuth(distanceMeters, azimuthDegrees));
144 QJsonObject innerObject;
160 QJsonObject cameraCalcObject;
164 QJsonValue transectPointsJson;
171 QJsonArray missionItemsJsonArray;
172 QObject* missionItemParent =
new QObject();
173 QList<MissionItem*> missionItems;
175 for (
const MissionItem* missionItem: missionItems) {
176 QJsonObject missionItemJsonObject;
177 missionItem->save(missionItemJsonObject);
178 missionItemsJsonArray.append(missionItemJsonObject);
180 missionItemParent->deleteLater();
197 QList<JsonHelper::KeyValidateInfo> keyInfoList = {
208 bool v1FollowTerrain =
false;
223 v1FollowTerrain = innerObject[_jsonTerrainFollowKeyDeprecated].toBool();
224 innerObject.remove(_jsonTerrainFollowKeyDeprecated);
228 errorString = tr(
"TransectStyleComplexItem version %2 not supported").arg(version);
232 QList<JsonHelper::KeyValidateInfo> innerKeyInfoList = {
258 QJsonArray missionItemsJsonArray = innerObject[
_jsonItemsKey].toArray();
259 for (
const QJsonValue missionItemJson: missionItemsJsonArray) {
288 QList<JsonHelper::KeyValidateInfo> followTerrainKeyInfoList = {
322 _queryMissionItemCoordHeights();
337 double greatestDistance = 0.0;
340 double distance = vertex.distanceTo(other);
346 return greatestDistance;
415 qCWarning(TransectStyleComplexItemLog) <<
"Internal Error: _rebuildTransects - invalid _cameraCalc.distanceMode()" <<
_cameraCalc.
distanceMode();
422 _buildFlightPathCoordInfoFromTransects();
427 _queryTransectsPathHeightInfo();
433 double south = 180.0;
436 double bottom = 100000.;
440 for (
const QList<CoordInfo_t>& transect:
_transects) {
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());
455 QGeoCoordinate(north - 90.0, west - 180.0, bottom),
456 QGeoCoordinate(south - 90.0, east - 180.0, top)));
483void TransectStyleComplexItem::_segmentTerrainCollisionChanged(
bool terrainCollision)
490void TransectStyleComplexItem::_updateFlightPathSegmentsDontCallDirectly(
void)
504 qCWarning(TransectStyleComplexItemLog) <<
"Internal Error: _updateFlightPathSegmentsDontCallDirectly - invalid _cameraCalc.distanceMode()" <<
_cameraCalc.
distanceMode();
511 QGeoCoordinate prevCoord;
514 QGeoCoordinate thisCoord = varCoord.value<QGeoCoordinate>();
515 if (prevCoord.isValid()) {
518 prevCoord = thisCoord;
526 QGeoCoordinate prevCoord = QGeoCoordinate();
529 if (missionItem->command() == MAV_CMD_NAV_WAYPOINT || missionItem->command() == MAV_CMD_CONDITION_GATE) {
530 if (prevCoord.isValid()) {
533 prevCoord = missionItem->coordinate();
534 prevAlt = missionItem->param7();
564void TransectStyleComplexItem::_queryTransectsPathHeightInfo(
void)
572 _terrainPolyPathQueryTimer.start();
576void TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo(
void)
578 qCDebug(TransectStyleComplexItemLog) <<
"_reallyQueryTransectsPathHeightInfo";
581 if (_currentTerrainPolyPathQuery) {
582 disconnect(_currentTerrainPolyPathQuery);
583 _currentTerrainPolyPathQuery =
nullptr;
585 if (_currentTerrainAtCoordinateQuery) {
586 disconnect(_currentTerrainAtCoordinateQuery);
587 _currentTerrainAtCoordinateQuery =
nullptr;
591 QList<QGeoCoordinate> transectPoints;
592 for (
const QList<CoordInfo_t>& transect:
_transects) {
593 for (
const CoordInfo_t& coordInfo: transect) {
594 transectPoints.append(coordInfo.coord);
598 if (transectPoints.count() > 1) {
601 _currentTerrainPolyPathQuery->
requestData(transectPoints);
605void TransectStyleComplexItem::_queryMissionItemCoordHeights(
void)
607 qCDebug(TransectStyleComplexItemLog) <<
"_queryMissionItemCoordHeights";
611 if (_currentTerrainAtCoordinateQuery) {
612 qCWarning(TransectStyleComplexItemLog) <<
"Internal error: _queryMissionItemCoordHeights called multiple times";
614 disconnect(_currentTerrainPolyPathQuery);
615 _currentTerrainPolyPathQuery =
nullptr;
620 if (missionItem->frame() == MAV_FRAME_GLOBAL_TERRAIN_ALT) {
637 qCDebug(TransectStyleComplexItemLog) <<
"_polyPathTerrainData" << success;
645 _adjustForAvailableTerrainData();
648 _currentTerrainPolyPathQuery =
nullptr;
653 qCDebug(TransectStyleComplexItemLog) <<
"_polyPathTerrainData" << success;
661 _adjustForAvailableTerrainData();
664 _currentTerrainPolyPathQuery =
nullptr;
669 bool terrainReady =
false;
688void TransectStyleComplexItem::_adjustForAvailableTerrainData(
void)
693 qCWarning(TransectStyleComplexItemLog) <<
"Internal Error: _adjustForAvailableTerrainData - invalid _cameraCalc.distanceMode()" <<
_cameraCalc.
distanceMode();
700 _buildFlightPathCoordInfoFromPathHeightInfoForCalcAboveTerrain();
701 _adjustForMaxRates();
702 _adjustForTolerance();
713 _buildFlightPathCoordInfoFromMissionItems();
715 _buildFlightPathCoordInfoFromPathHeightInfoForTerrainFrame();
729double TransectStyleComplexItem::_altitudeBetweenCoords(
const QGeoCoordinate& fromCoord,
const QGeoCoordinate& toCoord,
double percentTowardsTo)
731 double fromAlt = fromCoord.altitude();
732 double toAlt = toCoord.altitude();
733 double altDiff = toAlt - fromAlt;
734 return fromAlt + (altDiff * percentTowardsTo);
746 if (toIndex - fromIndex < 2) {
753 int maxIndex = fromIndex;
754 maxHeight = pathHeightInfo.
heights[fromIndex];
756 for (
int i=fromIndex; i<=toIndex; i++) {
757 if (pathHeightInfo.
heights[i] > maxHeight) {
759 maxHeight = pathHeightInfo.
heights[i];
766void TransectStyleComplexItem::_adjustForMaxRates(
void)
772 if (qIsNaN(flightSpeed) || (maxClimbRate == 0 && maxDescentRate == 0)) {
773 if (qIsNaN(flightSpeed)) {
774 qWarning() <<
"TransectStyleComplexItem::_adjustForMaxRates called with flightSpeed = NaN";
778 if (maxClimbRate <= 0 && maxDescentRate <= 0) {
782 if (maxClimbRate > 0) {
783 bool climbRateAdjusted;
786 climbRateAdjusted =
false;
791 double altDifference = toCoord.altitude() - fromCoord.altitude();
792 double distance = fromCoord.distanceTo(toCoord);
793 double seconds =
distance / flightSpeed;
798 if (climbRate > 0 && climbRate - maxClimbRate > 0.1) {
799 double maxAltitudeDelta = maxClimbRate * seconds;
800 fromCoord.setAltitude(toCoord.altitude() - maxAltitudeDelta);
802 climbRateAdjusted =
true;
805 }
while (climbRateAdjusted);
808 if (maxDescentRate > 0) {
809 bool descentRateAdjusted;
810 maxDescentRate = -maxDescentRate;
813 descentRateAdjusted =
false;
818 double altDifference = toCoord.altitude() - fromCoord.altitude();
819 double distance = fromCoord.distanceTo(toCoord);
820 double seconds =
distance / flightSpeed;
825 if (descentRate < 0 && descentRate - maxDescentRate < -0.1) {
826 double maxAltitudeDelta = maxDescentRate * seconds;
827 toCoord.setAltitude(fromCoord.altitude() + maxAltitudeDelta);
829 descentRateAdjusted =
true;
832 }
while (descentRateAdjusted);
836void TransectStyleComplexItem::_adjustForTolerance(
void)
838 QList<CoordInfo_t> adjustedFlightPath;
842 adjustedFlightPath.append(lastCoordInfo);
849 if (nextCoordInfo.coordType !=
CoordTypeInteriorTerrainAdded || qAbs(lastCoordInfo.coord.altitude() - nextCoordInfo.coord.altitude()) > tolerance) {
850 adjustedFlightPath.append(nextCoordInfo);
851 lastCoordInfo = nextCoordInfo;
859void TransectStyleComplexItem::_buildFlightPathCoordInfoFromTransects(
void)
866 for (
int transectIndex=0; transectIndex<
_transects.count(); transectIndex++) {
867 const QList<CoordInfo_t>& transect =
_transects[transectIndex];
869 for (
int transectCoordIndex=0; transectCoordIndex<transect.count() - 1; transectCoordIndex++) {
870 CoordInfo_t fromCoordInfo = transect[transectCoordIndex];
871 CoordInfo_t toCoordInfo = transect[transectCoordIndex+1];
873 fromCoordInfo.coord.setAltitude(distanceToSurface);
874 toCoordInfo.coord.setAltitude(distanceToSurface);
876 if (transectCoordIndex == 0) {
884void TransectStyleComplexItem::_buildFlightPathCoordInfoFromPathHeightInfoForCalcAboveTerrain(
void)
889 qCWarning(TransectStyleComplexItemLog) <<
"TransectStyleComplexItem::_buildFlightPathCoordInfoFromPathHeightInfo terrain height needed but _rgPathHeightInfo.count() == 0";
896 int pathHeightIndex = 0;
897 for (
int transectIndex=0; transectIndex<
_transects.count(); transectIndex++) {
898 const QList<CoordInfo_t>& transect =
_transects[transectIndex];
901 for (
int transectCoordIndex=0; transectCoordIndex<transect.count() - 1; transectCoordIndex++) {
902 CoordInfo_t fromCoordInfo = transect[transectCoordIndex];
903 CoordInfo_t toCoordInfo = transect[transectCoordIndex+1];
907 fromCoordInfo.coord.setAltitude(distanceToSurface + pathHeightInfo.
heights.first());
908 toCoordInfo.coord.setAltitude(distanceToSurface + pathHeightInfo.
heights.last());
910 if (transectCoordIndex == 0) {
915 int cHeights = pathHeightInfo.
heights.count();
917 double azimuth = fromCoordInfo.coord.azimuthTo(toCoordInfo.coord);
918 double distance = fromCoordInfo.coord.distanceTo(toCoordInfo.coord);
920 for (
int interstitialIndex=1; interstitialIndex<cHeights - 1; interstitialIndex++) {
921 double interstitialTerrainHeight = pathHeightInfo.
heights[interstitialIndex];
922 double percentTowardsTo = (1.0 / (cHeights - 1)) * interstitialIndex;
924 CoordInfo_t interstitialCoordInfo;
926 interstitialCoordInfo.coord = fromCoordInfo.coord.atDistanceAndAzimuth(
distance * percentTowardsTo,
azimuth);
927 interstitialCoordInfo.coord.setAltitude(interstitialTerrainHeight + distanceToSurface);
937 if (transectIndex !=
_transects.count() - 1) {
940 int cHeights = pathHeightInfo.
heights.count();
942 CoordInfo_t fromCoordInfo =
_transects[transectIndex].last();
943 CoordInfo_t toCoordInfo =
_transects[transectIndex+1].first();
945 double azimuth = fromCoordInfo.coord.azimuthTo(toCoordInfo.coord);
946 double distance = fromCoordInfo.coord.distanceTo(toCoordInfo.coord);
948 for (
int interstitialIndex=1; interstitialIndex<cHeights - 1; interstitialIndex++) {
949 double interstitialTerrainHeight = pathHeightInfo.
heights[interstitialIndex];
950 double percentTowardsTo = (1.0 / (cHeights - 1)) * interstitialIndex;
952 CoordInfo_t interstitialCoordInfo;
954 interstitialCoordInfo.coord = fromCoordInfo.coord.atDistanceAndAzimuth(
distance * percentTowardsTo,
azimuth);
955 interstitialCoordInfo.coord.setAltitude(interstitialTerrainHeight + distanceToSurface);
963void TransectStyleComplexItem::_buildFlightPathCoordInfoFromPathHeightInfoForTerrainFrame(
void)
968 qCWarning(TransectStyleComplexItemLog) <<
"TransectStyleComplexItem::_buildFlightPathCoordInfoFromPathHeightInfoForTerrainFrame terrain height needed but _rgPathHeightInfo.count() == 0";
975 int pathHeightIndex = 0;
976 for (
int transectIndex=0; transectIndex<
_transects.count(); transectIndex++) {
977 const QList<CoordInfo_t>& transect =
_transects[transectIndex];
980 for (
int transectCoordIndex=0; transectCoordIndex<transect.count() - 1; transectCoordIndex++) {
981 CoordInfo_t fromCoordInfo = transect[transectCoordIndex];
982 CoordInfo_t toCoordInfo = transect[transectCoordIndex+1];
986 fromCoordInfo.coord.setAltitude(distanceToSurface + pathHeightInfo.
heights.first());
987 toCoordInfo.coord.setAltitude(distanceToSurface + pathHeightInfo.
heights.last());
989 if (transectCoordIndex == 0) {
1000void TransectStyleComplexItem::_buildFlightPathCoordInfoFromMissionItems(
void)
1005 qCWarning(TransectStyleComplexItemLog) <<
"_buildFlightPathCoordInfoFromMissionItems - terrain height needed but _rgFlyThroughMissionItemCoordsTerrainHeights.count() == 0";
1009 qCWarning(TransectStyleComplexItemLog) <<
"_buildFlightPathCoordInfoFromMissionItems - _rgFlyThroughMissionItemCoordsTerrainHeights.count() != _rgFlyThroughMissionItemCoords.count()";
1013 qCWarning(TransectStyleComplexItemLog) <<
"_buildFlightPathCoordInfoFromMissionItems - rgFlyThroughMissionItemCoords.count() < 2";
1025 fromCoordInfo.coord.setAltitude(fromCoordInfo.coord.altitude() + heightAtCoord);
1026 toCoordInfo.coord.setAltitude(toCoordInfo.coord.altitude() + heightAtCoord);
1042 BuildMissionItemsState_t buildState = _buildMissionItemsState();
1054 bool firstEntryTurnaround = coordIndex == 0;
1056 if (buildState.addTriggerAtFirstAndLastPoint && (firstEntryTurnaround || lastExitTurnaround)) {
1078 }
else if (buildState.addTriggerAtFirstAndLastPoint && !buildState.hasTurnarounds && lastSurveyExit) {
1080 }
else if (buildState.imagesInTurnaround) {
1098 for (
const QList<CoordInfo_t>& rgCoordInfo:
_transects) {
1099 itemCount += rgCoordInfo.count();
1106void TransectStyleComplexItem::_distanceModeChanged(
int distanceMode)
1114void TransectStyleComplexItem::_handleHoverAndCaptureEnabled(QVariant enabled)
1137 MAV_CMD_NAV_WAYPOINT,
1142 std::numeric_limits<double>::quiet_NaN(),
1155 MAV_CMD_IMAGE_START_CAPTURE,
1161 qQNaN(), qQNaN(), qQNaN(),
1173 MAV_CMD_CONDITION_GATE,
1190 MAV_CMD_DO_SET_CAM_TRIGG_DIST,
1204 if (useConditionGate) {
1212TransectStyleComplexItem::BuildMissionItemsState_t TransectStyleComplexItem::_buildMissionItemsState(
void)
const
1214 BuildMissionItemsState_t state;
1229 BuildMissionItemsState_t buildState = _buildMissionItemsState();
1230 MAV_FRAME mavFrame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
1232 qCDebug(TransectStyleComplexItemLog) <<
"_buildAndAppendMissionItems";
1236 mavFrame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
1240 mavFrame = MAV_FRAME_GLOBAL;
1243 mavFrame = MAV_FRAME_GLOBAL_TERRAIN_ALT;
1247 qCWarning(TransectStyleComplexItemLog) <<
"Internal Error: _buildAndAppendMissionItems incorrect _cameraCalc.distanceMode" <<
_cameraCalc.
distanceMode();
1248 mavFrame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
1262 bool firstEntryTurnaround = coordIndex == 0;
1264 if (buildState.addTriggerAtFirstAndLastPoint && (firstEntryTurnaround || lastExitTurnaround)) {
1294 }
else if (buildState.addTriggerAtFirstAndLastPoint && !buildState.hasTurnarounds && lastSurveyExit) {
1296 }
else if (buildState.imagesInTurnaround) {
1312 qCDebug(TransectStyleComplexItemLog) <<
"_appendLoadedMissionItems";
1327 QDomElement placemarkElement = domDocument.
addPlacemark(QStringLiteral(
"Survey Area"),
true);
1330 placemarkElement.appendChild(polygonElement);
1351 double alt = qQNaN();
1359 alt = distanceToSurface;
1389 qCWarning(TransectStyleComplexItemLog) <<
"Internal Error: amslEntryAlt incorrect _cameraCalc.distanceMode" <<
_cameraCalc.
distanceMode();
1398 double alt = qQNaN();
1433 qCWarning(TransectStyleComplexItemLog) <<
"Internal Error: amslExitAlt incorrect _cameraCalc.distanceMode" <<
_cameraCalc.
distanceMode();
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void save(QJsonObject &json) const
void distanceModeChanged(int altMode)
Fact * distanceToSurface(void)
bool load(const QJsonObject &json, bool deprecatedFollowTerrain, QString &errorString, bool forPresets)
QGroundControlQmlGlobal::AltMode distanceMode(void) const
Fact * valueSetIsDistance(void)
void setDirty(bool dirty)
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)
int _cTerrainCollisionSegments
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.
@ SegmentTypeTerrainFrame
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
double param7(void) const
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)
static constexpr const VehicleClass_t VehicleClassGeneric
void dirtyChanged(bool dirty)
double area(void) const
Returns the area of the polygon in meters squared.
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)
@ AltitudeModeCalcAboveTerrain
@ AltitudeModeTerrainFrame
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
QGeoCoordinate _exitCoordinate
void _appendLoadedMissionItems(QList< MissionItem * > &items, QObject *missionItemParent)
static constexpr const char * cameraTriggerInTurnAroundName
void _updateCoordinateAltitudes(void)
static constexpr const char * terrainAdjustMaxDescentRateName
SettingsFact _refly90DegreesFact
double amslExitAlt(void) const final
int lastSequenceNumber(void) const final
bool hoverAndCaptureEnabled(void) const
double maxAMSLAltitude(void) const final
void _appendSinglePhotoCapture(QList< MissionItem * > &items, QObject *missionItemParent, int &seqNum)
QList< MissionItem * > _loadedMissionItems
Mission items loaded from plan file.
void _recalcComplexDistance(void)
void setMissionFlightStatus(MissionController::MissionFlightStatus_t &missionFlightStatus) final
static constexpr const char * _jsonVisualTransectPointsKey
SettingsFact _terrainAdjustToleranceFact
void _setIfDirty(bool dirty)
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
bool _hasTurnaround(void) const
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
SettingsFact _terrainAdjustMaxDescentRateFact
void addKMLVisuals(KMLPlanDomDocument &domDocument) final
bool triggerCamera(void) const
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)
double _turnAroundDistance(void) const
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.
double coveredArea(void) const
static constexpr int _hoverAndCaptureDelaySeconds
QGCMapPolygon _surveyAreaPolygon
QVariantList _visualTransectPoints
Used to draw the flight path visuals on the screen.
int cameraShots(void) const
SettingsFact _hoverAndCaptureFact
SettingsFact _cameraTriggerInTurnAroundFact
QList< double > _rgFlyThroughMissionItemCoordsTerrainHeights
QGeoCoordinate entryCoordinate(void) const final
double triggerDistance(void) const
void cameraShotsChanged(void)
void _save(QJsonObject &saveObject)
double amslEntryAlt(void) const final
void coveredAreaChanged(void)
void _rebuildTransects(void)
bool dirty(void) const final
void visualTransectPointsChanged(void)
QList< CoordInfo_t > _rgFlightPathCoordInfo
Fully calculated flight path (including terrain if needed)
virtual void _recalcCameraShots(void)=0
bool hoverAndCaptureAllowed(void) const
void timeBetweenShotsChanged(void)
SettingsFact _turnAroundDistanceFact
QGeoCoordinate exitCoordinate(void) const final
SettingsFact _terrainAdjustMaxClimbRateFact
void setDirty(bool dirty) final
QGeoCoordinate _entryCoordinate
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
FirmwarePlugin * firmwarePlugin()
Provides access to the Firmware Plugin for this Vehicle.
void _amslExitAltChanged(void)
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)
Vehicle * _controllerVehicle
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
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.
double vehicleSpeed
Either cruise or hover speed based on vehicle type and vtol state.
QList< double > heights
Terrain heights along path.