6class LandingComplexItemTest;
14 Q_MOC_INCLUDE(
"Fact.h")
15 Q_MOC_INCLUDE(
"MissionItem.h")
86 QString
commandName (
void)
const final {
return "Landing Pattern"; }
95 void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent)
final;
152 QPointF
_rotatePoint (
const QPointF& point,
const QPointF& origin,
double angle);
156 QJsonObject
_save (
void);
157 bool _load (
const QJsonObject& complexObject,
int sequenceNumber,
const QString& jsonComplexItemTypeValue,
bool useDeprecatedRelAltKeys, QString&
errorString);
195 void _recalcFromRadiusChange (
void);
196 void _recalcFromApproachModeChange (
void);
197 void _signalLastSequenceNumberChanged (
void);
198 void _updateFinalApproachCoodinateAltitudeFromFact (
void);
199 void _updateLandingCoodinateAltitudeFromFact (
void);
201#ifdef QGC_UNITTEST_BUILD
202 friend class LandingComplexItemTest;
A Fact is used to hold a single value within the system.
Q_INVOKABLE void setLandingHeadingToTakeoffHeading()
virtual const Fact * _landingAltitude(void) const =0
const Fact * landingAltitude(void) const
static constexpr const char * stopTakingPhotosName
static constexpr const char * useDoChangeSpeedName
bool _altitudesAreRelative
virtual void _updateFlightPathSegmentsDontCallDirectly(void)=0
QString abbreviation(void) const final
void landingCoordSetChanged(bool landingCoordSet)
bool _ignoreRecalcSignals
virtual const Fact * _loiterClockwise(void) const =0
static constexpr const char * stopTakingVideoName
Fact * stopTakingVideo(void)
static constexpr const char * _jsonAltitudesAreRelativeKey
const Fact * finalApproachSpeed(void) const
static bool _scanForItem(QmlObjectListModel *visualItems, int &startIndex, bool flyView, PlanMasterController *masterController, IsLandItemFunc isLandItemFunc, CreateItemFunc createItemFunc)
static constexpr const char * landingAltitudeName
static constexpr const char * _jsonStopTakingVideoKey
static constexpr const char * finalApproachSpeedName
static constexpr const char * _jsonStopTakingPhotosKey
QGeoCoordinate _slopeStartCoordinate
double maxAMSLAltitude(void) const final
void _recalcFromCoordinateChange(void)
static constexpr const char * _jsonDeprecatedLoiterAltitudeRelativeKey
double amslEntryAlt(void) const final
void setSequenceNumber(int sequenceNumber) final
bool _load(const QJsonObject &complexObject, int sequenceNumber, const QString &jsonComplexItemTypeValue, bool useDeprecatedRelAltKeys, QString &errorString)
const Fact * loiterClockwise(void) const
bool landingCoordSet(void) const
Fact * landingHeading(void)
QGeoCoordinate _finalApproachCoordinate
void setLandingCoordinate(const QGeoCoordinate &coordinate)
static constexpr const char * _jsonFinalApproachSpeedKey
QGeoCoordinate slopeStartCoordinate(void) const
QGeoCoordinate exitCoordinate(void) const final
const Fact * landingDistance(void) const
void applyNewAltitude(double newAltitude) final
Adjust the altitude of the item if appropriate to the new altitude.
void finalApproachCoordinateChanged(QGeoCoordinate coordinate)
static constexpr const char * landingHeadingName
double greatestDistanceTo(const QGeoCoordinate &other) const final
void setDirty(bool dirty) final
void altitudesAreRelativeChanged(bool altitudesAreRelative)
bool(* IsLandItemFunc)(const MissionItem &missionItem)
static constexpr const char * _jsonFinalApproachCoordinateKey
static constexpr const char * finalApproachToLandDistanceName
static constexpr const char * finalApproachAltitudeName
static bool _scanForItems(QmlObjectListModel *visualItems, bool flyView, PlanMasterController *masterController, IsLandItemFunc isLandItemFunc, CreateItemFunc createItemFunc)
Fact * finalApproachAltitude(void)
QGeoCoordinate entryCoordinate(void) const final
static constexpr const char * useLoiterToAltName
static constexpr const char * _jsonLoiterClockwiseKey
double specifiedGimbalYaw(void) final
QGeoCoordinate coordinate(void) const final
MissionItem * _createDoLandStartItem(int seqNum, QObject *parent)
void _updateFlightPathSegmentsSignal(void)
virtual const Fact * _landingDistance(void) const =0
virtual const Fact * _loiterRadius(void) const =0
double minAMSLAltitude(void) const final
static constexpr const char * _jsonUseDoChangeSpeedKey
bool altitudesAreRelative(void) const
void landingCoordinateChanged(QGeoCoordinate coordinate)
double complexDistance(void) const final
virtual const Fact * _landingHeading(void) const =0
ReadyForSaveState readyForSaveState(void) const final
QGeoCoordinate finalApproachCoordinate(void) const
bool exitCoordinateSameAsEntry(void) const final
bool isStandaloneCoordinate(void) const final
Fact * useDoChangeSpeed(void)
void slopeStartCoordinateChanged(QGeoCoordinate coordinate)
const Fact * stopTakingPhotos(void) const
const Fact * useDoChangeSpeed(void) const
double specifiedFlightSpeed(void) final
double specifiedGimbalPitch(void) final
static constexpr const char * _jsonLoiterRadiusKey
MissionItem * _createDoChangeSpeedItem(int speedType, int speedValue, int throttlePercentage, int seqNum, QObject *parent)
virtual const Fact * _useDoChangeSpeed(void) const =0
virtual const Fact * _stopTakingPhotos(void) const =0
virtual const Fact * _stopTakingVideo(void) const =0
virtual const Fact * _finalApproachSpeed(void) const =0
static constexpr const char * _jsonUseLoiterToAltKey
const Fact * landingHeading(void) const
int lastSequenceNumber(void) const final
QString commandDescription(void) const final
LandingComplexItem *(* CreateItemFunc)(PlanMasterController *masterController, bool flyView)
QGeoCoordinate landingCoordinate(void) const
void setCoordinate(const QGeoCoordinate &coordinate) final
static constexpr const char * loiterRadiusName
double amslExitAlt(void) const final
virtual void _calcGlideSlope(void)=0
bool specifiesCoordinate(void) const final
bool isLandCommand(void) const final
const Fact * useLoiterToAlt(void) const
double additionalTimeDelay(void) const final
MissionItem * _createFinalApproachItem(int seqNum, QObject *parent)
virtual const Fact * _useLoiterToAlt(void) const =0
QGeoCoordinate _landingCoordinate
static constexpr const char * _jsonLandingCoordinateKey
void _recalcFromHeadingAndDistanceChange(void)
const Fact * loiterRadius(void) const
Fact * loiterRadius(void)
static constexpr const char * _jsonDeprecatedLandingAltitudeRelativeKey
void setAltitudesAreRelative(bool altitudesAreRelative)
double editableAlt(void) const final
const Fact * stopTakingVideo(void) const
bool specifiesAltitudeOnly(void) const final
void appendMissionItems(QList< MissionItem * > &items, QObject *missionItemParent) final
virtual const Fact * _finalApproachAltitude(void) const =0
QPointF _rotatePoint(const QPointF &point, const QPointF &origin, double angle)
static constexpr const char * loiterClockwiseName
Fact * stopTakingPhotos(void)
int sequenceNumber(void) const final
void setFinalApproachCoordinate(const QGeoCoordinate &coordinate)
Fact * landingDistance(void)
Fact * landingAltitude(void)
Fact * useLoiterToAlt(void)
QString commandName(void) const final
static constexpr const char * _jsonDeprecatedLoiterCoordinateKey
Fact * loiterClockwise(void)
virtual MissionItem * _createLandItem(int seqNum, bool altRel, double lat, double lon, double alt, QObject *parent)=0
const Fact * finalApproachAltitude(void) const
bool dirty(void) const final
bool isSimpleItem(void) const final
Fact * finalApproachSpeed(void)
Master controller for mission, fence, rally.
PlanMasterController * masterController(void)