9#include <QtCore/QJsonArray>
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])
30 _editorQml =
"qrc:/qml/QGroundControl/PlanView/FWLandingPatternEditor.qml";
31 _isIncomplete =
false;
35 connect(&_glideSlopeFact, &
Fact::valueChanged,
this, &FixedWingLandingComplexItem::_glideSlopeChanged);
38 if (_valueSetIsDistanceFact.rawValue().toBool()) {
39 _recalcFromHeadingAndDistanceChange();
50 return tr(
"Alternate Landing");
56 QJsonObject saveObject =
_save();
61 saveObject[_jsonValueSetIsDistanceKey] = _valueSetIsDistanceFact.
rawValue().toBool();
63 missionItems.append(saveObject);
68 QList<JsonParsing::KeyValidateInfo> keyInfoList = {
78 }
else if (version == 2) {
79 QList<JsonParsing::KeyValidateInfo> v2KeyInfoList = {
80 { _jsonValueSetIsDistanceKey, QJsonValue::Bool,
true },
87 _valueSetIsDistanceFact.
setRawValue(complexObject[_jsonValueSetIsDistanceKey].toBool());
97MissionItem* FixedWingLandingComplexItem::_createLandItem(
int seqNum,
bool altRel,
double lat,
double lon,
double alt, QObject* parent)
101 altRel ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
110void FixedWingLandingComplexItem::_glideSlopeChanged(
void)
113 double landingAltDifference = _finalApproachAltitudeFact.
rawValue().toDouble() - _landingAltitudeFact.
rawValue().toDouble();
119void FixedWingLandingComplexItem::_calcGlideSlope(
void)
121 double landingAltDifference = _finalApproachAltitudeFact.
rawValue().toDouble() - _landingAltitudeFact.
rawValue().toDouble();
127bool FixedWingLandingComplexItem::_isValidLandItem(
const MissionItem& missionItem)
129 if (missionItem.
command() != MAV_CMD_NAV_LAND ||
130 !(missionItem.
frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT || missionItem.
frame() == MAV_FRAME_GLOBAL) ||
132 missionItem.
param1() != 0 || missionItem.
param2() != 0 || missionItem.
param3() != 0 || (missionItem.
param4() != 0 && missionItem.
param4() != 1)) {
145void FixedWingLandingComplexItem::_updateFlightPathSegmentsDontCallDirectly(
void)
#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
int _cTerrainCollisionSegments
void terrainCollisionChanged(bool terrainCollision)
void setRawValue(const QVariant &value)
QVariant rawValue() const
Value after translation.
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
QString patternName(void) const final
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
bool _ignoreRecalcSignals
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
MAV_FRAME frame(void) const
double param3(void) const
double param1(void) const
double param4(void) const
double param2(void) const
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
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