17#include <QtCore/QJsonArray>
23 , _cameraCalc (masterController, settingsGroup)
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])
34 _terrainPolyPathQueryTimer.setSingleShot(
true);
35 connect(&_terrainPolyPathQueryTimer, &QTimer::timeout,
this, &TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo);
90 connect(&_hoverAndCaptureFact, &
Fact::rawValueChanged,
this, &TransectStyleComplexItem::_handleHoverAndCaptureEnabled);
135 QList<QGeoCoordinate> translatedVertices;
136 translatedVertices.reserve(vertices.count());
137 for (
const QGeoCoordinate& vertex: vertices) {
138 translatedVertices.append(vertex.atDistanceAndAzimuth(distanceMeters, azimuthDegrees));
146 QJsonObject innerObject;
162 QJsonObject cameraCalcObject;
166 QJsonValue transectPointsJson;
173 QJsonArray missionItemsJsonArray;
174 QObject* missionItemParent =
new QObject();
175 QList<MissionItem*> missionItems;
177 for (
const MissionItem* missionItem: missionItems) {
178 QJsonObject missionItemJsonObject;
179 missionItem->save(missionItemJsonObject);
180 missionItemsJsonArray.append(missionItemJsonObject);
182 missionItemParent->deleteLater();
199 QList<JsonParsing::KeyValidateInfo> keyInfoList = {
210 bool v1FollowTerrain =
false;
225 v1FollowTerrain = innerObject[_jsonTerrainFollowKeyDeprecated].toBool();
226 innerObject.remove(_jsonTerrainFollowKeyDeprecated);
230 errorString = tr(
"TransectStyleComplexItem version %2 not supported").arg(version);
234 QList<JsonParsing::KeyValidateInfo> innerKeyInfoList = {
260 QJsonArray missionItemsJsonArray = innerObject[
_jsonItemsKey].toArray();
261 for (
const QJsonValue missionItemJson: missionItemsJsonArray) {
290 QList<JsonParsing::KeyValidateInfo> followTerrainKeyInfoList = {
324 _queryMissionItemCoordHeights();
339 double greatestDistance = 0.0;
342 double distance = vertex.distanceTo(other);
348 return greatestDistance;
417 qCWarning(TransectStyleComplexItemLog) <<
"Internal Error: _rebuildTransects - invalid _cameraCalc.distanceMode()" <<
_cameraCalc.
distanceMode();
424 _buildFlightPathCoordInfoFromTransects();
429 _queryTransectsPathHeightInfo();
435 double south = 180.0;
438 double bottom = 100000.;
442 for (
const QList<CoordInfo_t>& transect:
_transects) {
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());
457 QGeoCoordinate(north - 90.0, west - 180.0, bottom),
458 QGeoCoordinate(south - 90.0, east - 180.0, top)));
485void TransectStyleComplexItem::_segmentTerrainCollisionChanged(
bool terrainCollision)
492void TransectStyleComplexItem::_updateFlightPathSegmentsDontCallDirectly(
void)
506 qCWarning(TransectStyleComplexItemLog) <<
"Internal Error: _updateFlightPathSegmentsDontCallDirectly - invalid _cameraCalc.distanceMode()" <<
_cameraCalc.
distanceMode();
513 QGeoCoordinate prevCoord;
516 QGeoCoordinate thisCoord = varCoord.value<QGeoCoordinate>();
517 if (prevCoord.isValid()) {
520 prevCoord = thisCoord;
528 QGeoCoordinate prevCoord = QGeoCoordinate();
531 if (missionItem->command() == MAV_CMD_NAV_WAYPOINT || missionItem->command() == MAV_CMD_CONDITION_GATE) {
532 if (prevCoord.isValid()) {
535 prevCoord = missionItem->coordinate();
536 prevAlt = missionItem->param7();
566void TransectStyleComplexItem::_queryTransectsPathHeightInfo(
void)
574 _terrainPolyPathQueryTimer.start();
578void TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo(
void)
580 qCDebug(TransectStyleComplexItemLog) <<
"_reallyQueryTransectsPathHeightInfo";
583 if (_currentTerrainPolyPathQuery) {
584 disconnect(_currentTerrainPolyPathQuery);
585 _currentTerrainPolyPathQuery =
nullptr;
587 if (_currentTerrainAtCoordinateQuery) {
588 disconnect(_currentTerrainAtCoordinateQuery);
589 _currentTerrainAtCoordinateQuery =
nullptr;
593 QList<QGeoCoordinate> transectPoints;
594 for (
const QList<CoordInfo_t>& transect:
_transects) {
595 for (
const CoordInfo_t& coordInfo: transect) {
596 transectPoints.append(coordInfo.coord);
600 if (transectPoints.count() > 1) {
603 _currentTerrainPolyPathQuery->
requestData(transectPoints);
607void TransectStyleComplexItem::_queryMissionItemCoordHeights(
void)
609 qCDebug(TransectStyleComplexItemLog) <<
"_queryMissionItemCoordHeights";
613 if (_currentTerrainAtCoordinateQuery) {
614 qCWarning(TransectStyleComplexItemLog) <<
"Internal error: _queryMissionItemCoordHeights called multiple times";
616 disconnect(_currentTerrainPolyPathQuery);
617 _currentTerrainPolyPathQuery =
nullptr;
622 if (missionItem->frame() == MAV_FRAME_GLOBAL_TERRAIN_ALT) {
639 qCDebug(TransectStyleComplexItemLog) <<
"_polyPathTerrainData" << success;
647 _adjustForAvailableTerrainData();
650 _currentTerrainPolyPathQuery =
nullptr;
655 qCDebug(TransectStyleComplexItemLog) <<
"_polyPathTerrainData" << success;
663 _adjustForAvailableTerrainData();
666 _currentTerrainPolyPathQuery =
nullptr;
671 bool terrainReady =
false;
690void TransectStyleComplexItem::_adjustForAvailableTerrainData(
void)
695 qCWarning(TransectStyleComplexItemLog) <<
"Internal Error: _adjustForAvailableTerrainData - invalid _cameraCalc.distanceMode()" <<
_cameraCalc.
distanceMode();
702 _buildFlightPathCoordInfoFromPathHeightInfoForCalcAboveTerrain();
703 _adjustForMaxRates();
704 _adjustForTolerance();
715 _buildFlightPathCoordInfoFromMissionItems();
717 _buildFlightPathCoordInfoFromPathHeightInfoForTerrainFrame();
731double TransectStyleComplexItem::_altitudeBetweenCoords(
const QGeoCoordinate& fromCoord,
const QGeoCoordinate& toCoord,
double percentTowardsTo)
733 double fromAlt = fromCoord.altitude();
734 double toAlt = toCoord.altitude();
735 double altDiff = toAlt - fromAlt;
736 return fromAlt + (altDiff * percentTowardsTo);
748 if (toIndex - fromIndex < 2) {
755 int maxIndex = fromIndex;
756 maxHeight = pathHeightInfo.
heights[fromIndex];
758 for (
int i=fromIndex; i<=toIndex; i++) {
759 if (pathHeightInfo.
heights[i] > maxHeight) {
761 maxHeight = pathHeightInfo.
heights[i];
768void TransectStyleComplexItem::_adjustForMaxRates(
void)
774 if (qIsNaN(flightSpeed) || (maxClimbRate == 0 && maxDescentRate == 0)) {
775 if (qIsNaN(flightSpeed)) {
776 qWarning() <<
"TransectStyleComplexItem::_adjustForMaxRates called with flightSpeed = NaN";
780 if (maxClimbRate <= 0 && maxDescentRate <= 0) {
784 if (maxClimbRate > 0) {
785 bool climbRateAdjusted;
788 climbRateAdjusted =
false;
793 double altDifference = toCoord.altitude() - fromCoord.altitude();
794 double distance = fromCoord.distanceTo(toCoord);
795 double seconds =
distance / flightSpeed;
800 if (climbRate > 0 && climbRate - maxClimbRate > 0.1) {
801 double maxAltitudeDelta = maxClimbRate * seconds;
802 fromCoord.setAltitude(toCoord.altitude() - maxAltitudeDelta);
804 climbRateAdjusted =
true;
807 }
while (climbRateAdjusted);
810 if (maxDescentRate > 0) {
811 bool descentRateAdjusted;
812 maxDescentRate = -maxDescentRate;
815 descentRateAdjusted =
false;
820 double altDifference = toCoord.altitude() - fromCoord.altitude();
821 double distance = fromCoord.distanceTo(toCoord);
822 double seconds =
distance / flightSpeed;
827 if (descentRate < 0 && descentRate - maxDescentRate < -0.1) {
828 double maxAltitudeDelta = maxDescentRate * seconds;
829 toCoord.setAltitude(fromCoord.altitude() + maxAltitudeDelta);
831 descentRateAdjusted =
true;
834 }
while (descentRateAdjusted);
838void TransectStyleComplexItem::_adjustForTolerance(
void)
840 QList<CoordInfo_t> adjustedFlightPath;
844 adjustedFlightPath.append(lastCoordInfo);
851 if (nextCoordInfo.coordType !=
CoordTypeInteriorTerrainAdded || qAbs(lastCoordInfo.coord.altitude() - nextCoordInfo.coord.altitude()) > tolerance) {
852 adjustedFlightPath.append(nextCoordInfo);
853 lastCoordInfo = nextCoordInfo;
861void TransectStyleComplexItem::_buildFlightPathCoordInfoFromTransects(
void)
868 for (
int transectIndex=0; transectIndex<
_transects.count(); transectIndex++) {
869 const QList<CoordInfo_t>& transect =
_transects[transectIndex];
871 for (
int transectCoordIndex=0; transectCoordIndex<transect.count() - 1; transectCoordIndex++) {
872 CoordInfo_t fromCoordInfo = transect[transectCoordIndex];
873 CoordInfo_t toCoordInfo = transect[transectCoordIndex+1];
875 fromCoordInfo.coord.setAltitude(distanceToSurface);
876 toCoordInfo.coord.setAltitude(distanceToSurface);
878 if (transectCoordIndex == 0) {
886void TransectStyleComplexItem::_buildFlightPathCoordInfoFromPathHeightInfoForCalcAboveTerrain(
void)
891 qCWarning(TransectStyleComplexItemLog) <<
"TransectStyleComplexItem::_buildFlightPathCoordInfoFromPathHeightInfo terrain height needed but _rgPathHeightInfo.count() == 0";
898 int pathHeightIndex = 0;
899 for (
int transectIndex=0; transectIndex<
_transects.count(); transectIndex++) {
900 const QList<CoordInfo_t>& transect =
_transects[transectIndex];
903 for (
int transectCoordIndex=0; transectCoordIndex<transect.count() - 1; transectCoordIndex++) {
904 CoordInfo_t fromCoordInfo = transect[transectCoordIndex];
905 CoordInfo_t toCoordInfo = transect[transectCoordIndex+1];
909 fromCoordInfo.coord.setAltitude(distanceToSurface + pathHeightInfo.
heights.first());
910 toCoordInfo.coord.setAltitude(distanceToSurface + pathHeightInfo.
heights.last());
912 if (transectCoordIndex == 0) {
917 int cHeights = pathHeightInfo.
heights.count();
919 double azimuth = fromCoordInfo.coord.azimuthTo(toCoordInfo.coord);
920 double distance = fromCoordInfo.coord.distanceTo(toCoordInfo.coord);
922 for (
int interstitialIndex=1; interstitialIndex<cHeights - 1; interstitialIndex++) {
923 double interstitialTerrainHeight = pathHeightInfo.
heights[interstitialIndex];
924 double percentTowardsTo = (1.0 / (cHeights - 1)) * interstitialIndex;
926 CoordInfo_t interstitialCoordInfo;
928 interstitialCoordInfo.coord = fromCoordInfo.coord.atDistanceAndAzimuth(
distance * percentTowardsTo,
azimuth);
929 interstitialCoordInfo.coord.setAltitude(interstitialTerrainHeight + distanceToSurface);
939 if (transectIndex !=
_transects.count() - 1) {
942 int cHeights = pathHeightInfo.
heights.count();
944 CoordInfo_t fromCoordInfo =
_transects[transectIndex].last();
945 CoordInfo_t toCoordInfo =
_transects[transectIndex+1].first();
947 double azimuth = fromCoordInfo.coord.azimuthTo(toCoordInfo.coord);
948 double distance = fromCoordInfo.coord.distanceTo(toCoordInfo.coord);
950 for (
int interstitialIndex=1; interstitialIndex<cHeights - 1; interstitialIndex++) {
951 double interstitialTerrainHeight = pathHeightInfo.
heights[interstitialIndex];
952 double percentTowardsTo = (1.0 / (cHeights - 1)) * interstitialIndex;
954 CoordInfo_t interstitialCoordInfo;
956 interstitialCoordInfo.coord = fromCoordInfo.coord.atDistanceAndAzimuth(
distance * percentTowardsTo,
azimuth);
957 interstitialCoordInfo.coord.setAltitude(interstitialTerrainHeight + distanceToSurface);
965void TransectStyleComplexItem::_buildFlightPathCoordInfoFromPathHeightInfoForTerrainFrame(
void)
970 qCWarning(TransectStyleComplexItemLog) <<
"TransectStyleComplexItem::_buildFlightPathCoordInfoFromPathHeightInfoForTerrainFrame terrain height needed but _rgPathHeightInfo.count() == 0";
977 int pathHeightIndex = 0;
978 for (
int transectIndex=0; transectIndex<
_transects.count(); transectIndex++) {
979 const QList<CoordInfo_t>& transect =
_transects[transectIndex];
982 for (
int transectCoordIndex=0; transectCoordIndex<transect.count() - 1; transectCoordIndex++) {
983 CoordInfo_t fromCoordInfo = transect[transectCoordIndex];
984 CoordInfo_t toCoordInfo = transect[transectCoordIndex+1];
988 fromCoordInfo.coord.setAltitude(distanceToSurface + pathHeightInfo.
heights.first());
989 toCoordInfo.coord.setAltitude(distanceToSurface + pathHeightInfo.
heights.last());
991 if (transectCoordIndex == 0) {
1002void TransectStyleComplexItem::_buildFlightPathCoordInfoFromMissionItems(
void)
1007 qCWarning(TransectStyleComplexItemLog) <<
"_buildFlightPathCoordInfoFromMissionItems - terrain height needed but _rgFlyThroughMissionItemCoordsTerrainHeights.count() == 0";
1011 qCWarning(TransectStyleComplexItemLog) <<
"_buildFlightPathCoordInfoFromMissionItems - _rgFlyThroughMissionItemCoordsTerrainHeights.count() != _rgFlyThroughMissionItemCoords.count()";
1015 qCWarning(TransectStyleComplexItemLog) <<
"_buildFlightPathCoordInfoFromMissionItems - rgFlyThroughMissionItemCoords.count() < 2";
1027 fromCoordInfo.coord.setAltitude(fromCoordInfo.coord.altitude() + heightAtCoord);
1028 toCoordInfo.coord.setAltitude(toCoordInfo.coord.altitude() + heightAtCoord);
1044 BuildMissionItemsState_t buildState = _buildMissionItemsState();
1056 bool firstEntryTurnaround = coordIndex == 0;
1058 if (buildState.addTriggerAtFirstAndLastPoint && (firstEntryTurnaround || lastExitTurnaround)) {
1080 }
else if (buildState.addTriggerAtFirstAndLastPoint && !buildState.hasTurnarounds && lastSurveyExit) {
1082 }
else if (buildState.imagesInTurnaround) {
1100 for (
const QList<CoordInfo_t>& rgCoordInfo:
_transects) {
1101 itemCount += rgCoordInfo.count();
1108void TransectStyleComplexItem::_distanceModeChanged(
int distanceMode)
1116void TransectStyleComplexItem::_handleHoverAndCaptureEnabled(QVariant enabled)
1139 MAV_CMD_NAV_WAYPOINT,
1144 std::numeric_limits<double>::quiet_NaN(),
1157 MAV_CMD_IMAGE_START_CAPTURE,
1163 qQNaN(), qQNaN(), qQNaN(),
1175 MAV_CMD_CONDITION_GATE,
1192 MAV_CMD_DO_SET_CAM_TRIGG_DIST,
1206 if (useConditionGate) {
1214TransectStyleComplexItem::BuildMissionItemsState_t TransectStyleComplexItem::_buildMissionItemsState(
void)
const
1216 BuildMissionItemsState_t state;
1231 BuildMissionItemsState_t buildState = _buildMissionItemsState();
1232 MAV_FRAME mavFrame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
1234 qCDebug(TransectStyleComplexItemLog) <<
"_buildAndAppendMissionItems";
1238 mavFrame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
1242 mavFrame = MAV_FRAME_GLOBAL;
1245 mavFrame = MAV_FRAME_GLOBAL_TERRAIN_ALT;
1249 qCWarning(TransectStyleComplexItemLog) <<
"Internal Error: _buildAndAppendMissionItems incorrect _cameraCalc.distanceMode" <<
_cameraCalc.
distanceMode();
1250 mavFrame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
1264 bool firstEntryTurnaround = coordIndex == 0;
1266 if (buildState.addTriggerAtFirstAndLastPoint && (firstEntryTurnaround || lastExitTurnaround)) {
1296 }
else if (buildState.addTriggerAtFirstAndLastPoint && !buildState.hasTurnarounds && lastSurveyExit) {
1298 }
else if (buildState.imagesInTurnaround) {
1314 qCDebug(TransectStyleComplexItemLog) <<
"_appendLoadedMissionItems";
1329 QDomElement placemarkElement = domDocument.
addPlacemark(QStringLiteral(
"Survey Area"),
true);
1332 placemarkElement.appendChild(polygonElement);
1353 double alt = qQNaN();
1361 alt = distanceToSurface;
1391 qCWarning(TransectStyleComplexItemLog) <<
"Internal Error: amslEntryAlt incorrect _cameraCalc.distanceMode" <<
_cameraCalc.
distanceMode();
1400 double alt = qQNaN();
1435 qCWarning(TransectStyleComplexItemLog) <<
"Internal Error: amslExitAlt incorrect _cameraCalc.distanceMode" <<
_cameraCalc.
distanceMode();
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void save(QJsonObject &json) const
void distanceModeChanged(int altFrame)
Fact * distanceToSurface(void)
bool load(const QJsonObject &json, bool deprecatedFollowTerrain, QString &errorString, bool forPresets)
QGroundControlQmlGlobal::AltitudeFrame 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 setRawValue(const QVariant &value)
QVariant rawValue() const
Value after translation.
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.
@ 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)
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
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)
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)
@ AltitudeFrameCalcAboveTerrain
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
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)
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 setMissionFlightStatus(MissionFlightStatus_t &missionFlightStatus) final
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
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
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.
static constexpr VehicleClass_t VehicleClassGeneric
QList< double > heights
Terrain heights along path.