diff --git a/src/FirmwarePlugin/APM/APMGeoFenceManager.cc b/src/FirmwarePlugin/APM/APMGeoFenceManager.cc
index 7b019f7..0590c11 100644
--- a/src/FirmwarePlugin/APM/APMGeoFenceManager.cc
+++ b/src/FirmwarePlugin/APM/APMGeoFenceManager.cc
@@ -22,11 +22,12 @@ APMGeoFenceManager::APMGeoFenceManager(Vehicle* vehicle)
     : GeoFenceManager(vehicle)
     , _fenceSupported(false)
     , _breachReturnSupported(vehicle->fixedWing())
+    , _circleSupported(false)
+    , _polygonSupported(false)
     , _firstParamLoadComplete(false)
     , _circleRadiusFact(NULL)
     , _readTransactionInProgress(false)
     , _writeTransactionInProgress(false)
-    , _fenceEnableFact(NULL)
     , _fenceTypeFact(NULL)
 {
     connect(_vehicle,                       &Vehicle::mavlinkMessageReceived,           this, &APMGeoFenceManager::_mavlinkMessageReceived);
@@ -80,7 +81,7 @@ void APMGeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn, const
     fenceEnableFact->setRawValue(0);
 
     // Total point count, +1 polygon close in last index, +1 for breach in index 0
-    _cWriteFencePoints = (validatedPolygonCount ? (validatedPolygonCount + 1) : 0) + 1 ;
+    _cWriteFencePoints = validatedPolygonCount ? validatedPolygonCount + 1 + 1 : 0;
     _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _fenceTotalParam)->setRawValue(_cWriteFencePoints);
 
     // FIXME: No validation of correct fence received
@@ -106,11 +107,11 @@ void APMGeoFenceManager::loadFromVehicle(void)
         return;
     }
 
-    // Point 0: Breach return point (ArduPlane only)
+    // Point 0: Breach return point (always sent, but supported by ArduPlane only)
     // Point [1,N]: Polygon points
     // Point N+1: Close polygon point (same as point 1)
     int cFencePoints = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _fenceTotalParam)->rawValue().toInt();
-    int minFencePoints = 6;
+    int minFencePoints = 5;
     qCDebug(GeoFenceManagerLog) << "APMGeoFenceManager::loadFromVehicle" << cFencePoints;
     if (cFencePoints == 0) {
         // No fence
@@ -242,8 +243,19 @@ bool APMGeoFenceManager::_geoFenceSupported(void)
 
 void APMGeoFenceManager::_updateSupportedFlags(void)
 {
-    emit circleSupportedChanged(circleSupported());
-    emit polygonSupportedChanged(polygonSupported());
+    bool newCircleSupported = _fenceSupported && _vehicle->multiRotor() && _fenceTypeFact && (_fenceTypeFact->rawValue().toInt() & 2);
+    if (newCircleSupported != _circleSupported) {
+        _circleSupported = newCircleSupported;
+        emit circleSupportedChanged(newCircleSupported);
+    }
+
+    bool newPolygonSupported = _fenceSupported &&
+            ((_vehicle->multiRotor() && _fenceTypeFact && (_fenceTypeFact->rawValue().toInt() & 4)) ||
+             _vehicle->fixedWing());
+    if (newPolygonSupported != _polygonSupported) {
+        _polygonSupported = newPolygonSupported;
+        emit polygonSupportedChanged(newPolygonSupported);
+    }
 }
 
 void APMGeoFenceManager::_parametersReady(void)
@@ -258,11 +270,9 @@ void APMGeoFenceManager::_parametersReady(void)
             QStringList paramLabels;
 
             if (_vehicle->multiRotor()) {
-                _fenceEnableFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("FENCE_ENABLE"));
                 _fenceTypeFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("FENCE_TYPE"));
 
-                connect(_fenceEnableFact,   &Fact::rawValueChanged, this, &APMGeoFenceManager::_updateSupportedFlags);
-                connect(_fenceTypeFact,     &Fact::rawValueChanged, this, &APMGeoFenceManager::_updateSupportedFlags);
+                connect(_fenceTypeFact, &Fact::rawValueChanged, this, &APMGeoFenceManager::_updateSupportedFlags);
 
                 _circleRadiusFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("FENCE_RADIUS"));
                 connect(_circleRadiusFact, &Fact::rawValueChanged, this, &APMGeoFenceManager::_circleRadiusRawValueChanged);
@@ -293,8 +303,7 @@ void APMGeoFenceManager::_parametersReady(void)
             emit paramLabelsChanged(_paramLabels);
 
             emit fenceSupportedChanged(_fenceSupported);
-            emit circleSupportedChanged(circleSupported());
-            emit polygonSupportedChanged(polygonSupported());
+            _updateSupportedFlags();
         }
 
         qCDebug(GeoFenceManagerLog) << "fenceSupported:circleSupported:polygonSupported:breachReturnSupported" <<
@@ -318,26 +327,12 @@ void APMGeoFenceManager::_circleRadiusRawValueChanged(QVariant value)
 
 bool APMGeoFenceManager::circleSupported(void) const
 {
-    if (_fenceSupported && _vehicle->multiRotor() && _fenceEnableFact && _fenceTypeFact) {
-        return _fenceEnableFact->rawValue().toBool() && (_fenceTypeFact->rawValue().toInt() & 2);
-    }
-
-    return false;
+    return _circleSupported;
 }
 
 bool APMGeoFenceManager::polygonSupported(void) const
 {
-    if (_fenceSupported) {
-        if (_vehicle->multiRotor()) {
-            if (_fenceEnableFact && _fenceTypeFact) {
-                return _fenceEnableFact->rawValue().toBool() && (_fenceTypeFact->rawValue().toInt() & 4);
-            }
-        } else if (_vehicle->fixedWing()) {
-            return true;
-        }
-    }
-
-    return false;
+    return _polygonSupported;
 }
 
 QString APMGeoFenceManager::editorQml(void) const
diff --git a/src/FirmwarePlugin/APM/APMGeoFenceManager.h b/src/FirmwarePlugin/APM/APMGeoFenceManager.h
index fe98aae..33fe159 100644
--- a/src/FirmwarePlugin/APM/APMGeoFenceManager.h
+++ b/src/FirmwarePlugin/APM/APMGeoFenceManager.h
@@ -49,6 +49,8 @@ private:
 private:
     bool _fenceSupported;
     bool _breachReturnSupported;
+    bool _circleSupported;
+    bool _polygonSupported;
     bool _firstParamLoadComplete;
 
     QVariantList    _params;
@@ -63,7 +65,6 @@ private:
     uint8_t _cWriteFencePoints;
     uint8_t _currentFencePoint;
 
-    Fact* _fenceEnableFact;
     Fact* _fenceTypeFact;
 
     static const char* _fenceTotalParam;