QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
LandingComplexItem.h
Go to the documentation of this file.
1#pragma once
2
4
6class LandingComplexItemTest;
7class Fact;
8class MissionItem;
9
10// Base class for landing patterns complex items.
12{
13 Q_OBJECT
14 Q_MOC_INCLUDE("Fact.h")
15 Q_MOC_INCLUDE("MissionItem.h")
16
17public:
19
20 Q_PROPERTY(Fact* finalApproachAltitude READ finalApproachAltitude CONSTANT)
21 Q_PROPERTY(Fact* useDoChangeSpeed READ useDoChangeSpeed CONSTANT)
22 Q_PROPERTY(Fact* finalApproachSpeed READ finalApproachSpeed CONSTANT)
23 Q_PROPERTY(Fact* loiterRadius READ loiterRadius CONSTANT)
24 Q_PROPERTY(Fact* landingAltitude READ landingAltitude CONSTANT)
25 Q_PROPERTY(Fact* landingHeading READ landingHeading CONSTANT)
26 Q_PROPERTY(Fact* landingDistance READ landingDistance CONSTANT)
27 Q_PROPERTY(Fact* loiterClockwise READ loiterClockwise CONSTANT)
28 Q_PROPERTY(Fact* useLoiterToAlt READ useLoiterToAlt CONSTANT)
29 Q_PROPERTY(Fact* stopTakingPhotos READ stopTakingPhotos CONSTANT)
30 Q_PROPERTY(Fact* stopTakingVideo READ stopTakingVideo CONSTANT)
32 Q_PROPERTY(QGeoCoordinate slopeStartCoordinate READ slopeStartCoordinate NOTIFY slopeStartCoordinateChanged)
33 Q_PROPERTY(QGeoCoordinate landingCoordinate READ landingCoordinate WRITE setLandingCoordinate NOTIFY landingCoordinateChanged)
35 Q_PROPERTY(bool landingCoordSet READ landingCoordSet NOTIFY landingCoordSetChanged)
36
37 Q_INVOKABLE void setLandingHeadingToTakeoffHeading();
38
39 const Fact* finalApproachAltitude (void) const { return _finalApproachAltitude(); }
40 const Fact* useDoChangeSpeed (void) const { return _useDoChangeSpeed(); }
41 const Fact* finalApproachSpeed (void) const { return _finalApproachSpeed(); }
42 const Fact* loiterRadius (void) const { return _loiterRadius(); }
43 const Fact* loiterClockwise (void) const { return _loiterClockwise(); }
44 const Fact* landingAltitude (void) const { return _landingAltitude(); }
45 const Fact* landingDistance (void) const { return _landingDistance(); }
46 const Fact* landingHeading (void) const { return _landingHeading(); }
47 const Fact* useLoiterToAlt (void) const { return _useLoiterToAlt(); }
48 const Fact* stopTakingPhotos (void) const { return _stopTakingPhotos(); }
49 const Fact* stopTakingVideo (void) const { return _stopTakingVideo(); }
50
51 Fact* finalApproachAltitude (void) { return const_cast<Fact*>(const_cast<const LandingComplexItem*>(this)->_finalApproachAltitude()); };
52 Fact* useDoChangeSpeed (void) { return const_cast<Fact*>(const_cast<const LandingComplexItem*>(this)->_useDoChangeSpeed()); };
53 Fact* finalApproachSpeed (void) { return const_cast<Fact*>(const_cast<const LandingComplexItem*>(this)->_finalApproachSpeed()); };
54 Fact* loiterRadius (void) { return const_cast<Fact*>(const_cast<const LandingComplexItem*>(this)->_loiterRadius()); };
55 Fact* loiterClockwise (void) { return const_cast<Fact*>(const_cast<const LandingComplexItem*>(this)->_loiterClockwise()); };
56 Fact* landingAltitude (void) { return const_cast<Fact*>(const_cast<const LandingComplexItem*>(this)->_landingAltitude()); };
57 Fact* landingDistance (void) { return const_cast<Fact*>(const_cast<const LandingComplexItem*>(this)->_landingDistance()); };
58 Fact* landingHeading (void) { return const_cast<Fact*>(const_cast<const LandingComplexItem*>(this)->_landingHeading()); };
59 Fact* useLoiterToAlt (void) { return const_cast<Fact*>(const_cast<const LandingComplexItem*>(this)->_useLoiterToAlt()); };
60 Fact* stopTakingPhotos (void) { return const_cast<Fact*>(const_cast<const LandingComplexItem*>(this)->_stopTakingPhotos()); };
61 Fact* stopTakingVideo (void) { return const_cast<Fact*>(const_cast<const LandingComplexItem*>(this)->_stopTakingVideo()); };
62
63 bool altitudesAreRelative (void) const { return _altitudesAreRelative; }
64 bool landingCoordSet (void) const { return _landingCoordSet; }
65 QGeoCoordinate landingCoordinate (void) const { return _landingCoordinate; }
66 QGeoCoordinate finalApproachCoordinate (void) const { return _finalApproachCoordinate; }
67 QGeoCoordinate slopeStartCoordinate (void) const { return _slopeStartCoordinate; }
68
69 void setLandingCoordinate (const QGeoCoordinate& coordinate);
70 void setFinalApproachCoordinate (const QGeoCoordinate& coordinate);
72
73 // Overrides from ComplexMissionItem
74 double complexDistance (void) const final;
75 double greatestDistanceTo (const QGeoCoordinate &other) const final;
76 int lastSequenceNumber (void) const final;
77
78 // Overrides from VisualMissionItem
79 bool dirty (void) const final { return _dirty; }
80 bool isSimpleItem (void) const final { return false; }
81 bool isLandCommand (void) const final { return true; }
82 bool isStandaloneCoordinate (void) const final { return false; }
83 bool specifiesCoordinate (void) const final { return true; }
84 bool specifiesAltitudeOnly (void) const final { return false; }
85 QString commandDescription (void) const final { return "Landing Pattern"; }
86 QString commandName (void) const final { return "Landing Pattern"; }
87 QString abbreviation (void) const final { return "L"; }
88 QGeoCoordinate coordinate (void) const final { return exitCoordinate(); }
89 QGeoCoordinate entryCoordinate (void) const final { return _finalApproachCoordinate; }
90 QGeoCoordinate exitCoordinate (void) const final { return _landingCoordinate; }
91 int sequenceNumber (void) const final { return _sequenceNumber; }
92 double specifiedFlightSpeed (void) final { return std::numeric_limits<double>::quiet_NaN(); }
93 double specifiedGimbalYaw (void) final { return std::numeric_limits<double>::quiet_NaN(); }
94 double specifiedGimbalPitch (void) final { return std::numeric_limits<double>::quiet_NaN(); }
95 void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
96 void applyNewAltitude (double newAltitude) final;
97 double additionalTimeDelay (void) const final { return 0; }
98 ReadyForSaveState readyForSaveState (void) const final;
99 bool exitCoordinateSameAsEntry (void) const final { return false; }
100 void setDirty (bool dirty) final;
101 void setCoordinate (const QGeoCoordinate& coordinate) final;
102 void setSequenceNumber (int sequenceNumber) final;
103 double editableAlt (void) const final;
104 double amslEntryAlt (void) const final;
105 double amslExitAlt (void) const final;
106 double minAMSLAltitude (void) const final { return amslExitAlt(); }
107 double maxAMSLAltitude (void) const final { return amslEntryAlt(); }
108
109 static constexpr const char* finalApproachToLandDistanceName = "LandingDistance";
110 static constexpr const char* landingHeadingName = "LandingHeading";
111 static constexpr const char* finalApproachAltitudeName = "FinalApproachAltitude";
112 static constexpr const char* useDoChangeSpeedName = "UseDoChangeSpeed";
113 static constexpr const char* finalApproachSpeedName = "FinalApproachSpeed";
114 static constexpr const char* loiterRadiusName = "LoiterRadius";
115 static constexpr const char* loiterClockwiseName = "LoiterClockwise";
116 static constexpr const char* landingAltitudeName = "LandingAltitude";
117 static constexpr const char* useLoiterToAltName = "UseLoiterToAlt";
118 static constexpr const char* stopTakingPhotosName = "StopTakingPhotos";
119 static constexpr const char* stopTakingVideoName = "StopTakingVideo";
120
121signals:
128
129protected slots:
131
133 void _recalcFromCoordinateChange (void);
134 void _setDirty (void);
135
136protected:
137 virtual const Fact* _finalApproachAltitude (void) const = 0;
138 virtual const Fact* _useDoChangeSpeed (void) const = 0;
139 virtual const Fact* _finalApproachSpeed (void) const = 0;
140 virtual const Fact* _loiterRadius (void) const = 0;
141 virtual const Fact* _loiterClockwise (void) const = 0;
142 virtual const Fact* _landingAltitude (void) const = 0;
143 virtual const Fact* _landingDistance (void) const = 0;
144 virtual const Fact* _landingHeading (void) const = 0;
145 virtual const Fact* _useLoiterToAlt (void) const = 0;
146 virtual const Fact* _stopTakingPhotos (void) const = 0;
147 virtual const Fact* _stopTakingVideo (void) const = 0;
148 virtual void _calcGlideSlope (void) = 0;
149 virtual MissionItem* _createLandItem (int seqNum, bool altRel, double lat, double lon, double alt, QObject* parent) = 0;
150
151 void _init (void);
152 QPointF _rotatePoint (const QPointF& point, const QPointF& origin, double angle);
153 MissionItem* _createDoLandStartItem (int seqNum, QObject* parent);
154 MissionItem* _createDoChangeSpeedItem(int speedType, int speedValue, int throttlePercentage, int seqNum, QObject* parent);
155 MissionItem* _createFinalApproachItem(int seqNum, QObject* parent);
156 QJsonObject _save (void);
157 bool _load (const QJsonObject& complexObject, int sequenceNumber, const QString& jsonComplexItemTypeValue, bool useDeprecatedRelAltKeys, QString& errorString);
158
159 typedef bool (*IsLandItemFunc)(const MissionItem& missionItem);
161
162 static bool _scanForItems(QmlObjectListModel* visualItems, bool flyView, PlanMasterController* masterController, IsLandItemFunc isLandItemFunc, CreateItemFunc createItemFunc);
163 static bool _scanForItem(QmlObjectListModel* visualItems, int& startIndex, bool flyView, PlanMasterController* masterController, IsLandItemFunc isLandItemFunc, CreateItemFunc createItemFunc);
164
166 bool _dirty = false;
168 QGeoCoordinate _slopeStartCoordinate;
169 QGeoCoordinate _landingCoordinate;
170 bool _landingCoordSet = false;
173
174 // Support for separate relative alt settings for land/loiter was removed. It now only has a single
175 // relative alt setting stored in _jsonAltitudesAreRelativeKey.
176 static constexpr const char* _jsonDeprecatedLandingAltitudeRelativeKey = "landAltitudeRelative";
177 static constexpr const char* _jsonDeprecatedLoiterAltitudeRelativeKey = "loiterAltitudeRelative";
178
179 // Name changed from _jsonDeprecatedLoiterCoordinateKey to _jsonFinalApproachCoordinateKey to reflect
180 // the new support for using either a loiter or just a waypoint as the approach entry point.
181 static constexpr const char* _jsonDeprecatedLoiterCoordinateKey = "loiterCoordinate";
182
183 static constexpr const char* _jsonFinalApproachCoordinateKey = "landingApproachCoordinate";
184 static constexpr const char* _jsonUseDoChangeSpeedKey = "useDoChangeSpeed";
185 static constexpr const char* _jsonFinalApproachSpeedKey = "finalApproachSpeed";
186 static constexpr const char* _jsonLoiterRadiusKey = "loiterRadius";
187 static constexpr const char* _jsonLoiterClockwiseKey = "loiterClockwise";
188 static constexpr const char* _jsonLandingCoordinateKey = "landCoordinate";
189 static constexpr const char* _jsonAltitudesAreRelativeKey = "altitudesAreRelative";
190 static constexpr const char* _jsonUseLoiterToAltKey = "useLoiterToAlt";
191 static constexpr const char* _jsonStopTakingPhotosKey = "stopTakingPhotos";
192 static constexpr const char* _jsonStopTakingVideoKey = "stopVideoPhotos";
193
194private slots:
195 void _recalcFromRadiusChange (void);
196 void _recalcFromApproachModeChange (void);
197 void _signalLastSequenceNumberChanged (void);
198 void _updateFinalApproachCoodinateAltitudeFromFact (void);
199 void _updateLandingCoodinateAltitudeFromFact (void);
200
201#ifdef QGC_UNITTEST_BUILD
202 friend class LandingComplexItemTest;
203#endif
204};
QString errorString
A Fact is used to hold a single value within the system.
Definition Fact.h:17
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
virtual void _updateFlightPathSegmentsDontCallDirectly(void)=0
QJsonObject _save(void)
QString abbreviation(void) const final
void landingCoordSetChanged(bool landingCoordSet)
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
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.
bool flyView(void) const
PlanMasterController * masterController(void)