QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
FixedWingLandingComplexItem.cc
Go to the documentation of this file.
2#include "JsonParsing.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
14 : LandingComplexItem (masterController, flyView)
15 , _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/FWLandingPattern.FactMetaData.json"), this))
16 , _landingDistanceFact (settingsGroup, _metaDataMap[finalApproachToLandDistanceName])
17 , _finalApproachAltitudeFact(settingsGroup, _metaDataMap[finalApproachAltitudeName])
18 , _useDoChangeSpeedFact (settingsGroup, _metaDataMap[useDoChangeSpeedName])
19 , _finalApproachSpeedFact (settingsGroup, _metaDataMap[finalApproachSpeedName])
20 , _loiterRadiusFact (settingsGroup, _metaDataMap[loiterRadiusName])
21 , _loiterClockwiseFact (settingsGroup, _metaDataMap[loiterClockwiseName])
22 , _landingHeadingFact (settingsGroup, _metaDataMap[landingHeadingName])
23 , _landingAltitudeFact (settingsGroup, _metaDataMap[landingAltitudeName])
24 , _glideSlopeFact (settingsGroup, _metaDataMap[glideSlopeName])
25 , _useLoiterToAltFact (settingsGroup, _metaDataMap[useLoiterToAltName])
26 , _stopTakingPhotosFact (settingsGroup, _metaDataMap[stopTakingPhotosName])
27 , _stopTakingVideoFact (settingsGroup, _metaDataMap[stopTakingVideoName])
28 , _valueSetIsDistanceFact (settingsGroup, _metaDataMap[valueSetIsDistanceName])
29{
30 _editorQml = "qrc:/qml/QGroundControl/PlanView/FWLandingPatternEditor.qml";
31 _isIncomplete = false;
32
33 _init();
34
35 connect(&_glideSlopeFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_glideSlopeChanged);
36 connect(&_valueSetIsDistanceFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_setDirty);
37
38 if (_valueSetIsDistanceFact.rawValue().toBool()) {
39 _recalcFromHeadingAndDistanceChange();
40 } else {
41 _glideSlopeChanged();
42 }
43 setDirty(false);
44}
45
48 return tr(canonicalName);
49 } else {
50 return tr("Alternate Landing");
51 }
52}
53
54void FixedWingLandingComplexItem::save(QJsonArray& missionItems)
55{
56 QJsonObject saveObject = _save();
57
58 saveObject[JsonParsing::jsonVersionKey] = 2;
61 saveObject[_jsonValueSetIsDistanceKey] = _valueSetIsDistanceFact.rawValue().toBool();
62
63 missionItems.append(saveObject);
64}
65
66bool FixedWingLandingComplexItem::load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString)
67{
68 QList<JsonParsing::KeyValidateInfo> keyInfoList = {
69 { JsonParsing::jsonVersionKey, QJsonValue::Double, true },
70 };
71 if (!JsonParsing::validateKeys(complexObject, keyInfoList, errorString)) {
72 return false;
73 }
74
75 int version = complexObject[JsonParsing::jsonVersionKey].toInt();
76 if (version == 1) {
77 _valueSetIsDistanceFact.setRawValue(true);
78 } else if (version == 2) {
79 QList<JsonParsing::KeyValidateInfo> v2KeyInfoList = {
80 { _jsonValueSetIsDistanceKey, QJsonValue::Bool, true },
81 };
82 if (!JsonParsing::validateKeys(complexObject, v2KeyInfoList, errorString)) {
84 return false;
85 }
86
87 _valueSetIsDistanceFact.setRawValue(complexObject[_jsonValueSetIsDistanceKey].toBool());
88 } else {
89 errorString = tr("%1 complex item version %2 not supported").arg(jsonComplexItemTypeValue).arg(version);
91 return false;
92 }
93
94 return _load(complexObject, sequenceNumber, jsonComplexItemTypeValue, version == 1 /* useDeprecatedRelAltKeys */, errorString);
95}
96
97MissionItem* FixedWingLandingComplexItem::_createLandItem(int seqNum, bool altRel, double lat, double lon, double alt, QObject* parent)
98{
99 return new MissionItem(seqNum,
100 MAV_CMD_NAV_LAND,
101 altRel ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
102 0.0, 0.0, 0.0, 0.0,
103 lat, lon, alt,
104 true, // autoContinue
105 false, // isCurrentItem
106 parent);
107
108}
109
110void FixedWingLandingComplexItem::_glideSlopeChanged(void)
111{
113 double landingAltDifference = _finalApproachAltitudeFact.rawValue().toDouble() - _landingAltitudeFact.rawValue().toDouble();
114 double glideSlope = _glideSlopeFact.rawValue().toDouble();
115 _landingDistanceFact.setRawValue(landingAltDifference / qTan(qDegreesToRadians(glideSlope)));
116 }
117}
118
119void FixedWingLandingComplexItem::_calcGlideSlope(void)
120{
121 double landingAltDifference = _finalApproachAltitudeFact.rawValue().toDouble() - _landingAltitudeFact.rawValue().toDouble();
122 double landingDistance = _landingDistanceFact.rawValue().toDouble();
123
124 _glideSlopeFact.setRawValue(qRadiansToDegrees(qAtan(landingAltDifference / landingDistance)));
125}
126
127bool FixedWingLandingComplexItem::_isValidLandItem(const MissionItem& missionItem)
128{
129 if (missionItem.command() != MAV_CMD_NAV_LAND ||
130 !(missionItem.frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT || missionItem.frame() == MAV_FRAME_GLOBAL) ||
131 // ArduPilot automatically sets param4 to 1, so we have to allow for it.
132 missionItem.param1() != 0 || missionItem.param2() != 0 || missionItem.param3() != 0 || (missionItem.param4() != 0 && missionItem.param4() != 1)) {
133 return false;
134 } else {
135 return true;
136 }
137}
138
140{
141 return _scanForItems(visualItems, flyView, masterController, _isValidLandItem, _createItem);
142}
143
144// Never call this method directly. If you want to update the flight segments you emit _updateFlightPathSegmentsSignal()
145void FixedWingLandingComplexItem::_updateFlightPathSegmentsDontCallDirectly(void)
146{
149 emit terrainCollisionChanged(false);
150 }
151
154 if (useLoiterToAlt()->rawValue().toBool()) {
157 } else {
159 }
161
163 emit terrainCollisionChanged(true);
164 }
165
167}
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)
Holds the meta data associated with a Fact.
void setRawValue(const QVariant &value)
Definition Fact.cc:128
QVariant rawValue() const
Value after translation.
Definition Fact.h:85
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
static constexpr const char * canonicalName
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)
bool validateKeys(const QJsonObject &jsonObject, const QList< KeyValidateInfo > &keyInfo, QString &errorString)
Validates that all required keys are present and that listed keys have the expected type.
constexpr const char * jsonVersionKey
Definition JsonParsing.h:12