diff --git a/src/FirmwarePlugin/APM/APMGeoFenceManager.cc b/src/FirmwarePlugin/APM/APMGeoFenceManager.cc index a2562dd271c570ad66357df13e4bca60f4d67525..f65fb476ce472b54eb842ae918b984ee39e57e25 100644 --- a/src/FirmwarePlugin/APM/APMGeoFenceManager.cc +++ b/src/FirmwarePlugin/APM/APMGeoFenceManager.cc @@ -21,14 +21,15 @@ const char* APMGeoFenceManager::_fenceEnableParam = "FENCE_ENABLE"; APMGeoFenceManager::APMGeoFenceManager(Vehicle* vehicle) : GeoFenceManager(vehicle) , _fenceSupported(false) - , _breachReturnSupported(vehicle->fixedWing()) - , _circleSupported(false) - , _polygonSupported(false) + , _breachReturnEnabled(vehicle->fixedWing()) + , _circleEnabled(false) + , _polygonEnabled(false) , _firstParamLoadComplete(false) - , _circleRadiusFact(NULL) , _readTransactionInProgress(false) , _writeTransactionInProgress(false) , _fenceTypeFact(NULL) + , _fenceEnableFact(NULL) + , _circleRadiusFact(NULL) { connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &APMGeoFenceManager::_mavlinkMessageReceived); connect(_vehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &APMGeoFenceManager::_parametersReady); @@ -54,15 +55,15 @@ void APMGeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn, const return; } - if (!_geoFenceSupported()) { + if (!_fenceSupported) { return; } // Validate - int validatedPolygonCount = polygon.count(); - if (polygonSupported()) { - if (polygon.count() < 3) { - validatedPolygonCount = 0; + int validatedPolygonCount = 0; + if (polygonEnabled()) { + if (polygon.count() >= 3) { + validatedPolygonCount = polygon.count(); } if (polygon.count() > std::numeric_limits::max()) { _sendError(TooManyPoints, QStringLiteral("Geo-Fence polygon has too many points: %1.").arg(_polygon.count())); @@ -71,7 +72,11 @@ void APMGeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn, const } _breachReturnPoint = breachReturn; - _polygon = polygon; + if (validatedPolygonCount) { + _polygon = polygon; + } else { + _polygon.clear(); + } // Total point count, +1 polygon close in last index, +1 for breach in index 0 _cWriteFencePoints = validatedPolygonCount ? validatedPolygonCount + 1 + 1 : 0; @@ -94,7 +99,7 @@ void APMGeoFenceManager::loadFromVehicle(void) _breachReturnPoint = QGeoCoordinate(); _polygon.clear(); - if (!_geoFenceSupported()) { + if (!_fenceSupported) { return; } @@ -217,57 +222,27 @@ bool APMGeoFenceManager::inProgress(void) const return _readTransactionInProgress || _writeTransactionInProgress; } -bool APMGeoFenceManager::_geoFenceSupported(void) +void APMGeoFenceManager::_updateEnabledFlags(void) { - // FIXME: MockLink doesn't support geo fence yet - if (qgcApp()->runningUnitTests()) { - return false; - } - - if (!_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _fenceTotalParam) || - !_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _fenceActionParam)) { - return false; + bool fenceEnabled; + if (_fenceEnableFact) { + fenceEnabled = _fenceEnableFact->rawValue().toBool(); } else { - return true; - } -} - -bool APMGeoFenceManager::fenceEnabled(void) const -{ - if (qgcApp()->runningUnitTests()) { - return false; - } - - if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _fenceEnableParam)) { - bool fenceEnabled = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _fenceEnableParam)->rawValue().toBool(); - qCDebug(GeoFenceManagerLog) << "FENCE_ENABLE available" << fenceEnabled; - return fenceEnabled; + fenceEnabled = true; } - qCDebug(GeoFenceManagerLog) << "FENCE_ENABLE not available"; - return true; -} - -void APMGeoFenceManager::_fenceEnabledRawValueChanged(QVariant value) -{ - qCDebug(GeoFenceManagerLog) << "FENCE_ENABLE changed" << value.toBool(); - emit fenceEnabledChanged(!qgcApp()->runningUnitTests() && value.toBool()); -} - -void APMGeoFenceManager::_updateSupportedFlags(void) -{ - bool newCircleSupported = _fenceSupported && _vehicle->multiRotor() && _fenceTypeFact && (_fenceTypeFact->rawValue().toInt() & 2); - if (newCircleSupported != _circleSupported) { - _circleSupported = newCircleSupported; - emit circleSupportedChanged(newCircleSupported); + bool newCircleEnabled = _fenceSupported && fenceEnabled && _fenceTypeFact && (_fenceTypeFact->rawValue().toInt() & 2); + if (newCircleEnabled != _circleEnabled) { + _circleEnabled = newCircleEnabled; + emit circleEnabledChanged(newCircleEnabled); } - bool newPolygonSupported = _fenceSupported && + bool newPolygonEnabled = _fenceSupported && fenceEnabled && ((_vehicle->multiRotor() && _fenceTypeFact && (_fenceTypeFact->rawValue().toInt() & 4)) || _vehicle->fixedWing()); - if (newPolygonSupported != _polygonSupported) { - _polygonSupported = newPolygonSupported; - emit polygonSupportedChanged(newPolygonSupported); + if (newPolygonEnabled != _polygonEnabled) { + _polygonEnabled = newPolygonEnabled; + emit polygonEnabledChanged(newPolygonEnabled); } } @@ -276,20 +251,21 @@ void APMGeoFenceManager::_parametersReady(void) if (!_firstParamLoadComplete) { _firstParamLoadComplete = true; - _fenceSupported = _vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, QStringLiteral("FENCE_ACTION")); + _fenceSupported = _vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, QStringLiteral("FENCE_ACTION")) && + !qgcApp()->runningUnitTests(); if (_fenceSupported) { QStringList paramNames; QStringList paramLabels; if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _fenceEnableParam)) { - connect(_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _fenceEnableParam), &Fact::rawValueChanged, this, &APMGeoFenceManager::_fenceEnabledRawValueChanged); + _fenceEnableFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _fenceEnableParam); + connect(_fenceEnableFact, &Fact::rawValueChanged, this, &APMGeoFenceManager::_updateEnabledFlags); } if (_vehicle->multiRotor()) { _fenceTypeFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("FENCE_TYPE")); - - connect(_fenceTypeFact, &Fact::rawValueChanged, this, &APMGeoFenceManager::_updateSupportedFlags); + connect(_fenceTypeFact, &Fact::rawValueChanged, this, &APMGeoFenceManager::_updateEnabledFlags); _circleRadiusFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("FENCE_RADIUS")); connect(_circleRadiusFact, &Fact::rawValueChanged, this, &APMGeoFenceManager::_circleRadiusRawValueChanged); @@ -319,18 +295,17 @@ void APMGeoFenceManager::_parametersReady(void) emit paramsChanged(_params); emit paramLabelsChanged(_paramLabels); - emit fenceSupportedChanged(_fenceSupported); - _updateSupportedFlags(); + _updateEnabledFlags(); } - qCDebug(GeoFenceManagerLog) << "fenceSupported:circleSupported:polygonSupported:breachReturnSupported" << - _fenceSupported << circleSupported() << polygonSupported() << _breachReturnSupported; + qCDebug(GeoFenceManagerLog) << "fenceSupported:circleEnabled:polygonEnabled:breachReturnEnabled" << + _fenceSupported << _circleEnabled << _polygonEnabled << _breachReturnEnabled; } } float APMGeoFenceManager::circleRadius(void) const { - if (_circleRadiusFact) { + if (_circleEnabled) { return _circleRadiusFact->rawValue().toFloat(); } else { return 0.0; @@ -342,16 +317,6 @@ void APMGeoFenceManager::_circleRadiusRawValueChanged(QVariant value) emit circleRadiusChanged(value.toFloat()); } -bool APMGeoFenceManager::circleSupported(void) const -{ - return _circleSupported; -} - -bool APMGeoFenceManager::polygonSupported(void) const -{ - return _polygonSupported; -} - QString APMGeoFenceManager::editorQml(void) const { return _vehicle->multiRotor() ? diff --git a/src/FirmwarePlugin/APM/APMGeoFenceManager.h b/src/FirmwarePlugin/APM/APMGeoFenceManager.h index 8002de668ca6363c4463ed3b460fe31a81db187a..0540c3e68ec8a40e03180b873f72dedf940180ab 100644 --- a/src/FirmwarePlugin/APM/APMGeoFenceManager.h +++ b/src/FirmwarePlugin/APM/APMGeoFenceManager.h @@ -23,43 +23,37 @@ public: ~APMGeoFenceManager(); // Overrides from GeoFenceManager - bool inProgress (void) const final; - void loadFromVehicle (void) final; - void sendToVehicle (const QGeoCoordinate& breachReturn, const QList& polygon) final; - bool fenceSupported (void) const final { return _fenceSupported; } - bool fenceEnabled (void) const final; - bool circleSupported (void) const final; - bool polygonSupported (void) const final; - bool breachReturnSupported (void) const final { return _breachReturnSupported; } - float circleRadius (void) const final; - QVariantList params (void) const final { return _params; } - QStringList paramLabels (void) const final { return _paramLabels; } - QString editorQml (void) const final; + bool inProgress (void) const final; + void loadFromVehicle (void) final; + void sendToVehicle (const QGeoCoordinate& breachReturn, const QList& polygon) final; + bool circleEnabled (void) const final { return _circleEnabled; } + bool polygonEnabled (void) const final { return _polygonEnabled; } + bool breachReturnEnabled (void) const final { return _breachReturnEnabled; } + float circleRadius (void) const final; + QVariantList params (void) const final { return _params; } + QStringList paramLabels (void) const final { return _paramLabels; } + QString editorQml (void) const final; private slots: void _mavlinkMessageReceived(const mavlink_message_t& message); - void _updateSupportedFlags(void); + void _updateEnabledFlags(void); void _circleRadiusRawValueChanged(QVariant value); void _parametersReady(void); - void _fenceEnabledRawValueChanged(QVariant value); private: void _requestFencePoint(uint8_t pointIndex); void _sendFencePoint(uint8_t pointIndex); - bool _geoFenceSupported(void); private: bool _fenceSupported; - bool _breachReturnSupported; - bool _circleSupported; - bool _polygonSupported; + bool _breachReturnEnabled; + bool _circleEnabled; + bool _polygonEnabled; bool _firstParamLoadComplete; QVariantList _params; QStringList _paramLabels; - Fact* _circleRadiusFact; - bool _readTransactionInProgress; bool _writeTransactionInProgress; @@ -68,6 +62,8 @@ private: uint8_t _currentFencePoint; Fact* _fenceTypeFact; + Fact* _fenceEnableFact; + Fact* _circleRadiusFact; static const char* _fenceTotalParam; static const char* _fenceActionParam; diff --git a/src/FirmwarePlugin/PX4/PX4GeoFenceManager.cc b/src/FirmwarePlugin/PX4/PX4GeoFenceManager.cc index c7b2251eaf32d8e0f483b67931d2a47690d5f5f5..063b428baaaf33a04d69096cf051923dc123491b 100644 --- a/src/FirmwarePlugin/PX4/PX4GeoFenceManager.cc +++ b/src/FirmwarePlugin/PX4/PX4GeoFenceManager.cc @@ -15,6 +15,7 @@ PX4GeoFenceManager::PX4GeoFenceManager(Vehicle* vehicle) : GeoFenceManager(vehicle) , _firstParamLoadComplete(false) + , _circleEnabled(false) , _circleRadiusFact(NULL) { connect(_vehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &PX4GeoFenceManager::_parametersReady); @@ -57,10 +58,11 @@ void PX4GeoFenceManager::_parametersReady(void) emit paramsChanged(_params); emit paramLabelsChanged(_paramLabels); - emit circleSupportedChanged(circleSupported()); + _circleEnabled = true; + emit circleEnabledChanged(true); qCDebug(GeoFenceManagerLog) << "fenceSupported:circleSupported:polygonSupported:breachReturnSupported" << - fenceSupported() << circleSupported() << polygonSupported() << breachReturnSupported(); + _circleEnabled << polygonEnabled() << breachReturnEnabled(); } } @@ -76,14 +78,5 @@ float PX4GeoFenceManager::circleRadius(void) const void PX4GeoFenceManager::_circleRadiusRawValueChanged(QVariant value) { emit circleRadiusChanged(value.toFloat()); - emit circleSupportedChanged(circleSupported()); } -bool PX4GeoFenceManager::circleSupported(void) const -{ - if (_circleRadiusFact) { - return _circleRadiusFact->rawValue().toFloat() >= 0.0; - } - - return false; -} diff --git a/src/FirmwarePlugin/PX4/PX4GeoFenceManager.h b/src/FirmwarePlugin/PX4/PX4GeoFenceManager.h index fbeed77746d9198a7a98faf06182c7bebd9f7eab..b29cf1038f759d7f6aa6b45ba482efae1e2bda5c 100644 --- a/src/FirmwarePlugin/PX4/PX4GeoFenceManager.h +++ b/src/FirmwarePlugin/PX4/PX4GeoFenceManager.h @@ -23,12 +23,11 @@ public: ~PX4GeoFenceManager(); // Overrides from GeoFenceManager - bool fenceSupported (void) const final { return true; } - bool circleSupported (void) const final; - float circleRadius (void) const final; - QVariantList params (void) const final { return _params; } - QStringList paramLabels (void) const final { return _paramLabels; } - QString editorQml (void) const final { return QStringLiteral("qrc:/FirmwarePlugin/PX4/PX4GeoFenceEditor.qml"); } + bool circleEnabled (void) const final { return _circleEnabled; } + float circleRadius (void) const final; + QVariantList params (void) const final { return _params; } + QStringList paramLabels (void) const final { return _paramLabels; } + QString editorQml (void) const final { return QStringLiteral("qrc:/FirmwarePlugin/PX4/PX4GeoFenceEditor.qml"); } private slots: void _circleRadiusRawValueChanged(QVariant value); @@ -39,6 +38,7 @@ private: QVariantList _params; QStringList _paramLabels; + bool _circleEnabled; Fact* _circleRadiusFact; }; diff --git a/src/FlightDisplay/FlightDisplayViewMap.qml b/src/FlightDisplay/FlightDisplayViewMap.qml index 69cc038a59bc04c473c7084c9dc4530c9aa6abf2..cce975b99cb1656f0c7fe61d50a8468a9de8e982 100644 --- a/src/FlightDisplay/FlightDisplayViewMap.qml +++ b/src/FlightDisplay/FlightDisplayViewMap.qml @@ -111,7 +111,7 @@ FlightMap { border.color: "#80FF0000" border.width: 3 path: geoFenceController.polygon.path - visible: geoFenceController.fenceEnabled && geoFenceController.polygonSupported + visible: geoFenceController.polygonEnabled } // GeoFence circle @@ -119,16 +119,16 @@ FlightMap { border.color: "#80FF0000" border.width: 3 center: missionController.plannedHomePosition - radius: (geoFenceController.fenceEnabled && geoFenceController.circleSupported) ? geoFenceController.circleRadius : 0 + radius: geoFenceController.circleRadius z: QGroundControl.zOrderMapItems - visible: geoFenceController.fenceEnabled && geoFenceController.circleSupported + visible: geoFenceController.circleEnabled } // GeoFence breach return point MapQuickItem { anchorPoint: Qt.point(sourceItem.width / 2, sourceItem.height / 2) coordinate: geoFenceController.breachReturnPoint - visible: geoFenceController.fenceEnabled && geoFenceController.breachReturnSupported + visible: geoFenceController.breachReturnEnabled sourceItem: MissionItemIndexLabel { label: "F" } z: QGroundControl.zOrderMapItems } diff --git a/src/MissionEditor/MissionEditor.qml b/src/MissionEditor/MissionEditor.qml index fadd6595fc3e60ba8ae924fd63728ec036d6bb09..c7b8bfd148080ea62407a835375b8b017b8f22ce 100644 --- a/src/MissionEditor/MissionEditor.qml +++ b/src/MissionEditor/MissionEditor.qml @@ -145,14 +145,14 @@ QGCView { } function addFenceItemCoordsForFit(coordList) { - if (geoFenceController.circleSupported) { + if (geoFenceController.circleEnabled) { var azimuthList = [ 0, 180, 90, 270 ] for (var i=0; i 2) { + if (geoFenceController.polygonEnabled && geoFenceController.polygon.count() > 2) { for (var i=0; igeoFenceManager(); - connect(geoFenceManager, &GeoFenceManager::fenceSupportedChanged, this, &GeoFenceController::fenceSupportedChanged); - connect(geoFenceManager, &GeoFenceManager::fenceEnabledChanged, this, &GeoFenceController::fenceEnabledChanged); - connect(geoFenceManager, &GeoFenceManager::circleSupportedChanged, this, &GeoFenceController::_setDirty); - connect(geoFenceManager, &GeoFenceManager::polygonSupportedChanged, this, &GeoFenceController::_setDirty); - connect(geoFenceManager, &GeoFenceManager::circleSupportedChanged, this, &GeoFenceController::circleSupportedChanged); - connect(geoFenceManager, &GeoFenceManager::polygonSupportedChanged, this, &GeoFenceController::polygonSupportedChanged); - connect(geoFenceManager, &GeoFenceManager::breachReturnSupportedChanged, this, &GeoFenceController::breachReturnSupportedChanged); - connect(geoFenceManager, &GeoFenceManager::circleRadiusChanged, this, &GeoFenceController::circleRadiusChanged); - connect(geoFenceManager, &GeoFenceManager::paramsChanged, this, &GeoFenceController::paramsChanged); - connect(geoFenceManager, &GeoFenceManager::paramLabelsChanged, this, &GeoFenceController::paramLabelsChanged); - connect(geoFenceManager, &GeoFenceManager::loadComplete, this, &GeoFenceController::_loadComplete); - connect(geoFenceManager, &GeoFenceManager::inProgressChanged, this, &GeoFenceController::syncInProgressChanged); + connect(geoFenceManager, &GeoFenceManager::polygonEnabledChanged, this, &GeoFenceController::_setDirty); + connect(geoFenceManager, &GeoFenceManager::circleEnabledChanged, this, &GeoFenceController::circleEnabledChanged); + connect(geoFenceManager, &GeoFenceManager::polygonEnabledChanged, this, &GeoFenceController::polygonEnabledChanged); + connect(geoFenceManager, &GeoFenceManager::breachReturnEnabledChanged, this, &GeoFenceController::breachReturnEnabledChanged); + connect(geoFenceManager, &GeoFenceManager::circleRadiusChanged, this, &GeoFenceController::circleRadiusChanged); + connect(geoFenceManager, &GeoFenceManager::paramsChanged, this, &GeoFenceController::paramsChanged); + connect(geoFenceManager, &GeoFenceManager::paramLabelsChanged, this, &GeoFenceController::paramLabelsChanged); + connect(geoFenceManager, &GeoFenceManager::loadComplete, this, &GeoFenceController::_loadComplete); + connect(geoFenceManager, &GeoFenceManager::inProgressChanged, this, &GeoFenceController::syncInProgressChanged); if (!geoFenceManager->inProgress()) { _loadComplete(geoFenceManager->breachReturnPoint(), geoFenceManager->polygon()); @@ -136,7 +131,7 @@ bool GeoFenceController::_loadJsonFile(QJsonDocument& jsonDoc, QString& errorStr return false; } - if (breachReturnSupported()) { + if (breachReturnEnabled()) { if (json.contains(_jsonBreachReturnKey) && !JsonHelper::loadGeoCoordinate(json[_jsonBreachReturnKey], false /* altitudeRequired */, _breachReturnPoint, errorString)) { return false; @@ -145,7 +140,7 @@ bool GeoFenceController::_loadJsonFile(QJsonDocument& jsonDoc, QString& errorStr _breachReturnPoint = QGeoCoordinate(); } - if (polygonSupported()) { + if (polygonEnabled()) { if (!_polygon.loadFromJson(json, false /* reauired */, errorString)) { return false; } @@ -289,13 +284,13 @@ void GeoFenceController::saveToFile(const QString& filename) paramMgr->saveToJson(paramMgr->defaultComponentId(), paramNames, fenceFileObject); } - if (breachReturnSupported()) { + if (breachReturnEnabled()) { QJsonValue jsonBreachReturn; JsonHelper::saveGeoCoordinate(_breachReturnPoint, false /* writeAltitude */, jsonBreachReturn); fenceFileObject[_jsonBreachReturnKey] = jsonBreachReturn; } - if (polygonSupported()) { + if (polygonEnabled()) { _polygon.saveToJson(fenceFileObject); } @@ -373,29 +368,19 @@ void GeoFenceController::_polygonDirtyChanged(bool dirty) } } -bool GeoFenceController::fenceSupported(void) const +bool GeoFenceController::circleEnabled(void) const { - return _activeVehicle->geoFenceManager()->fenceSupported(); + return _activeVehicle->geoFenceManager()->circleEnabled(); } -bool GeoFenceController::fenceEnabled(void) const +bool GeoFenceController::polygonEnabled(void) const { - return _activeVehicle->geoFenceManager()->fenceEnabled(); + return _activeVehicle->geoFenceManager()->polygonEnabled(); } -bool GeoFenceController::circleSupported(void) const +bool GeoFenceController::breachReturnEnabled(void) const { - return _activeVehicle->geoFenceManager()->circleSupported(); -} - -bool GeoFenceController::polygonSupported(void) const -{ - return _activeVehicle->geoFenceManager()->polygonSupported(); -} - -bool GeoFenceController::breachReturnSupported(void) const -{ - return _activeVehicle->geoFenceManager()->breachReturnSupported(); + return _activeVehicle->geoFenceManager()->breachReturnEnabled(); } void GeoFenceController::_setDirty(void) diff --git a/src/MissionManager/GeoFenceController.h b/src/MissionManager/GeoFenceController.h index ae5b8c6dc06e5f88e8d8ca2eec9c67b757353e71..34c87bdad6127926b5245c2b5b67a383d5abffa5 100644 --- a/src/MissionManager/GeoFenceController.h +++ b/src/MissionManager/GeoFenceController.h @@ -29,17 +29,26 @@ public: GeoFenceController(QObject* parent = NULL); ~GeoFenceController(); + Q_PROPERTY(bool circleEnabled READ circleEnabled NOTIFY circleEnabledChanged) + Q_PROPERTY(float circleRadius READ circleRadius NOTIFY circleRadiusChanged) + + Q_PROPERTY(bool polygonEnabled READ polygonEnabled NOTIFY polygonEnabledChanged) + Q_PROPERTY(QGCMapPolygon* polygon READ polygon CONSTANT) + + Q_PROPERTY(bool breachReturnEnabled READ breachReturnEnabled NOTIFY breachReturnEnabledChanged) + Q_PROPERTY(QGeoCoordinate breachReturnPoint READ breachReturnPoint WRITE setBreachReturnPoint NOTIFY breachReturnPointChanged) + + Q_PROPERTY(QVariantList params READ params NOTIFY paramsChanged) + Q_PROPERTY(QStringList paramLabels READ paramLabels NOTIFY paramLabelsChanged) + Q_PROPERTY(QString editorQml READ editorQml NOTIFY editorQmlChanged) + +#if 0 Q_PROPERTY(bool fenceSupported READ fenceSupported NOTIFY fenceSupportedChanged) Q_PROPERTY(bool fenceEnabled READ fenceEnabled NOTIFY fenceEnabledChanged) Q_PROPERTY(bool circleSupported READ circleSupported NOTIFY circleSupportedChanged) Q_PROPERTY(bool polygonSupported READ polygonSupported NOTIFY polygonSupportedChanged) Q_PROPERTY(bool breachReturnSupported READ breachReturnSupported NOTIFY breachReturnSupportedChanged) - Q_PROPERTY(float circleRadius READ circleRadius NOTIFY circleRadiusChanged) - Q_PROPERTY(QGCMapPolygon* polygon READ polygon CONSTANT) - Q_PROPERTY(QGeoCoordinate breachReturnPoint READ breachReturnPoint WRITE setBreachReturnPoint NOTIFY breachReturnPointChanged) - Q_PROPERTY(QVariantList params READ params NOTIFY paramsChanged) - Q_PROPERTY(QStringList paramLabels READ paramLabels NOTIFY paramLabelsChanged) - Q_PROPERTY(QString editorQml READ editorQml NOTIFY editorQmlChanged) +#endif void start (bool editMode) final; void loadFromVehicle (void) final; @@ -55,33 +64,29 @@ public: QString fileExtension(void) const final; - bool fenceSupported (void) const; - bool fenceEnabled (void) const; - bool circleSupported (void) const; - bool polygonSupported (void) const; - bool breachReturnSupported (void) const; - float circleRadius (void) const; - QGCMapPolygon* polygon (void) { return &_polygon; } - QGeoCoordinate breachReturnPoint (void) const { return _breachReturnPoint; } - QVariantList params (void) const; - QStringList paramLabels (void) const; - QString editorQml (void) const; + bool circleEnabled (void) const; + bool polygonEnabled (void) const; + bool breachReturnEnabled (void) const; + float circleRadius (void) const; + QGCMapPolygon* polygon (void) { return &_polygon; } + QGeoCoordinate breachReturnPoint (void) const { return _breachReturnPoint; } + QVariantList params (void) const; + QStringList paramLabels (void) const; + QString editorQml (void) const; void setBreachReturnPoint(const QGeoCoordinate& breachReturnPoint); signals: - void fenceSupportedChanged (bool fenceSupported); - void fenceEnabledChanged (bool fenceEnabled); - void circleSupportedChanged (bool circleSupported); - void polygonSupportedChanged (bool polygonSupported); - void breachReturnSupportedChanged (bool breachReturnSupported); - void circleRadiusChanged (float circleRadius); - void polygonPathChanged (const QVariantList& polygonPath); - void breachReturnPointChanged (QGeoCoordinate breachReturnPoint); - void paramsChanged (QVariantList params); - void paramLabelsChanged (QStringList paramLabels); - void editorQmlChanged (QString editorQml); - void loadComplete (void); + void circleEnabledChanged (bool circleEnabled); + void polygonEnabledChanged (bool polygonEnabled); + void breachReturnEnabledChanged (bool breachReturnEnabled); + void circleRadiusChanged (float circleRadius); + void polygonPathChanged (const QVariantList& polygonPath); + void breachReturnPointChanged (QGeoCoordinate breachReturnPoint); + void paramsChanged (QVariantList params); + void paramLabelsChanged (QStringList paramLabels); + void editorQmlChanged (QString editorQml); + void loadComplete (void); private slots: void _polygonDirtyChanged(bool dirty); diff --git a/src/MissionManager/GeoFenceManager.h b/src/MissionManager/GeoFenceManager.h index eb2e8f6b67057529b9a0d1137cfdf6108d1be2cd..c88de86dd6d5bebe1d3a47e972e8ffab5c84ed88 100644 --- a/src/MissionManager/GeoFenceManager.h +++ b/src/MissionManager/GeoFenceManager.h @@ -38,12 +38,9 @@ public: /// Send the current settings to the vehicle virtual void sendToVehicle(const QGeoCoordinate& breachReturn, const QList& polygon); - // Support flags - virtual bool fenceSupported (void) const { return false; } - virtual bool fenceEnabled (void) const { return false; } - virtual bool circleSupported (void) const { return false; } - virtual bool polygonSupported (void) const { return false; } - virtual bool breachReturnSupported (void) const { return false; } + virtual bool circleEnabled (void) const { return false; } + virtual bool polygonEnabled (void) const { return false; } + virtual bool breachReturnEnabled (void) const { return false; } virtual float circleRadius (void) const { return 0.0; } QList polygon (void) const { return _polygon; } @@ -63,17 +60,15 @@ public: } ErrorCode_t; signals: - void loadComplete (const QGeoCoordinate& breachReturn, const QList& polygon); - void fenceSupportedChanged (bool fenceSupported); - void fenceEnabledChanged (bool fenceEnabled); - void circleSupportedChanged (bool circleSupported); - void polygonSupportedChanged (bool polygonSupported); - void breachReturnSupportedChanged (bool fenceSupported); - void circleRadiusChanged (float circleRadius); - void inProgressChanged (bool inProgress); - void error (int errorCode, const QString& errorMsg); - void paramsChanged (QVariantList params); - void paramLabelsChanged (QStringList paramLabels); + void loadComplete (const QGeoCoordinate& breachReturn, const QList& polygon); + void circleEnabledChanged (bool circleEnabled); + void polygonEnabledChanged (bool polygonEnabled); + void breachReturnEnabledChanged (bool fenceEnabled); + void circleRadiusChanged (float circleRadius); + void inProgressChanged (bool inProgress); + void error (int errorCode, const QString& errorMsg); + void paramsChanged (QVariantList params); + void paramLabelsChanged (QStringList paramLabels); protected: void _sendError(ErrorCode_t errorCode, const QString& errorMsg);