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