Commit 1c2579a7 authored by DonLakeFlyer's avatar DonLakeFlyer

parent ab442567
...@@ -21,34 +21,13 @@ FactTextField { ...@@ -21,34 +21,13 @@ FactTextField {
showUnits: true showUnits: true
showHelp: true showHelp: true
property int altitudeMode: QGroundControl.AltitudeModeNone property int altitudeMode: QGroundControl.AltitudeModeNone
property bool showAboveTerrainWarning: true
readonly property string _altModeNoneExtraUnits: "" property string _altitudeModeExtraUnits
readonly property string _altModeRelativeExtraUnits: qsTr("(Rel)")
readonly property string _altModeAbsoluteExtraUnits: qsTr("(AMSL)")
readonly property string _altModeAboveTerrainExtraUnits: qsTr("(Abv Terr)")
readonly property string _altModeTerrainFrameExtraUnits: qsTr("(TerrF)")
property string _altitudeModeExtraUnits: _altModeNoneExtraUnits
onAltitudeModeChanged: updateAltitudeModeExtraUnits() onAltitudeModeChanged: updateAltitudeModeExtraUnits()
function updateAltitudeModeExtraUnits() { function updateAltitudeModeExtraUnits() {
if (altitudeMode === QGroundControl.AltitudeModeNone) { _altitudeModeExtraUnits = QGroundControl.altitudeModeExtraUnits(altitudeMode);
_altitudeModeExtraUnits = _altModeNoneExtraUnits
} else if (altitudeMode === QGroundControl.AltitudeModeRelative) {
//_altitudeModeExtraUnits = _altModeRelativeExtraUnits
_altitudeModeExtraUnits = "" // Showing (rel) all the time is too noisy
} else if (altitudeMode === QGroundControl.AltitudeModeAbsolute) {
_altitudeModeExtraUnits = _altModeAbsoluteExtraUnits
} else if (altitudeMode === QGroundControl.AltitudeModeAboveTerrain) {
_altitudeModeExtraUnits = _altModeAboveTerrainExtraUnits
} else if (missionItem.altitudeMode === QGroundControl.AltitudeModeTerrainFrame) {
_altitudeModeExtraUnits = _altModeTerrainFrameExtraUnits
} else {
console.log("AltitudeFactTextField Internal error: Unknown altitudeMode", altitudeMode)
_altitudeModeExtraUnits = ""
}
} }
} }
...@@ -46,6 +46,7 @@ const char* MissionController::_jsonVehicleTypeKey = "vehicleType"; ...@@ -46,6 +46,7 @@ const char* MissionController::_jsonVehicleTypeKey = "vehicleType";
const char* MissionController::_jsonCruiseSpeedKey = "cruiseSpeed"; const char* MissionController::_jsonCruiseSpeedKey = "cruiseSpeed";
const char* MissionController::_jsonHoverSpeedKey = "hoverSpeed"; const char* MissionController::_jsonHoverSpeedKey = "hoverSpeed";
const char* MissionController::_jsonParamsKey = "params"; const char* MissionController::_jsonParamsKey = "params";
const char* MissionController::_jsonGlobalPlanAltitudeModeKey = "globalPlanAltitudeMode";
// Deprecated V1 format keys // Deprecated V1 format keys
const char* MissionController::_jsonComplexItemsKey = "complexItems"; const char* MissionController::_jsonComplexItemsKey = "complexItems";
...@@ -65,11 +66,10 @@ MissionController::MissionController(PlanMasterController* masterController, QOb ...@@ -65,11 +66,10 @@ MissionController::MissionController(PlanMasterController* masterController, QOb
_resetMissionFlightStatus(); _resetMissionFlightStatus();
_updateTimer.setSingleShot(true); _updateTimer.setSingleShot(true);
connect(&_updateTimer, &QTimer::timeout, this, &MissionController::_updateTimeout);
connect(_planViewSettings->takeoffItemNotRequired(), &Fact::rawValueChanged, this, &MissionController::_takeoffItemNotRequiredChanged); connect(&_updateTimer, &QTimer::timeout, this, &MissionController::_updateTimeout);
connect(_planViewSettings->takeoffItemNotRequired(), &Fact::rawValueChanged, this, &MissionController::_takeoffItemNotRequiredChanged);
connect(this, &MissionController::missionDistanceChanged, this, &MissionController::recalcTerrainProfile); connect(this, &MissionController::missionDistanceChanged, this, &MissionController::recalcTerrainProfile);
// The follow is used to compress multiple recalc calls in a row to into a single call. // The follow is used to compress multiple recalc calls in a row to into a single call.
connect(this, &MissionController::_recalcMissionFlightStatusSignal, this, &MissionController::_recalcMissionFlightStatus, Qt::QueuedConnection); connect(this, &MissionController::_recalcMissionFlightStatusSignal, this, &MissionController::_recalcMissionFlightStatus, Qt::QueuedConnection);
...@@ -614,6 +614,8 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec ...@@ -614,6 +614,8 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec
return false; return false;
} }
setGlobalAltitudeMode(QGroundControlQmlGlobal::AltitudeModeNone); // Mixed mode
// Read complex items // Read complex items
QList<SurveyComplexItem*> surveyItems; QList<SurveyComplexItem*> surveyItems;
QJsonArray complexArray(json[_jsonComplexItemsKey].toArray()); QJsonArray complexArray(json[_jsonComplexItemsKey].toArray());
...@@ -711,11 +713,14 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec ...@@ -711,11 +713,14 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
{ _jsonVehicleTypeKey, QJsonValue::Double, false }, { _jsonVehicleTypeKey, QJsonValue::Double, false },
{ _jsonCruiseSpeedKey, QJsonValue::Double, false }, { _jsonCruiseSpeedKey, QJsonValue::Double, false },
{ _jsonHoverSpeedKey, QJsonValue::Double, false }, { _jsonHoverSpeedKey, QJsonValue::Double, false },
{ _jsonGlobalPlanAltitudeModeKey, QJsonValue::Double, false },
}; };
if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) { if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
return false; return false;
} }
setGlobalAltitudeMode(QGroundControlQmlGlobal::AltitudeModeNone); // Mixed mode
qCDebug(MissionControllerLog) << "MissionController::_loadJsonMissionFileV2 itemCount:" << json[_jsonItemsKey].toArray().count(); qCDebug(MissionControllerLog) << "MissionController::_loadJsonMissionFileV2 itemCount:" << json[_jsonItemsKey].toArray().count();
AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings(); AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
...@@ -746,6 +751,9 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec ...@@ -746,6 +751,9 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
if (json.contains(_jsonHoverSpeedKey)) { if (json.contains(_jsonHoverSpeedKey)) {
appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble()); appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
} }
if (json.contains(_jsonGlobalPlanAltitudeModeKey)) {
setGlobalAltitudeMode(json[_jsonGlobalPlanAltitudeModeKey].toVariant().value<QGroundControlQmlGlobal::AltitudeMode>());
}
QGeoCoordinate homeCoordinate; QGeoCoordinate homeCoordinate;
if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) { if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
...@@ -1044,6 +1052,8 @@ bool MissionController::loadTextFile(QFile& file, QString& errorString) ...@@ -1044,6 +1052,8 @@ bool MissionController::loadTextFile(QFile& file, QString& errorString)
QByteArray bytes = file.readAll(); QByteArray bytes = file.readAll();
QTextStream stream(bytes); QTextStream stream(bytes);
setGlobalAltitudeMode(QGroundControlQmlGlobal::AltitudeModeNone); // Mixed mode
QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this); QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);
if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) { if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
errorString = errorMessage.arg(errorStr); errorString = errorMessage.arg(errorStr);
...@@ -1080,11 +1090,12 @@ void MissionController::save(QJsonObject& json) ...@@ -1080,11 +1090,12 @@ void MissionController::save(QJsonObject& json)
} }
QJsonValue coordinateValue; QJsonValue coordinateValue;
JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue); JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
json[_jsonPlannedHomePositionKey] = coordinateValue; json[_jsonPlannedHomePositionKey] = coordinateValue;
json[_jsonFirmwareTypeKey] = _controllerVehicle->firmwareType(); json[_jsonFirmwareTypeKey] = _controllerVehicle->firmwareType();
json[_jsonVehicleTypeKey] = _controllerVehicle->vehicleType(); json[_jsonVehicleTypeKey] = _controllerVehicle->vehicleType();
json[_jsonCruiseSpeedKey] = _controllerVehicle->defaultCruiseSpeed(); json[_jsonCruiseSpeedKey] = _controllerVehicle->defaultCruiseSpeed();
json[_jsonHoverSpeedKey] = _controllerVehicle->defaultHoverSpeed(); json[_jsonHoverSpeedKey] = _controllerVehicle->defaultHoverSpeed();
json[_jsonGlobalPlanAltitudeModeKey] = _globalAltMode;
// Save the visual items // Save the visual items
...@@ -2588,3 +2599,25 @@ MissionController::SendToVehiclePreCheckState MissionController::sendToVehiclePr ...@@ -2588,3 +2599,25 @@ MissionController::SendToVehiclePreCheckState MissionController::sendToVehiclePr
} }
return SendToVehiclePreCheckStateOk; return SendToVehiclePreCheckStateOk;
} }
QGroundControlQmlGlobal::AltitudeMode MissionController::globalAltitudeMode(void)
{
return _globalAltMode;
}
QGroundControlQmlGlobal::AltitudeMode MissionController::globalAltitudeModeDefault(void)
{
if (_globalAltMode == QGroundControlQmlGlobal::AltitudeModeNone) {
return QGroundControlQmlGlobal::AltitudeModeRelative;
} else {
return _globalAltMode;
}
}
void MissionController::setGlobalAltitudeMode(QGroundControlQmlGlobal::AltitudeMode altMode)
{
if (_globalAltMode != altMode) {
_globalAltMode = altMode;
emit globalAltitudeModeChanged();
}
}
...@@ -15,6 +15,7 @@ ...@@ -15,6 +15,7 @@
#include "QGCLoggingCategory.h" #include "QGCLoggingCategory.h"
#include "KMLPlanDomDocument.h" #include "KMLPlanDomDocument.h"
#include "QGCGeoBoundingCube.h" #include "QGCGeoBoundingCube.h"
#include "QGroundControlQmlGlobal.h"
#include <QHash> #include <QHash>
...@@ -105,6 +106,9 @@ public: ...@@ -105,6 +106,9 @@ public:
Q_PROPERTY(double minAMSLAltitude MEMBER _minAMSLAltitude NOTIFY minAMSLAltitudeChanged) ///< Minimum altitude associated with this mission. Used to calculate percentages for terrain status. Q_PROPERTY(double minAMSLAltitude MEMBER _minAMSLAltitude NOTIFY minAMSLAltitudeChanged) ///< Minimum altitude associated with this mission. Used to calculate percentages for terrain status.
Q_PROPERTY(double maxAMSLAltitude MEMBER _maxAMSLAltitude NOTIFY maxAMSLAltitudeChanged) ///< Maximum altitude associated with this mission. Used to calculate percentages for terrain status. Q_PROPERTY(double maxAMSLAltitude MEMBER _maxAMSLAltitude NOTIFY maxAMSLAltitudeChanged) ///< Maximum altitude associated with this mission. Used to calculate percentages for terrain status.
Q_PROPERTY(QGroundControlQmlGlobal::AltitudeMode globalAltitudeMode READ globalAltitudeMode WRITE setGlobalAltitudeMode NOTIFY globalAltitudeModeChanged) ///< AltitudeModeNone indicates the plan can used mixed modes
Q_PROPERTY(QGroundControlQmlGlobal::AltitudeMode globalAltitudeModeDefault READ globalAltitudeModeDefault NOTIFY globalAltitudeModeChanged) ///< Default to use for newly created items
Q_INVOKABLE void removeVisualItem(int viIndex); Q_INVOKABLE void removeVisualItem(int viIndex);
/// Add a new simple mission item to the list /// Add a new simple mission item to the list
...@@ -246,6 +250,10 @@ public: ...@@ -246,6 +250,10 @@ public:
bool isEmpty (void) const; bool isEmpty (void) const;
QGroundControlQmlGlobal::AltitudeMode globalAltitudeMode(void);
QGroundControlQmlGlobal::AltitudeMode globalAltitudeModeDefault(void);
void setGlobalAltitudeMode(QGroundControlQmlGlobal::AltitudeMode altMode);
signals: signals:
void visualItemsChanged (void); void visualItemsChanged (void);
void waypointPathChanged (void); void waypointPathChanged (void);
...@@ -284,6 +292,7 @@ signals: ...@@ -284,6 +292,7 @@ signals:
void recalcTerrainProfile (void); void recalcTerrainProfile (void);
void _recalcMissionFlightStatusSignal (void); void _recalcMissionFlightStatusSignal (void);
void _recalcFlightPathSegmentsSignal (void); void _recalcFlightPathSegmentsSignal (void);
void globalAltitudeModeChanged (void);
private slots: private slots:
void _newMissionItemsAvailableFromVehicle (bool removeAllRequested); void _newMissionItemsAvailableFromVehicle (bool removeAllRequested);
...@@ -383,6 +392,8 @@ private: ...@@ -383,6 +392,8 @@ private:
double _maxAMSLAltitude = 0; double _maxAMSLAltitude = 0;
bool _missionContainsVTOLTakeoff = false; bool _missionContainsVTOLTakeoff = false;
QGroundControlQmlGlobal::AltitudeMode _globalAltMode = QGroundControlQmlGlobal::AltitudeModeRelative;
static const char* _settingsGroup; static const char* _settingsGroup;
// Json file keys for persistence // Json file keys for persistence
...@@ -394,6 +405,7 @@ private: ...@@ -394,6 +405,7 @@ private:
static const char* _jsonItemsKey; static const char* _jsonItemsKey;
static const char* _jsonPlannedHomePositionKey; static const char* _jsonPlannedHomePositionKey;
static const char* _jsonParamsKey; static const char* _jsonParamsKey;
static const char* _jsonGlobalPlanAltitudeModeKey;
// Deprecated V1 format keys // Deprecated V1 format keys
static const char* _jsonMavAutopilotKey; static const char* _jsonMavAutopilotKey;
......
...@@ -64,9 +64,9 @@ PlanMasterController::PlanMasterController(MAV_AUTOPILOT firmwareType, MAV_TYPE ...@@ -64,9 +64,9 @@ PlanMasterController::PlanMasterController(MAV_AUTOPILOT firmwareType, MAV_TYPE
void PlanMasterController::_commonInit(void) void PlanMasterController::_commonInit(void)
{ {
connect(&_missionController, &MissionController::dirtyChanged, this, &PlanMasterController::dirtyChanged); connect(&_missionController, &MissionController::dirtyChanged, this, &PlanMasterController::dirtyChanged);
connect(&_geoFenceController, &GeoFenceController::dirtyChanged, this, &PlanMasterController::dirtyChanged); connect(&_geoFenceController, &GeoFenceController::dirtyChanged, this, &PlanMasterController::dirtyChanged);
connect(&_rallyPointController, &RallyPointController::dirtyChanged, this, &PlanMasterController::dirtyChanged); connect(&_rallyPointController, &RallyPointController::dirtyChanged, this, &PlanMasterController::dirtyChanged);
connect(&_missionController, &MissionController::containsItemsChanged, this, &PlanMasterController::containsItemsChanged); connect(&_missionController, &MissionController::containsItemsChanged, this, &PlanMasterController::containsItemsChanged);
connect(&_geoFenceController, &GeoFenceController::containsItemsChanged, this, &PlanMasterController::containsItemsChanged); connect(&_geoFenceController, &GeoFenceController::containsItemsChanged, this, &PlanMasterController::containsItemsChanged);
...@@ -77,11 +77,7 @@ void PlanMasterController::_commonInit(void) ...@@ -77,11 +77,7 @@ void PlanMasterController::_commonInit(void)
connect(&_rallyPointController, &RallyPointController::syncInProgressChanged, this, &PlanMasterController::syncInProgressChanged); connect(&_rallyPointController, &RallyPointController::syncInProgressChanged, this, &PlanMasterController::syncInProgressChanged);
// Offline vehicle can change firmware/vehicle type // Offline vehicle can change firmware/vehicle type
connect(_controllerVehicle, &Vehicle::capabilityBitsChanged, this, &PlanMasterController::_updateSupportsTerrain); connect(_controllerVehicle, &Vehicle::vehicleTypeChanged, this, &PlanMasterController::_updatePlanCreatorsList);
connect(_controllerVehicle, &Vehicle::vehicleTypeChanged, this, &PlanMasterController::_updateSupportsTerrain);
connect(_controllerVehicle, &Vehicle::vehicleTypeChanged, this, &PlanMasterController::_updatePlanCreatorsList);
_updateSupportsTerrain();
} }
...@@ -134,7 +130,6 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle) ...@@ -134,7 +130,6 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle)
disconnect(_managerVehicle->missionManager(), nullptr, nullptr, nullptr); disconnect(_managerVehicle->missionManager(), nullptr, nullptr, nullptr);
disconnect(_managerVehicle->geoFenceManager(), nullptr, nullptr, nullptr); disconnect(_managerVehicle->geoFenceManager(), nullptr, nullptr, nullptr);
disconnect(_managerVehicle->rallyPointManager(), nullptr, nullptr, nullptr); disconnect(_managerVehicle->rallyPointManager(), nullptr, nullptr, nullptr);
disconnect(_managerVehicle, &Vehicle::capabilityBitsChanged, this, &PlanMasterController::_updateSupportsTerrain);
} }
bool newOffline = false; bool newOffline = false;
...@@ -160,9 +155,6 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle) ...@@ -160,9 +155,6 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle)
connect(_managerVehicle->rallyPointManager(), &RallyPointManager::sendComplete, this, &PlanMasterController::_sendRallyPointsComplete); connect(_managerVehicle->rallyPointManager(), &RallyPointManager::sendComplete, this, &PlanMasterController::_sendRallyPointsComplete);
} }
// Change in capabilities will affect terrain support
connect(_managerVehicle, &Vehicle::capabilityBitsChanged, this, &PlanMasterController::_updateSupportsTerrain);
emit managerVehicleChanged(_managerVehicle); emit managerVehicleChanged(_managerVehicle);
// Vehicle changed so we need to signal everything // Vehicle changed so we need to signal everything
...@@ -171,7 +163,6 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle) ...@@ -171,7 +163,6 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle)
emit syncInProgressChanged(); emit syncInProgressChanged();
emit dirtyChanged(dirty()); emit dirtyChanged(dirty());
emit offlineChanged(offline()); emit offlineChanged(offline());
_updateSupportsTerrain();
if (!_flyView) { if (!_flyView) {
if (!offline()) { if (!offline()) {
...@@ -630,12 +621,3 @@ void PlanMasterController::_updatePlanCreatorsList(void) ...@@ -630,12 +621,3 @@ void PlanMasterController::_updatePlanCreatorsList(void)
} }
} }
} }
void PlanMasterController::_updateSupportsTerrain(void)
{
bool supportsTerrain = _managerVehicle->capabilityBits() & MAV_PROTOCOL_CAPABILITY_TERRAIN;
if (supportsTerrain != _supportsTerrain) {
_supportsTerrain = supportsTerrain;
emit supportsTerrainChanged(supportsTerrain);
}
}
...@@ -51,7 +51,6 @@ public: ...@@ -51,7 +51,6 @@ public:
Q_PROPERTY(QStringList loadNameFilters READ loadNameFilters CONSTANT) ///< File filter list loading plan files Q_PROPERTY(QStringList loadNameFilters READ loadNameFilters CONSTANT) ///< File filter list loading plan files
Q_PROPERTY(QStringList saveNameFilters READ saveNameFilters CONSTANT) ///< File filter list saving plan files Q_PROPERTY(QStringList saveNameFilters READ saveNameFilters CONSTANT) ///< File filter list saving plan files
Q_PROPERTY(QmlObjectListModel* planCreators MEMBER _planCreators NOTIFY planCreatorsChanged) Q_PROPERTY(QmlObjectListModel* planCreators MEMBER _planCreators NOTIFY planCreatorsChanged)
Q_PROPERTY(bool supportsTerrain READ supportsTerrain NOTIFY supportsTerrainChanged)
/// Should be called immediately upon Component.onCompleted. /// Should be called immediately upon Component.onCompleted.
Q_INVOKABLE void start(void); Q_INVOKABLE void start(void);
...@@ -94,7 +93,6 @@ public: ...@@ -94,7 +93,6 @@ public:
QStringList loadNameFilters (void) const; QStringList loadNameFilters (void) const;
QStringList saveNameFilters (void) const; QStringList saveNameFilters (void) const;
bool isEmpty (void) const; bool isEmpty (void) const;
bool supportsTerrain (void) const { return _supportsTerrain; }
void setFlyView(bool flyView) { _flyView = flyView; } void setFlyView(bool flyView) { _flyView = flyView; }
...@@ -117,7 +115,6 @@ signals: ...@@ -117,7 +115,6 @@ signals:
void currentPlanFileChanged (); void currentPlanFileChanged ();
void planCreatorsChanged (QmlObjectListModel* planCreators); void planCreatorsChanged (QmlObjectListModel* planCreators);
void managerVehicleChanged (Vehicle* managerVehicle); void managerVehicleChanged (Vehicle* managerVehicle);
void supportsTerrainChanged (bool supportsTerrain);
private slots: private slots:
void _activeVehicleChanged (Vehicle* activeVehicle); void _activeVehicleChanged (Vehicle* activeVehicle);
...@@ -128,7 +125,6 @@ private slots: ...@@ -128,7 +125,6 @@ private slots:
void _sendGeoFenceComplete (void); void _sendGeoFenceComplete (void);
void _sendRallyPointsComplete (void); void _sendRallyPointsComplete (void);
void _updatePlanCreatorsList (void); void _updatePlanCreatorsList (void);
void _updateSupportsTerrain (void);
#if defined(QGC_AIRMAP_ENABLED) #if defined(QGC_AIRMAP_ENABLED)
void _startFlightPlanning (void); void _startFlightPlanning (void);
#endif #endif
...@@ -152,5 +148,4 @@ private: ...@@ -152,5 +148,4 @@ private:
QString _currentPlanFile; QString _currentPlanFile;
bool _deleteWhenSendCompleted = false; bool _deleteWhenSendCompleted = false;
QmlObjectListModel* _planCreators = nullptr; QmlObjectListModel* _planCreators = nullptr;
bool _supportsTerrain = false;
}; };
...@@ -103,10 +103,10 @@ SimpleMissionItem::SimpleMissionItem(PlanMasterController* masterController, boo ...@@ -103,10 +103,10 @@ SimpleMissionItem::SimpleMissionItem(PlanMasterController* masterController, boo
}; };
const struct MavFrame2AltMode_s rgMavFrame2AltMode[] = { const struct MavFrame2AltMode_s rgMavFrame2AltMode[] = {
{ MAV_FRAME_GLOBAL_TERRAIN_ALT, QGroundControlQmlGlobal::AltitudeModeTerrainFrame }, { MAV_FRAME_GLOBAL_TERRAIN_ALT, QGroundControlQmlGlobal::AltitudeModeTerrainFrame },
{ MAV_FRAME_GLOBAL, QGroundControlQmlGlobal::AltitudeModeAbsolute }, { MAV_FRAME_GLOBAL, QGroundControlQmlGlobal::AltitudeModeAbsolute },
{ MAV_FRAME_GLOBAL_RELATIVE_ALT, QGroundControlQmlGlobal::AltitudeModeRelative }, { MAV_FRAME_GLOBAL_RELATIVE_ALT, QGroundControlQmlGlobal::AltitudeModeRelative },
}; };
_altitudeMode = QGroundControlQmlGlobal::AltitudeModeRelative; _altitudeMode = QGroundControlQmlGlobal::AltitudeModeRelative;
for (size_t i=0; i<sizeof(rgMavFrame2AltMode)/sizeof(rgMavFrame2AltMode[0]); i++) { for (size_t i=0; i<sizeof(rgMavFrame2AltMode)/sizeof(rgMavFrame2AltMode[0]); i++) {
const MavFrame2AltMode_s& pMavFrame2AltMode = rgMavFrame2AltMode[i]; const MavFrame2AltMode_s& pMavFrame2AltMode = rgMavFrame2AltMode[i];
...@@ -730,6 +730,7 @@ void SimpleMissionItem::_setDefaultsForCommand(void) ...@@ -730,6 +730,7 @@ void SimpleMissionItem::_setDefaultsForCommand(void)
double defaultAlt = qgcApp()->toolbox()->settingsManager()->appSettings()->defaultMissionItemAltitude()->rawValue().toDouble(); double defaultAlt = qgcApp()->toolbox()->settingsManager()->appSettings()->defaultMissionItemAltitude()->rawValue().toDouble();
_altitudeFact.setRawValue(defaultAlt); _altitudeFact.setRawValue(defaultAlt);
_missionItem._param7Fact.setRawValue(defaultAlt); _missionItem._param7Fact.setRawValue(defaultAlt);
setAltitudeMode(_missionController->globalAltitudeModeDefault());
} else { } else {
_altitudeFact.setRawValue(0); _altitudeFact.setRawValue(0);
_missionItem._param7Fact.setRawValue(0); _missionItem._param7Fact.setRawValue(0);
......
...@@ -96,7 +96,6 @@ Column { ...@@ -96,7 +96,6 @@ Column {
AltitudeFactTextField { AltitudeFactTextField {
fact: cameraCalc.distanceToSurface fact: cameraCalc.distanceToSurface
altitudeMode: distanceToSurfaceAltitudeMode altitudeMode: distanceToSurfaceAltitudeMode
showAboveTerrainWarning: false
enabled: fixedDistanceRadio.checked enabled: fixedDistanceRadio.checked
Layout.fillWidth: true Layout.fillWidth: true
} }
...@@ -130,7 +129,6 @@ Column { ...@@ -130,7 +129,6 @@ Column {
AltitudeFactTextField { AltitudeFactTextField {
fact: cameraCalc.distanceToSurface fact: cameraCalc.distanceToSurface
altitudeMode: distanceToSurfaceAltitudeMode altitudeMode: distanceToSurfaceAltitudeMode
showAboveTerrainWarning: false
Layout.fillWidth: true Layout.fillWidth: true
} }
......
...@@ -24,7 +24,6 @@ Rectangle { ...@@ -24,7 +24,6 @@ Rectangle {
property var _missionController: _masterControler.missionController property var _missionController: _masterControler.missionController
property var _controllerVehicle: _masterControler.controllerVehicle property var _controllerVehicle: _masterControler.controllerVehicle
property bool _vehicleHasHomePosition: _controllerVehicle.homePosition.isValid property bool _vehicleHasHomePosition: _controllerVehicle.homePosition.isValid
property bool _enableOfflineVehicleCombos: _noMissionItemsAdded
property bool _showCruiseSpeed: !_controllerVehicle.multiRotor property bool _showCruiseSpeed: !_controllerVehicle.multiRotor
property bool _showHoverSpeed: _controllerVehicle.multiRotor || _controllerVehicle.vtol property bool _showHoverSpeed: _controllerVehicle.multiRotor || _controllerVehicle.vtol
property bool _multipleFirmware: QGroundControl.supportedFirmwareCount > 2 property bool _multipleFirmware: QGroundControl.supportedFirmwareCount > 2
...@@ -46,7 +45,7 @@ Rectangle { ...@@ -46,7 +45,7 @@ Rectangle {
QGCPalette { id: qgcPal } QGCPalette { id: qgcPal }
QGCFileDialogController { id: fileController } QGCFileDialogController { id: fileController }
Column { ColumnLayout {
id: valuesColumn id: valuesColumn
anchors.margins: _margin anchors.margins: _margin
anchors.left: parent.left anchors.left: parent.left
...@@ -54,20 +53,87 @@ Rectangle { ...@@ -54,20 +53,87 @@ Rectangle {
anchors.top: parent.top anchors.top: parent.top
spacing: _margin spacing: _margin
GridLayout { QGCLabel {
anchors.left: parent.left text: qsTr("All Altitudes")
anchors.right: parent.right font.pointSize: ScreenTools.smallFontPointSize
columnSpacing: ScreenTools.defaultFontPixelWidth }
rowSpacing: columnSpacing QGCComboBox {
columns: 2 id: altModeCombo
model: enumStrings
Layout.fillWidth: true
enabled: _noMissionItemsAdded
onActivated: _missionController.globalAltitudeMode = enumValues[index]
Component.onCompleted: buildEnumStrings()
QGCLabel { readonly property var enumStringsBase: [ QGroundControl.altitudeModeShortDescription(QGroundControl.AltitudeModeRelative),
text: qsTr("Waypoint alt") QGroundControl.altitudeModeShortDescription(QGroundControl.AltitudeModeAbsolute),
QGroundControl.altitudeModeShortDescription(QGroundControl.AltitudeModeAboveTerrain),
QGroundControl.altitudeModeShortDescription(QGroundControl.AltitudeModeTerrainFrame),
qsTr("Mixed Modes") ]
readonly property var enumValuesBase: [QGroundControl.AltitudeModeRelative, QGroundControl.AltitudeModeAbsolute, QGroundControl.AltitudeModeAboveTerrain, QGroundControl.AltitudeModeTerrainFrame, QGroundControl.AltitudeModeNone ]
property var enumStrings: [ ]
property var enumValues: [ ]
function buildEnumStrings() {
var newEnumStrings = enumStringsBase.slice(0)
var newEnumValues = enumValuesBase.slice(0)
if (!_controllerVehicle.supportsTerrainFrame) {
// We need to find and pull out the QGroundControl.AltitudeModeTerrainFrame values
var deleteIndex = newEnumValues.lastIndexOf(QGroundControl.AltitudeModeTerrainFrame)
newEnumStrings.splice(deleteIndex, 1)
newEnumValues.splice(deleteIndex, 1)
if (_missionController.globalAltitudeMode == QGroundControl.AltitudeModeTerrainFrame) {
_missionController.globalAltitudeMode = QGroundControl.AltitudeModeAboveTerrain
}
}
enumStrings = newEnumStrings
enumValues = newEnumValues
currentIndex = enumValues.lastIndexOf(_missionController.globalAltitudeMode)
} }
FactTextField {
fact: QGroundControl.settingsManager.appSettings.defaultMissionItemAltitude Connections {
Layout.fillWidth: true target: _controllerVehicle
onSupportsTerrainFrameChanged: altModeCombo.buildEnumStrings()
} }
}
QGCLabel {
Layout.fillWidth: true
wrapMode: Text.WordWrap
horizontalAlignment: Text.AlignHCenter
font.pointSize: ScreenTools.smallFontPointSize
text: switch(_missionController.globalAltitudeMode) {
case QGroundControl.AltitudeModeAboveTerrain:
qsTr("Specified altitudes are distance above terrain. Actual altitudes sent to vehicle are calculated from terrain data and sent in AMSL")
break
case QGroundControl.AltitudeModeTerrainFrame:
qsTr("Specified altitudes are distance above terrain. The actual altitude flown is controlled by the vehicle either from terrain height maps being sent to vehicle or a distance sensor.")
break
case QGroundControl.AltitudeModeNone:
qsTr("The altitude mode can differ for each individual item.")
break
default:
""
break
}
visible: _missionController.globalAltitudeMode == QGroundControl.AltitudeModeAboveTerrain || _missionController.globalAltitudeMode == QGroundControl.AltitudeModeTerrainFrame || _missionController.globalAltitudeMode == QGroundControl.AltitudeModeNone
}
QGCLabel {
text: qsTr("Initial Waypoint Alt")
font.pointSize: ScreenTools.smallFontPointSize
}
AltitudeFactTextField {
fact: QGroundControl.settingsManager.appSettings.defaultMissionItemAltitude
altitudeMode: _missionController.globalAltitudeModeDefault
Layout.fillWidth: true
}
GridLayout {
Layout.fillWidth: true
columnSpacing: ScreenTools.defaultFontPixelWidth
rowSpacing: columnSpacing
columns: 2
QGCCheckBox { QGCCheckBox {
id: flightSpeedCheckBox id: flightSpeedCheckBox
...@@ -85,10 +151,9 @@ Rectangle { ...@@ -85,10 +151,9 @@ Rectangle {
} }
Column { Column {
anchors.left: parent.left Layout.fillWidth: true
anchors.right: parent.right spacing: _margin
spacing: _margin visible: !_simpleMissionStart
visible: !_simpleMissionStart
CameraSection { CameraSection {
id: cameraSection id: cameraSection
...@@ -132,11 +197,11 @@ Rectangle { ...@@ -132,11 +197,11 @@ Rectangle {
fact: QGroundControl.settingsManager.appSettings.offlineEditingFirmwareType fact: QGroundControl.settingsManager.appSettings.offlineEditingFirmwareType
indexModel: false indexModel: false
Layout.preferredWidth: _fieldWidth Layout.preferredWidth: _fieldWidth
visible: _multipleFirmware && _enableOfflineVehicleCombos visible: _multipleFirmware && _noMissionItemsAdded
} }
QGCLabel { QGCLabel {
text: _controllerVehicle.firmwareTypeString text: _controllerVehicle.firmwareTypeString
visible: _multipleFirmware && !_enableOfflineVehicleCombos visible: _multipleFirmware && !_noMissionItemsAdded
} }
QGCLabel { QGCLabel {
...@@ -148,11 +213,11 @@ Rectangle { ...@@ -148,11 +213,11 @@ Rectangle {
fact: QGroundControl.settingsManager.appSettings.offlineEditingVehicleType fact: QGroundControl.settingsManager.appSettings.offlineEditingVehicleType
indexModel: false indexModel: false
Layout.preferredWidth: _fieldWidth Layout.preferredWidth: _fieldWidth
visible: _multipleVehicleTypes && _enableOfflineVehicleCombos visible: _multipleVehicleTypes && _noMissionItemsAdded
} }
QGCLabel { QGCLabel {
text: _controllerVehicle.vehicleTypeString text: _controllerVehicle.vehicleTypeString
visible: _multipleVehicleTypes && !_enableOfflineVehicleCombos visible: _multipleVehicleTypes && !_noMissionItemsAdded
} }
QGCLabel { QGCLabel {
......
...@@ -21,6 +21,8 @@ Rectangle { ...@@ -21,6 +21,8 @@ Rectangle {
property real _margin: ScreenTools.defaultFontPixelHeight / 2 property real _margin: ScreenTools.defaultFontPixelHeight / 2
property bool _supportsTerrainFrame: missionItem.masterController.supportsTerrain property bool _supportsTerrainFrame: missionItem.masterController.supportsTerrain
property var _controllerVehicle: missionItem.masterController.controllerVehicle property var _controllerVehicle: missionItem.masterController.controllerVehicle
property int _globalAltMode: missionItem.masterController.missionController.globalAltitudeMode
property bool _globalAltModeIsMixed: _globalAltMode == QGroundControl.AltitudeModeNone
property string _altModeRelativeHelpText: qsTr("Altitude relative to launch altitude") property string _altModeRelativeHelpText: qsTr("Altitude relative to launch altitude")
property string _altModeAbsoluteHelpText: qsTr("Altitude above mean sea level") property string _altModeAbsoluteHelpText: qsTr("Altitude above mean sea level")
...@@ -29,16 +31,16 @@ Rectangle { ...@@ -29,16 +31,16 @@ Rectangle {
function updateAltitudeModeText() { function updateAltitudeModeText() {
if (missionItem.altitudeMode === QGroundControl.AltitudeModeRelative) { if (missionItem.altitudeMode === QGroundControl.AltitudeModeRelative) {
altModeLabel.text = qsTr("Altitude") altModeLabel.text = QGroundControl.altitudeModeShortDescription(QGroundControl.AltitudeModeRelative)
altModeHelp.text = _altModeRelativeHelpText altModeHelp.text = _altModeRelativeHelpText
} else if (missionItem.altitudeMode === QGroundControl.AltitudeModeAbsolute) { } else if (missionItem.altitudeMode === QGroundControl.AltitudeModeAbsolute) {
altModeLabel.text = qsTr("Above Mean Sea Level") altModeLabel.text = QGroundControl.altitudeModeShortDescription(QGroundControl.AltitudeModeAbsolute)
altModeHelp.text = _altModeAbsoluteHelpText altModeHelp.text = _altModeAbsoluteHelpText
} else if (missionItem.altitudeMode === QGroundControl.AltitudeModeAboveTerrain) { } else if (missionItem.altitudeMode === QGroundControl.AltitudeModeAboveTerrain) {
altModeLabel.text = qsTr("Above Terrain") altModeLabel.text = QGroundControl.altitudeModeShortDescription(QGroundControl.AltitudeModeAboveTerrain)
altModeHelp.text = Qt.binding(function() { return _altModeAboveTerrainHelpText }) altModeHelp.text = Qt.binding(function() { return _altModeAboveTerrainHelpText })
} else if (missionItem.altitudeMode === QGroundControl.AltitudeModeTerrainFrame) { } else if (missionItem.altitudeMode === QGroundControl.AltitudeModeTerrainFrame) {
altModeLabel.text = qsTr("Terrain Frame") altModeLabel.text = QGroundControl.altitudeModeShortDescription(QGroundControl.AltitudeModeTerrainFrame)
altModeHelp.text = _altModeTerrainFrameHelpText altModeHelp.text = _altModeTerrainFrameHelpText
} else { } else {
altModeLabel.text = qsTr("Internal Error") altModeLabel.text = qsTr("Internal Error")
...@@ -149,37 +151,39 @@ Rectangle { ...@@ -149,37 +151,39 @@ Rectangle {
} }
} }
// This control needs to morph between a simple altitude entry field to a more complex alt mode picker based on the global plan alt mode
Rectangle { Rectangle {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
height: altColumn.y + altColumn.height + _margin height: altColumn.y + altColumn.height + _margin
color: qgcPal.windowShade color: _globalAltModeIsMixed ? qgcPal.windowShade: qgcPal.window
visible: _specifiesAltitude visible: _specifiesAltitude
Column { ColumnLayout {
id: altColumn id: altColumn
anchors.margins: _margin anchors.margins: _globalAltModeIsMixed ? _margin : 0
anchors.top: parent.top anchors.top: parent.top
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: _margin spacing: _globalAltModeIsMixed ? _margin : 0
QGCLabel { QGCLabel {
width: parent.width Layout.fillWidth: true
wrapMode: Text.WordWrap wrapMode: Text.WordWrap
font.pointSize: ScreenTools.smallFontPointSize font.pointSize: ScreenTools.smallFontPointSize
text: qsTr("Altitude below specifies the approximate altitude of the ground. Normally 0 for landing back at original launch location.") text: qsTr("Altitude below specifies the approximate altitude of the ground. Normally 0 for landing back at original launch location.")
visible: missionItem.isLandCommand visible: missionItem.isLandCommand
} }
Item { Item {
width: altHamburger.x + altHamburger.width width: altModeDropArrow.x + altModeDropArrow.width
height: altModeLabel.height height: altModeLabel.height
visible: _globalAltModeIsMixed
QGCLabel { id: altModeLabel } QGCLabel { id: altModeLabel }
QGCColoredImage { QGCColoredImage {
id: altHamburger id: altModeDropArrow
anchors.leftMargin: ScreenTools.defaultFontPixelWidth / 4 anchors.leftMargin: ScreenTools.defaultFontPixelWidth / 4
anchors.left: altModeLabel.right anchors.left: altModeLabel.right
anchors.verticalCenter: altModeLabel.verticalCenter anchors.verticalCenter: altModeLabel.verticalCenter
...@@ -192,21 +196,21 @@ Rectangle { ...@@ -192,21 +196,21 @@ Rectangle {
QGCMouseArea { QGCMouseArea {
anchors.fill: parent anchors.fill: parent
onClicked: altHamburgerMenu.popup() onClicked: altModeMenu.popup()
} }
QGCMenu { QGCMenu {
id: altHamburgerMenu id: altModeMenu
QGCMenuItem { QGCMenuItem {
text: qsTr("Altitude Relative To Launch") text: QGroundControl.altitudeModeShortDescription(QGroundControl.AltitudeModeRelative)
checkable: true checkable: true
checked: missionItem.altitudeMode === QGroundControl.AltitudeModeRelative checked: missionItem.altitudeMode === QGroundControl.AltitudeModeRelative
onTriggered: missionItem.altitudeMode = QGroundControl.AltitudeModeRelative onTriggered: missionItem.altitudeMode = QGroundControl.AltitudeModeRelative
} }
QGCMenuItem { QGCMenuItem {
text: qsTr("Altitude Above Mean Sea Level") text: QGroundControl.altitudeModeShortDescription(QGroundControl.AltitudeModeAbsolute)
checkable: true checkable: true
checked: missionItem.altitudeMode === QGroundControl.AltitudeModeAbsolute checked: missionItem.altitudeMode === QGroundControl.AltitudeModeAbsolute
visible: QGroundControl.corePlugin.options.showMissionAbsoluteAltitude visible: QGroundControl.corePlugin.options.showMissionAbsoluteAltitude
...@@ -214,7 +218,7 @@ Rectangle { ...@@ -214,7 +218,7 @@ Rectangle {
} }
QGCMenuItem { QGCMenuItem {
text: qsTr("Altitude Above Terrain") text: QGroundControl.altitudeModeShortDescription(QGroundControl.AltitudeModeAboveTerrain)
checkable: true checkable: true
checked: missionItem.altitudeMode === QGroundControl.AltitudeModeAboveTerrain checked: missionItem.altitudeMode === QGroundControl.AltitudeModeAboveTerrain
onTriggered: missionItem.altitudeMode = QGroundControl.AltitudeModeAboveTerrain onTriggered: missionItem.altitudeMode = QGroundControl.AltitudeModeAboveTerrain
...@@ -222,7 +226,7 @@ Rectangle { ...@@ -222,7 +226,7 @@ Rectangle {
} }
QGCMenuItem { QGCMenuItem {
text: qsTr("Terrain Frame") text: QGroundControl.altitudeModeShortDescription(QGroundControl.AltitudeModeTerrainFrame)
checkable: true checkable: true
checked: missionItem.altitudeMode === QGroundControl.AltitudeModeTerrainFrame checked: missionItem.altitudeMode === QGroundControl.AltitudeModeTerrainFrame
visible: _supportsTerrainFrame && (missionItem.specifiesCoordinate || missionItem.specifiesAltitudeOnly) visible: _supportsTerrainFrame && (missionItem.specifiesCoordinate || missionItem.specifiesAltitudeOnly)
...@@ -231,20 +235,25 @@ Rectangle { ...@@ -231,20 +235,25 @@ Rectangle {
} }
} }
QGCLabel {
text: qsTr("Altitude")
font.pointSize: ScreenTools.smallFontPointSize
visible: !_globalAltModeIsMixed
}
AltitudeFactTextField { AltitudeFactTextField {
id: altField id: altField
Layout.fillWidth: true
fact: missionItem.altitude fact: missionItem.altitude
altitudeMode: missionItem.altitudeMode altitudeMode: missionItem.altitudeMode
anchors.left: parent.left
anchors.right: parent.right
} }
QGCLabel { QGCLabel {
id: altModeHelp id: altModeHelp
Layout.fillWidth: true
wrapMode: Text.WordWrap wrapMode: Text.WordWrap
font.pointSize: ScreenTools.smallFontPointSize font.pointSize: ScreenTools.smallFontPointSize
anchors.left: parent.left visible: _globalAltModeIsMixed
anchors.right: parent.right
} }
} }
} }
......
...@@ -267,3 +267,42 @@ QString QGroundControlQmlGlobal::qgcVersion(void) const ...@@ -267,3 +267,42 @@ QString QGroundControlQmlGlobal::qgcVersion(void) const
#endif #endif
return versionStr; return versionStr;
} }
QString QGroundControlQmlGlobal::altitudeModeExtraUnits(AltitudeMode altMode)
{
switch (altMode) {
case AltitudeModeNone:
return QString();
case AltitudeModeRelative:
// Showing (Rel) all the time ends up being too noisy
return QString();
case AltitudeModeAbsolute:
return tr("(AMSL)");
case AltitudeModeAboveTerrain:
return tr("(Abv Terr)");
case AltitudeModeTerrainFrame:
return tr("(TerrF)");
}
// Should never get here but makes some compilers happy
return QString();
}
QString QGroundControlQmlGlobal::altitudeModeShortDescription(AltitudeMode altMode)
{
switch (altMode) {
case AltitudeModeNone:
return QString();
case AltitudeModeRelative:
return tr("Relative To Launch");
case AltitudeModeAbsolute:
return tr("Above Mean Sea Level");
case AltitudeModeAboveTerrain:
return tr("Above Terrain");
case AltitudeModeTerrainFrame:
return tr("Terrain Frame");
}
// Should never get here but makes some compilers happy
return QString();
}
...@@ -148,6 +148,9 @@ public: ...@@ -148,6 +148,9 @@ public:
Q_INVOKABLE bool linesIntersect(QPointF xLine1, QPointF yLine1, QPointF xLine2, QPointF yLine2); Q_INVOKABLE bool linesIntersect(QPointF xLine1, QPointF yLine1, QPointF xLine2, QPointF yLine2);
Q_INVOKABLE QString altitudeModeExtraUnits(AltitudeMode altMode); ///< String shown in the FactTextField.extraUnits ui
Q_INVOKABLE QString altitudeModeShortDescription(AltitudeMode altMode); ///< String shown when a user needs to select an altitude mode
// Property accesors // Property accesors
QString appName () { return qgcApp()->applicationName(); } QString appName () { return qgcApp()->applicationName(); }
...@@ -268,6 +271,7 @@ private: ...@@ -268,6 +271,7 @@ private:
#endif #endif
bool _skipSetupPage = false; bool _skipSetupPage = false;
QStringList _altitudeModeEnumString;
static const char* _flightMapPositionSettingsGroup; static const char* _flightMapPositionSettingsGroup;
static const char* _flightMapPositionLatitudeSettingsKey; static const char* _flightMapPositionLatitudeSettingsKey;
......
...@@ -3038,7 +3038,7 @@ bool Vehicle::supportsMotorInterference() const ...@@ -3038,7 +3038,7 @@ bool Vehicle::supportsMotorInterference() const
bool Vehicle::supportsTerrainFrame() const bool Vehicle::supportsTerrainFrame() const
{ {
return _capabilityBits & MAV_PROTOCOL_CAPABILITY_TERRAIN; return !px4Firmware();
} }
QString Vehicle::vehicleTypeName() const { QString Vehicle::vehicleTypeName() const {
......
...@@ -627,7 +627,7 @@ public: ...@@ -627,7 +627,7 @@ public:
Q_PROPERTY(QString hobbsMeter READ hobbsMeter NOTIFY hobbsMeterChanged) Q_PROPERTY(QString hobbsMeter READ hobbsMeter NOTIFY hobbsMeterChanged)
Q_PROPERTY(bool vtolInFwdFlight READ vtolInFwdFlight WRITE setVtolInFwdFlight NOTIFY vtolInFwdFlightChanged) Q_PROPERTY(bool vtolInFwdFlight READ vtolInFwdFlight WRITE setVtolInFwdFlight NOTIFY vtolInFwdFlightChanged)
Q_PROPERTY(bool highLatencyLink READ highLatencyLink NOTIFY highLatencyLinkChanged) Q_PROPERTY(bool highLatencyLink READ highLatencyLink NOTIFY highLatencyLinkChanged)
Q_PROPERTY(bool supportsTerrainFrame READ supportsTerrainFrame NOTIFY capabilityBitsChanged) Q_PROPERTY(bool supportsTerrainFrame READ supportsTerrainFrame NOTIFY firmwareTypeChanged)
Q_PROPERTY(QString priorityLinkName READ priorityLinkName WRITE setPriorityLinkByName NOTIFY priorityLinkNameChanged) Q_PROPERTY(QString priorityLinkName READ priorityLinkName WRITE setPriorityLinkByName NOTIFY priorityLinkNameChanged)
Q_PROPERTY(QVariantList links READ links NOTIFY linksChanged) Q_PROPERTY(QVariantList links READ links NOTIFY linksChanged)
Q_PROPERTY(LinkInterface* priorityLink READ priorityLink NOTIFY priorityLinkNameChanged) Q_PROPERTY(LinkInterface* priorityLink READ priorityLink NOTIFY priorityLinkNameChanged)
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment