QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
FixedWingLandingComplexItem.cc
Go to the documentation of this file.
2#include "JsonHelper.h"
3#include "MissionController.h"
4#include "MissionItem.h"
6#include "FlightPathSegment.h"
8
9#include <QtCore/QJsonArray>
10
11QGC_LOGGING_CATEGORY(FixedWingLandingComplexItemLog, "Plan.FixedWingLandingComplexItem")
12
13const QString FixedWingLandingComplexItem::name(FixedWingLandingComplexItem::tr("Fixed Wing Landing"));
14
16 : LandingComplexItem (masterController, flyView)
17 , _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/FWLandingPattern.FactMetaData.json"), this))
18 , _landingDistanceFact (settingsGroup, _metaDataMap[finalApproachToLandDistanceName])
19 , _finalApproachAltitudeFact(settingsGroup, _metaDataMap[finalApproachAltitudeName])
20 , _useDoChangeSpeedFact (settingsGroup, _metaDataMap[useDoChangeSpeedName])
21 , _finalApproachSpeedFact (settingsGroup, _metaDataMap[finalApproachSpeedName])
22 , _loiterRadiusFact (settingsGroup, _metaDataMap[loiterRadiusName])
23 , _loiterClockwiseFact (settingsGroup, _metaDataMap[loiterClockwiseName])
24 , _landingHeadingFact (settingsGroup, _metaDataMap[landingHeadingName])
25 , _landingAltitudeFact (settingsGroup, _metaDataMap[landingAltitudeName])
26 , _glideSlopeFact (settingsGroup, _metaDataMap[glideSlopeName])
27 , _useLoiterToAltFact (settingsGroup, _metaDataMap[useLoiterToAltName])
28 , _stopTakingPhotosFact (settingsGroup, _metaDataMap[stopTakingPhotosName])
29 , _stopTakingVideoFact (settingsGroup, _metaDataMap[stopTakingVideoName])
30 , _valueSetIsDistanceFact (settingsGroup, _metaDataMap[valueSetIsDistanceName])
31{
32 _editorQml = "qrc:/qml/QGroundControl/Controls/FWLandingPatternEditor.qml";
33 _isIncomplete = false;
34
35 _init();
36
37 connect(&_glideSlopeFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_glideSlopeChanged);
38 connect(&_valueSetIsDistanceFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_setDirty);
39
40 if (_valueSetIsDistanceFact.rawValue().toBool()) {
41 _recalcFromHeadingAndDistanceChange();
42 } else {
43 _glideSlopeChanged();
44 }
45 setDirty(false);
46}
47
50 return name;
51 } else {
52 return "Alternate Landing";
53 }
54}
55
56void FixedWingLandingComplexItem::save(QJsonArray& missionItems)
57{
58 QJsonObject saveObject = _save();
59
60 saveObject[JsonHelper::jsonVersionKey] = 2;
63 saveObject[_jsonValueSetIsDistanceKey] = _valueSetIsDistanceFact.rawValue().toBool();
64
65 missionItems.append(saveObject);
66}
67
68bool FixedWingLandingComplexItem::load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString)
69{
70 QList<JsonHelper::KeyValidateInfo> keyInfoList = {
71 { JsonHelper::jsonVersionKey, QJsonValue::Double, true },
72 };
73 if (!JsonHelper::validateKeys(complexObject, keyInfoList, errorString)) {
74 return false;
75 }
76
77 int version = complexObject[JsonHelper::jsonVersionKey].toInt();
78 if (version == 1) {
79 _valueSetIsDistanceFact.setRawValue(true);
80 } else if (version == 2) {
81 QList<JsonHelper::KeyValidateInfo> v2KeyInfoList = {
82 { _jsonValueSetIsDistanceKey, QJsonValue::Bool, true },
83 };
84 if (!JsonHelper::validateKeys(complexObject, v2KeyInfoList, errorString)) {
86 return false;
87 }
88
89 _valueSetIsDistanceFact.setRawValue(complexObject[_jsonValueSetIsDistanceKey].toBool());
90 } else {
91 errorString = tr("%1 complex item version %2 not supported").arg(jsonComplexItemTypeValue).arg(version);
93 return false;
94 }
95
96 return _load(complexObject, sequenceNumber, jsonComplexItemTypeValue, version == 1 /* useDeprecatedRelAltKeys */, errorString);
97}
98
99MissionItem* FixedWingLandingComplexItem::_createLandItem(int seqNum, bool altRel, double lat, double lon, double alt, QObject* parent)
100{
101 return new MissionItem(seqNum,
102 MAV_CMD_NAV_LAND,
103 altRel ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
104 0.0, 0.0, 0.0, 0.0,
105 lat, lon, alt,
106 true, // autoContinue
107 false, // isCurrentItem
108 parent);
109
110}
111
112void FixedWingLandingComplexItem::_glideSlopeChanged(void)
113{
115 double landingAltDifference = _finalApproachAltitudeFact.rawValue().toDouble() - _landingAltitudeFact.rawValue().toDouble();
116 double glideSlope = _glideSlopeFact.rawValue().toDouble();
117 _landingDistanceFact.setRawValue(landingAltDifference / qTan(qDegreesToRadians(glideSlope)));
118 }
119}
120
121void FixedWingLandingComplexItem::_calcGlideSlope(void)
122{
123 double landingAltDifference = _finalApproachAltitudeFact.rawValue().toDouble() - _landingAltitudeFact.rawValue().toDouble();
124 double landingDistance = _landingDistanceFact.rawValue().toDouble();
125
126 _glideSlopeFact.setRawValue(qRadiansToDegrees(qAtan(landingAltDifference / landingDistance)));
127}
128
129bool FixedWingLandingComplexItem::_isValidLandItem(const MissionItem& missionItem)
130{
131 if (missionItem.command() != MAV_CMD_NAV_LAND ||
132 !(missionItem.frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT || missionItem.frame() == MAV_FRAME_GLOBAL) ||
133 // ArduPilot automatically sets param4 to 1, so we have to allow for it.
134 missionItem.param1() != 0 || missionItem.param2() != 0 || missionItem.param3() != 0 || (missionItem.param4() != 0 && missionItem.param4() != 1)) {
135 return false;
136 } else {
137 return true;
138 }
139}
140
142{
143 return _scanForItems(visualItems, flyView, masterController, _isValidLandItem, _createItem);
144}
145
146// Never call this method directly. If you want to update the flight segments you emit _updateFlightPathSegmentsSignal()
147void FixedWingLandingComplexItem::_updateFlightPathSegmentsDontCallDirectly(void)
148{
151 emit terrainCollisionChanged(false);
152 }
153
156 if (useLoiterToAlt()->rawValue().toBool()) {
159 } else {
161 }
163
165 emit terrainCollisionChanged(true);
166 }
167
169}
QString errorString
#define QGC_LOGGING_CATEGORY(name, categoryStr)
static constexpr const char * jsonComplexItemTypeKey
This mission item attribute specifies the type of the complex item.
void _appendFlightPathSegment(FlightPathSegment::SegmentType segmentType, const QGeoCoordinate &coord1, double coord1AMSLAlt, const QGeoCoordinate &coord2, double coord2AMSLAlt)
QmlObjectListModel _flightPathSegments
void terrainCollisionChanged(bool terrainCollision)
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 ...
static constexpr const char * jsonComplexItemTypeValue
static bool scanForItems(QmlObjectListModel *visualItems, bool flyView, PlanMasterController *masterController)
Scans the loaded items for a landing pattern complex item.
void save(QJsonArray &missionItems) final
bool load(const QJsonObject &complexObject, int sequenceNumber, QString &errorString) final
QJsonObject _save(void)
double amslEntryAlt(void) const final
bool _load(const QJsonObject &complexObject, int sequenceNumber, const QString &jsonComplexItemTypeValue, bool useDeprecatedRelAltKeys, QString &errorString)
QGeoCoordinate slopeStartCoordinate(void) const
const Fact * landingDistance(void) const
static bool _scanForItems(QmlObjectListModel *visualItems, bool flyView, PlanMasterController *masterController, IsLandItemFunc isLandItemFunc, CreateItemFunc createItemFunc)
QGeoCoordinate finalApproachCoordinate(void) const
QGeoCoordinate landingCoordinate(void) const
double amslExitAlt(void) const final
const Fact * useLoiterToAlt(void) const
int sequenceNumber(void) const final
void recalcTerrainProfile(void)
bool isFirstLandingComplexItem(const LandingComplexItem *item) const
MAV_CMD command(void) const
Definition MissionItem.h:49
MAV_FRAME frame(void) const
Definition MissionItem.h:52
double param3(void) const
Definition MissionItem.h:56
double param1(void) const
Definition MissionItem.h:54
double param4(void) const
Definition MissionItem.h:57
double param2(void) const
Definition MissionItem.h:55
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 clearAndDeleteContents() override final
Clears the list and calls deleteLater on each entry.
PlanMasterController * _masterController
bool flyView(void) const
static constexpr const char * jsonTypeComplexItemValue
Item type is Complex Item.
static constexpr const char * jsonTypeKey
Json file attribute which specifies the item type.
PlanMasterController * masterController(void)
constexpr const char * jsonVersionKey
Definition JsonHelper.h:109
bool validateKeys(const QJsonObject &jsonObject, const QList< KeyValidateInfo > &keyInfo, QString &errorString)