QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
VTOLLandingComplexItem.cc
Go to the documentation of this file.
2#include "JsonParsing.h"
3#include "MissionController.h"
5#include "FlightPathSegment.h"
6#include "MissionItem.h"
7#include "SettingsManager.h"
8#include "PlanViewSettings.h"
9#include "QGCMath.h"
10#include "QGCLoggingCategory.h"
11
12#include <QtCore/QJsonArray>
13
14QGC_LOGGING_CATEGORY(VTOLLandingComplexItemLog, "Plan.VTOLLandingComplexItem")
15
17 : LandingComplexItem (masterController, flyView)
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])
30{
31 _editorQml = "qrc:/qml/QGroundControl/PlanView/VTOLLandingPatternEditor.qml";
32 _isIncomplete = false;
33
34 _init();
35
36 // We adjust landing distance meta data to Plan View settings unless there was a custom build override
37 if (QGC::fuzzyCompare(_landingDistanceFact.rawValue().toDouble(), _landingDistanceFact.rawDefaultValue().toDouble())) {
38 Fact* vtolTransitionDistanceFact = SettingsManager::instance()->planViewSettings()->vtolTransitionDistance();
39 double vtolTransitionDistance = vtolTransitionDistanceFact->rawValue().toDouble();
40 _landingDistanceFact.metaData()->setRawDefaultValue(vtolTransitionDistance);
41 _landingDistanceFact.setRawValue(vtolTransitionDistance);
42 _landingDistanceFact.metaData()->setRawMin(vtolTransitionDistanceFact->metaData()->rawMin());
43 }
44
45 _recalcFromHeadingAndDistanceChange();
46
47 setDirty(false);
48}
49
52 return tr(canonicalName);
53 } else {
54 return tr("Alternate Landing");
55 }
56}
57
58
59void VTOLLandingComplexItem::save(QJsonArray& missionItems)
60{
61 QJsonObject saveObject = _save();
62
63 saveObject[JsonParsing::jsonVersionKey] = 1;
66
67 missionItems.append(saveObject);
68}
69
70bool VTOLLandingComplexItem::load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString)
71{
72 QList<JsonParsing::KeyValidateInfo> keyInfoList = {
73 { JsonParsing::jsonVersionKey, QJsonValue::Double, true },
74 };
75 if (!JsonParsing::validateKeys(complexObject, keyInfoList, errorString)) {
76 return false;
77 }
78
79 int version = complexObject[JsonParsing::jsonVersionKey].toInt();
80 if (version != 1) {
81 errorString = tr("%1 complex item version %2 not supported").arg(jsonComplexItemTypeValue).arg(version);
83 return false;
84 }
85
86 return _load(complexObject, sequenceNumber, jsonComplexItemTypeValue, false /* useDeprecatedRelAltKeys */, errorString);
87}
88
89MissionItem* VTOLLandingComplexItem::_createLandItem(int seqNum, bool altRel, double lat, double lon, double alt, QObject* parent)
90{
91 return new MissionItem(seqNum,
92 MAV_CMD_NAV_VTOL_LAND,
93 altRel ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
94 0.0, 0.0, 0.0,
95 qQNaN(), // Yaw - not specified
96 lat, lon, alt,
97 true, // autoContinue
98 false, // isCurrentItem
99 parent);
100
101}
102
103void VTOLLandingComplexItem::_calcGlideSlope(void)
104{
105 // No glide slope calc for VTOL
106}
107
108bool VTOLLandingComplexItem::_isValidLandItem(const MissionItem& missionItem)
109{
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())) {
113 return false;
114 } else {
115 return true;
116 }
117}
118
119bool VTOLLandingComplexItem::scanForItems(QmlObjectListModel* visualItems, bool flyView, PlanMasterController* masterController)
120{
121 return _scanForItems(visualItems, flyView, masterController, _isValidLandItem, _createItem);
122}
123
124// Never call this method directly. If you want to update the flight segments you emit _updateFlightPathSegmentsSignal()
125void VTOLLandingComplexItem::_updateFlightPathSegmentsDontCallDirectly(void)
126{
129 emit terrainCollisionChanged(false);
130 }
131
134 if (useLoiterToAlt()->rawValue().toBool()) {
137 } else {
139 }
142
144 emit terrainCollisionChanged(true);
145 }
146
148}
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.
QVariant rawMin() const
A Fact is used to hold a single value within the system.
Definition Fact.h:17
FactMetaData * metaData()
Definition Fact.h:171
QVariant rawValue() const
Value after translation.
Definition Fact.h:85
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
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.
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
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
bool fuzzyCompare(double value1, double value2)
Returns true if the two values are equal or close. Correctly handles 0 and NaN values.
Definition QGCMath.cc:109