QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
VTOLLandingComplexItem.cc
Go to the documentation of this file.
2#include "JsonHelper.h"
3#include "MissionController.h"
5#include "FlightPathSegment.h"
6#include "MissionItem.h"
7#include "SettingsManager.h"
8#include "PlanViewSettings.h"
9#include "QGC.h"
10#include "QGCLoggingCategory.h"
11
12#include <QtCore/QJsonArray>
13
14QGC_LOGGING_CATEGORY(VTOLLandingComplexItemLog, "Plan.VTOLLandingComplexItem")
15
16const QString VTOLLandingComplexItem::name(VTOLLandingComplexItem::tr("VTOL Landing"));
17
19 : LandingComplexItem (masterController, flyView)
20 , _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/VTOLLandingPattern.FactMetaData.json"), this))
21 , _landingDistanceFact (settingsGroup, _metaDataMap[finalApproachToLandDistanceName])
22 , _finalApproachAltitudeFact(settingsGroup, _metaDataMap[finalApproachAltitudeName])
23 , _useDoChangeSpeedFact (settingsGroup, _metaDataMap[useDoChangeSpeedName])
24 , _finalApproachSpeedFact (settingsGroup, _metaDataMap[finalApproachSpeedName])
25 , _loiterRadiusFact (settingsGroup, _metaDataMap[loiterRadiusName])
26 , _loiterClockwiseFact (settingsGroup, _metaDataMap[loiterClockwiseName])
27 , _landingHeadingFact (settingsGroup, _metaDataMap[landingHeadingName])
28 , _landingAltitudeFact (settingsGroup, _metaDataMap[landingAltitudeName])
29 , _useLoiterToAltFact (settingsGroup, _metaDataMap[useLoiterToAltName])
30 , _stopTakingPhotosFact (settingsGroup, _metaDataMap[stopTakingPhotosName])
31 , _stopTakingVideoFact (settingsGroup, _metaDataMap[stopTakingVideoName])
32{
33 _editorQml = "qrc:/qml/QGroundControl/Controls/VTOLLandingPatternEditor.qml";
34 _isIncomplete = false;
35
36 _init();
37
38 // We adjust landing distance meta data to Plan View settings unless there was a custom build override
39 if (QGC::fuzzyCompare(_landingDistanceFact.rawValue().toDouble(), _landingDistanceFact.rawDefaultValue().toDouble())) {
40 Fact* vtolTransitionDistanceFact = SettingsManager::instance()->planViewSettings()->vtolTransitionDistance();
41 double vtolTransitionDistance = vtolTransitionDistanceFact->rawValue().toDouble();
42 _landingDistanceFact.metaData()->setRawDefaultValue(vtolTransitionDistance);
43 _landingDistanceFact.setRawValue(vtolTransitionDistance);
44 _landingDistanceFact.metaData()->setRawMin(vtolTransitionDistanceFact->metaData()->rawMin());
45 }
46
47 _recalcFromHeadingAndDistanceChange();
48
49 setDirty(false);
50}
51
54 return name;
55 } else {
56 return "Alternate Landing";
57 }
58}
59
60
61void VTOLLandingComplexItem::save(QJsonArray& missionItems)
62{
63 QJsonObject saveObject = _save();
64
65 saveObject[JsonHelper::jsonVersionKey] = 1;
68
69 missionItems.append(saveObject);
70}
71
72bool VTOLLandingComplexItem::load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString)
73{
74 QList<JsonHelper::KeyValidateInfo> keyInfoList = {
75 { JsonHelper::jsonVersionKey, QJsonValue::Double, true },
76 };
77 if (!JsonHelper::validateKeys(complexObject, keyInfoList, errorString)) {
78 return false;
79 }
80
81 int version = complexObject[JsonHelper::jsonVersionKey].toInt();
82 if (version != 1) {
83 errorString = tr("%1 complex item version %2 not supported").arg(jsonComplexItemTypeValue).arg(version);
85 return false;
86 }
87
88 return _load(complexObject, sequenceNumber, jsonComplexItemTypeValue, false /* useDeprecatedRelAltKeys */, errorString);
89}
90
91MissionItem* VTOLLandingComplexItem::_createLandItem(int seqNum, bool altRel, double lat, double lon, double alt, QObject* parent)
92{
93 return new MissionItem(seqNum,
94 MAV_CMD_NAV_VTOL_LAND,
95 altRel ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
96 0.0, 0.0, 0.0,
97 qQNaN(), // Yaw - not specified
98 lat, lon, alt,
99 true, // autoContinue
100 false, // isCurrentItem
101 parent);
102
103}
104
105void VTOLLandingComplexItem::_calcGlideSlope(void)
106{
107 // No glide slope calc for VTOL
108}
109
110bool VTOLLandingComplexItem::_isValidLandItem(const MissionItem& missionItem)
111{
112 if (missionItem.command() != MAV_CMD_NAV_VTOL_LAND ||
113 !(missionItem.frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT || missionItem.frame() == MAV_FRAME_GLOBAL) ||
114 missionItem.param1() != 0 || missionItem.param2() != 0 || missionItem.param3() != 0 || !qIsNaN(missionItem.param4())) {
115 return false;
116 } else {
117 return true;
118 }
119}
120
121bool VTOLLandingComplexItem::scanForItems(QmlObjectListModel* visualItems, bool flyView, PlanMasterController* masterController)
122{
123 return _scanForItems(visualItems, flyView, masterController, _isValidLandItem, _createItem);
124}
125
126// Never call this method directly. If you want to update the flight segments you emit _updateFlightPathSegmentsSignal()
127void VTOLLandingComplexItem::_updateFlightPathSegmentsDontCallDirectly(void)
128{
131 emit terrainCollisionChanged(false);
132 }
133
136 if (useLoiterToAlt()->rawValue().toBool()) {
139 } else {
141 }
144
146 emit terrainCollisionChanged(true);
147 }
148
150}
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)
QVariant rawMin() const
A Fact is used to hold a single value within the system.
Definition Fact.h:19
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)
Fact *vtolTransitionDistance READ vtolTransitionDistance CONSTANT Fact * vtolTransitionDistance()
void clearAndDeleteContents() override final
Clears the list and calls deleteLater on each entry.
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)
constexpr const char * jsonVersionKey
Definition JsonHelper.h:109
bool validateKeys(const QJsonObject &jsonObject, const QList< KeyValidateInfo > &keyInfo, QString &errorString)
bool fuzzyCompare(double value1, double value2)
Returns true if the two values are equal or close. Correctly handles 0 and NaN values.
Definition QGC.cc:106