12#include <QtCore/QJsonArray>
18 , _metaDataMap (
FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/VTOLLandingPattern.
FactMetaData.json"), this))
19 , _landingDistanceFact (settingsGroup, _metaDataMap[finalApproachToLandDistanceName])
20 , _finalApproachAltitudeFact(settingsGroup, _metaDataMap[finalApproachAltitudeName])
21 , _useDoChangeSpeedFact (settingsGroup, _metaDataMap[useDoChangeSpeedName])
22 , _finalApproachSpeedFact (settingsGroup, _metaDataMap[finalApproachSpeedName])
23 , _loiterRadiusFact (settingsGroup, _metaDataMap[loiterRadiusName])
24 , _loiterClockwiseFact (settingsGroup, _metaDataMap[loiterClockwiseName])
25 , _landingHeadingFact (settingsGroup, _metaDataMap[landingHeadingName])
26 , _landingAltitudeFact (settingsGroup, _metaDataMap[landingAltitudeName])
27 , _useLoiterToAltFact (settingsGroup, _metaDataMap[useLoiterToAltName])
28 , _stopTakingPhotosFact (settingsGroup, _metaDataMap[stopTakingPhotosName])
29 , _stopTakingVideoFact (settingsGroup, _metaDataMap[stopTakingVideoName])
31 _editorQml =
"qrc:/qml/QGroundControl/PlanView/VTOLLandingPatternEditor.qml";
32 _isIncomplete =
false;
37 if (
QGC::fuzzyCompare(_landingDistanceFact.rawValue().toDouble(), _landingDistanceFact.rawDefaultValue().toDouble())) {
39 double vtolTransitionDistance = vtolTransitionDistanceFact->
rawValue().toDouble();
40 _landingDistanceFact.metaData()->setRawDefaultValue(vtolTransitionDistance);
41 _landingDistanceFact.setRawValue(vtolTransitionDistance);
42 _landingDistanceFact.metaData()->setRawMin(vtolTransitionDistanceFact->
metaData()->
rawMin());
45 _recalcFromHeadingAndDistanceChange();
54 return tr(
"Alternate Landing");
61 QJsonObject saveObject =
_save();
67 missionItems.append(saveObject);
72 QList<JsonParsing::KeyValidateInfo> keyInfoList = {
89MissionItem* VTOLLandingComplexItem::_createLandItem(
int seqNum,
bool altRel,
double lat,
double lon,
double alt, QObject* parent)
92 MAV_CMD_NAV_VTOL_LAND,
93 altRel ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
103void VTOLLandingComplexItem::_calcGlideSlope(
void)
108bool VTOLLandingComplexItem::_isValidLandItem(
const MissionItem& missionItem)
110 if (missionItem.
command() != MAV_CMD_NAV_VTOL_LAND ||
111 !(missionItem.
frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT || missionItem.
frame() == MAV_FRAME_GLOBAL) ||
112 missionItem.
param1() != 0 || missionItem.
param2() != 0 || missionItem.
param3() != 0 || !qIsNaN(missionItem.
param4())) {
125void VTOLLandingComplexItem::_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)
A Fact is used to hold a single value within the system.
FactMetaData * metaData()
QVariant rawValue() const
Value after translation.
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
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.
PlanViewSettings * planViewSettings() const
static SettingsManager * instance()
static constexpr const char * canonicalName
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 * jsonComplexItemTypeValue
bool load(const QJsonObject &complexObject, int sequenceNumber, QString &errorString) final
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
bool fuzzyCompare(double value1, double value2)
Returns true if the two values are equal or close. Correctly handles 0 and NaN values.