QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
TransectStyleComplexItem.h
Go to the documentation of this file.
1#pragma once
2
4#include "MissionItem.h"
5#include "SettingsFact.h"
6#include "QGCMapPolygon.h"
7#include "CameraCalc.h"
8#include "TerrainQuery.h"
9
11
13{
14 Q_OBJECT
15
16public:
18
19 Q_PROPERTY(QGCMapPolygon* surveyAreaPolygon READ surveyAreaPolygon CONSTANT)
20 Q_PROPERTY(CameraCalc* cameraCalc READ cameraCalc CONSTANT)
21 Q_PROPERTY(Fact* turnAroundDistance READ turnAroundDistance CONSTANT)
23 Q_PROPERTY(Fact* hoverAndCapture READ hoverAndCapture CONSTANT)
24 Q_PROPERTY(Fact* refly90Degrees READ refly90Degrees CONSTANT)
25
26 Q_PROPERTY(int cameraShots READ cameraShots NOTIFY cameraShotsChanged)
27 Q_PROPERTY(double timeBetweenShots READ timeBetweenShots NOTIFY timeBetweenShotsChanged)
28 Q_PROPERTY(double coveredArea READ coveredArea NOTIFY coveredAreaChanged)
29 Q_PROPERTY(bool hoverAndCaptureAllowed READ hoverAndCaptureAllowed CONSTANT)
31
32 Q_PROPERTY(Fact* terrainAdjustTolerance READ terrainAdjustTolerance CONSTANT)
35
37 CameraCalc* cameraCalc (void) { return &_cameraCalc; }
38 QVariantList visualTransectPoints(void) { return _visualTransectPoints; }
39
47
48 const Fact* hoverAndCapture (void) const { return &_hoverAndCaptureFact; }
49
50 int cameraShots (void) const { return _cameraShots; }
51 double coveredArea (void) const;
52 bool hoverAndCaptureAllowed (void) const;
53
54 virtual double timeBetweenShots (void) { return 0; } // Most be overridden. Implementation here is needed for unit testing.
55
56 double triggerDistance (void) const { return _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble(); }
57 bool hoverAndCaptureEnabled (void) const { return hoverAndCapture()->rawValue().toBool(); }
58 bool triggerCamera (void) const { return triggerDistance() != 0; }
59
60 // Used internally only by unit tests
61 int _transectCount(void) const { return _transects.count(); }
62
63 // Overrides from ComplexMissionItem
64 int lastSequenceNumber (void) const final;
65 QString mapVisualQML (void) const override = 0;
66 bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) override = 0;
67 void addKMLVisuals (KMLPlanDomDocument& domDocument) final;
68 double complexDistance (void) const final { return _complexDistance; }
69 double greatestDistanceTo (const QGeoCoordinate &other) const final;
70
71 // Overrides from VisualMissionItem
72 void save (QJsonArray& planItems) override = 0;
73 bool specifiesCoordinate (void) const override = 0;
74 void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
75 void applyNewAltitude (double newAltitude) final;
76 bool dirty (void) const final { return _dirty; }
77 bool isSimpleItem (void) const final { return false; }
78 bool isStandaloneCoordinate (void) const final { return false; }
79 bool specifiesAltitudeOnly (void) const final { return false; }
80 QGeoCoordinate coordinate (void) const final { return entryCoordinate(); }
81 QGeoCoordinate entryCoordinate (void) const final { return _entryCoordinate; }
82 QGeoCoordinate exitCoordinate (void) const final { return _exitCoordinate; }
83 int sequenceNumber (void) const final { return _sequenceNumber; }
84 double specifiedFlightSpeed (void) final { return std::numeric_limits<double>::quiet_NaN(); }
85 double specifiedGimbalYaw (void) final { return std::numeric_limits<double>::quiet_NaN(); }
86 double specifiedGimbalPitch (void) final { return std::numeric_limits<double>::quiet_NaN(); }
87 void setMissionFlightStatus (MissionFlightStatus_t& missionFlightStatus) final;
88 ReadyForSaveState readyForSaveState (void) const override;
89 QString commandDescription (void) const override { return tr("Transect"); }
90 QString commandName (void) const override { return tr("Transect"); }
91 QString abbreviation (void) const override { return tr("T"); }
92 bool exitCoordinateSameAsEntry (void) const final { return false; }
93 void setDirty (bool dirty) final;
94 void setCoordinate (const QGeoCoordinate& coordinate) override;
95 void setSequenceNumber (int sequenceNumber) final;
96 double editableAlt (void) const final;
97 double amslEntryAlt (void) const final;
98 double amslExitAlt (void) const final;
99 double minAMSLAltitude (void) const final;
100 double maxAMSLAltitude (void) const final;
101
102 static constexpr const char* turnAroundDistanceName = "TurnAroundDistance";
103 static constexpr const char* turnAroundDistanceMultiRotorName = "TurnAroundDistanceMultiRotor";
104 static constexpr const char* cameraTriggerInTurnAroundName = "CameraTriggerInTurnAround";
105 static constexpr const char* hoverAndCaptureName = "HoverAndCapture";
106 static constexpr const char* refly90DegreesName = "Refly90Degrees";
107 static constexpr const char* terrainAdjustToleranceName = "TerrainAdjustTolerance";
108 static constexpr const char* terrainAdjustMaxClimbRateName = "TerrainAdjustMaxClimbRate";
109 static constexpr const char* terrainAdjustMaxDescentRateName = "TerrainAdjustMaxDescentRate";
110
111signals:
117
118protected slots:
119 void _setDirty (void);
120 void _setIfDirty (bool dirty);
121 void _updateCoordinateAltitudes (void);
122 void _polyPathTerrainData (bool success, const QList<TerrainPathQuery::PathHeightInfo_t>& rgPathHeightInfo);
123 void _missionItemCoordTerrainData (bool success, QList<double> heights);
124 void _rebuildTransects (void);
125
126protected:
127 virtual void _rebuildTransectsPhase1 (void) = 0;
128 virtual void _recalcCameraShots (void) = 0;
129
130 void _save (QJsonObject& saveObject);
131 bool _load (const QJsonObject& complexObject, bool forPresets, QString& errorString);
132 void _setExitCoordinate (const QGeoCoordinate& coordinate);
133 void _setCameraShots (int cameraShots);
134 double _triggerDistance (void) const;
135 bool _hasTurnaround (void) const;
136 double _turnAroundDistance (void) const;
137 void _appendWaypoint (QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum, MAV_FRAME mavFrame, float holdTime, const QGeoCoordinate& coordinate);
138 void _appendSinglePhotoCapture (QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum);
139 void _appendConditionGate (QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum, MAV_FRAME mavFrame, const QGeoCoordinate& coordinate);
140 void _appendCameraTriggerDistance (QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum, float triggerDistance);
141 void _appendCameraTriggerDistanceUpdatePoint(QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum, MAV_FRAME mavFrame, const QGeoCoordinate& coordinate, bool useConditionGate, float triggerDistance);
142 void _buildAndAppendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent);
143 void _appendLoadedMissionItems (QList<MissionItem*>& items, QObject* missionItemParent);
144 void _recalcComplexDistance (void);
145
147 QGeoCoordinate _entryCoordinate;
148 QGeoCoordinate _exitCoordinate;
150
159
160 typedef struct {
161 QGeoCoordinate coord;
163 } CoordInfo_t;
164
166 QList<QList<CoordInfo_t>> _transects;
167 QList<TerrainPathQuery::PathHeightInfo_t> _rgPathHeightInfo;
168 QList<QGeoCoordinate> _rgFlyThroughMissionItemCoords;
170 QList<CoordInfo_t> _rgFlightPathCoordInfo;
171
172 bool _ignoreRecalc = false;
173 double _complexDistance = qQNaN();
176 double _vehicleSpeed = 5;
178 double _minAMSLAltitude = qQNaN();
179 double _maxAMSLAltitude = qQNaN();
180
181 QObject* _loadedMissionItemsParent = nullptr;
182 QList<MissionItem*> _loadedMissionItems;
183
184 QMap<QString, FactMetaData*> _metaDataMap;
185
193
194 static constexpr const char* _jsonTransectStyleComplexItemKey = "TransectStyleComplexItem";
195 static constexpr const char* _jsonCameraCalcKey = "CameraCalc";
196 static constexpr const char* _jsonVisualTransectPointsKey = "VisualTransectPoints";
197 static constexpr const char* _jsonItemsKey = "Items";
198 static constexpr const char* _jsonTerrainFlightSpeed = "TerrainFlightSpeed";
199 static constexpr const char* _jsonCameraShotsKey = "CameraShots";
200
201 static constexpr int _terrainQueryTimeoutMsecs= 1000;
202 static constexpr int _hoverAndCaptureDelaySeconds = 4;
203 static constexpr double _minimumTransectSpacingMeters = 0.3;
204 static constexpr double _forceLargeTransectSpacingMeters = 100000;
205
206private slots:
207 void _reallyQueryTransectsPathHeightInfo (void);
208 void _handleHoverAndCaptureEnabled (QVariant enabled);
209 void _updateFlightPathSegmentsDontCallDirectly (void);
210 void _segmentTerrainCollisionChanged (bool terrainCollision) final;
211 void _distanceModeChanged (int distanceMode);
212
213private:
214 typedef struct {
215 bool imagesInTurnaround;
216 bool hasTurnarounds;
217 bool addTriggerAtFirstAndLastPoint;
218 bool useConditionGate;
219 } BuildMissionItemsState_t;
220
221 void _queryTransectsPathHeightInfo (void);
222 void _queryMissionItemCoordHeights (void);
223 void _adjustForAvailableTerrainData (void);
224 void _buildFlightPathCoordInfoFromTransects (void);
225 void _buildFlightPathCoordInfoFromPathHeightInfoForCalcAboveTerrain (void);
226 void _buildFlightPathCoordInfoFromPathHeightInfoForTerrainFrame (void);
227 void _buildFlightPathCoordInfoFromMissionItems (void);
228 void _adjustForMaxRates (void);
229 void _adjustForTolerance (void);
230 double _altitudeBetweenCoords (const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord, double percentTowardsTo);
231 int _maxPathHeight (const TerrainPathQuery::PathHeightInfo_t& pathHeightInfo, int fromIndex, int toIndex, double& maxHeight);
232 BuildMissionItemsState_t _buildMissionItemsState (void) const;
233
234 TerrainPolyPathQuery* _currentTerrainPolyPathQuery = nullptr;
235 TerrainAtCoordinateQuery* _currentTerrainAtCoordinateQuery = nullptr;
236 QTimer _terrainPolyPathQueryTimer;
237
238 // Deprecated json keys
239 static constexpr const char* _jsonTerrainFollowKeyDeprecated = "FollowTerrain";
240};
QString errorString
Fact * adjustedFootprintFrontal(void)
Definition CameraCalc.h:58
virtual bool terrainCollision(void) const
A Fact is used to hold a single value within the system.
Definition Fact.h:17
QVariant rawValue() const
Value after translation.
Definition Fact.h:85
Used to convert a Plan to a KML document.
Master controller for mission, fence, rally.
The QGCMapPolygon class provides a polygon which can be displayed on a map using a map visuals contro...
A SettingsFact is Fact which holds a QSettings value.
NOTE: TerrainAtCoordinateQuery is not thread safe. All instances/calls to ElevationProvider must be o...
static constexpr double _minimumTransectSpacingMeters
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
double specifiedGimbalPitch(void) final
void _appendLoadedMissionItems(QList< MissionItem * > &items, QObject *missionItemParent)
static constexpr const char * cameraTriggerInTurnAroundName
QString commandName(void) const override
void save(QJsonArray &planItems) override=0
static constexpr const char * terrainAdjustMaxDescentRateName
double amslExitAlt(void) const final
int lastSequenceNumber(void) const final
double maxAMSLAltitude(void) const final
void _appendSinglePhotoCapture(QList< MissionItem * > &items, QObject *missionItemParent, int &seqNum)
QList< MissionItem * > _loadedMissionItems
Mission items loaded from plan file.
bool isSimpleItem(void) const final
static constexpr const char * _jsonVisualTransectPointsKey
void _setExitCoordinate(const QGeoCoordinate &coordinate)
virtual double timeBetweenShots(void)
void _buildAndAppendMissionItems(QList< MissionItem * > &items, QObject *missionItemParent)
static constexpr const char * _jsonItemsKey
static constexpr const char * _jsonTerrainFlightSpeed
double _triggerDistance(void) const
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
double complexDistance(void) const final
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
bool specifiesCoordinate(void) const override=0
static constexpr int _terrainQueryTimeoutMsecs
void addKMLVisuals(KMLPlanDomDocument &domDocument) final
double specifiedFlightSpeed(void) final
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)
QString abbreviation(void) const override
static constexpr const char * hoverAndCaptureName
static constexpr const char * refly90DegreesName
QMap< QString, FactMetaData * > _metaDataMap
QString commandDescription(void) const override
const Fact * hoverAndCapture(void) const
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.
bool exitCoordinateSameAsEntry(void) const final
static constexpr double _forceLargeTransectSpacingMeters
static constexpr int _hoverAndCaptureDelaySeconds
QVariantList _visualTransectPoints
Used to draw the flight path visuals on the screen.
QVariantList visualTransectPoints(void)
QList< double > _rgFlyThroughMissionItemCoordsTerrainHeights
QGeoCoordinate entryCoordinate(void) const final
static constexpr const char * turnAroundDistanceMultiRotorName
bool isStandaloneCoordinate(void) const final
void setMissionFlightStatus(MissionFlightStatus_t &missionFlightStatus) final
void _save(QJsonObject &saveObject)
QString mapVisualQML(void) const override=0
bool specifiesAltitudeOnly(void) const final
double amslEntryAlt(void) const final
QGCMapPolygon * surveyAreaPolygon(void)
void visualTransectPointsChanged(void)
QList< CoordInfo_t > _rgFlightPathCoordInfo
Fully calculated flight path (including terrain if needed)
virtual void _recalcCameraShots(void)=0
bool load(const QJsonObject &complexObject, int sequenceNumber, QString &errorString) override=0
void timeBetweenShotsChanged(void)
QGeoCoordinate exitCoordinate(void) const final
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
bool flyView(void) const
PlanMasterController * masterController(void)