diff --git a/QGCExternalLibs.pri b/QGCExternalLibs.pri
index 034dbfdc083c45cee4e469843ed44a2396985b5c..2aafbf5d5fcae9cea48626d259b8f159e45f4e93 100644
--- a/QGCExternalLibs.pri
+++ b/QGCExternalLibs.pri
@@ -53,6 +53,9 @@ isEmpty(MAVLINK_CONF) {
 contains (CONFIG, QGC_DISABLE_APM_MAVLINK) {
     message("Disable APM MAVLink support")
     DEFINES += NO_ARDUPILOT_DIALECT
+    CONFIG  += ArdupilotDisabled
+} else {
+    CONFIG  += ArdupilotEnabled
 }
 
 # First we select the dialect, checking for valid user selection
diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro
index 6e79009583e3f314c0f2318eee03d661422e4686..96ce62994814572e367e03455a68adcddc23ba08 100644
--- a/qgroundcontrol.pro
+++ b/qgroundcontrol.pro
@@ -596,7 +596,6 @@ HEADERS += \
     src/QmlControls/RCChannelMonitorController.h \
     src/QmlControls/ScreenToolsController.h \
     src/QtLocationPlugin/QMLControl/QGCMapEngineManager.h \
-    src/Settings/APMMavlinkStreamRateSettings.h \
     src/Settings/AppSettings.h \
     src/Settings/AutoConnectSettings.h \
     src/Settings/BrandImageSettings.h \
@@ -800,7 +799,6 @@ SOURCES += \
     src/QmlControls/RCChannelMonitorController.cc \
     src/QmlControls/ScreenToolsController.cc \
     src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc \
-    src/Settings/APMMavlinkStreamRateSettings.cc \
     src/Settings/AppSettings.cc \
     src/Settings/AutoConnectSettings.cc \
     src/Settings/BrandImageSettings.cc \
@@ -963,6 +961,16 @@ SOURCES += \
         src/VehicleSetup/PX4FirmwareUpgradeThread.cc \
 }}
 
+# ArduPilot Specific
+
+ArdupilotEnabled {
+    HEADERS += \
+        src/Settings/APMMavlinkStreamRateSettings.h \
+
+    SOURCES += \
+        src/Settings/APMMavlinkStreamRateSettings.cc \
+}
+
 # ArduPilot FirmwarePlugin
 
 APMFirmwarePlugin {
diff --git a/src/Settings/SettingsManager.cc b/src/Settings/SettingsManager.cc
index 70a44ecc5bf34b08ab999116b71f509146497ef4..8bb7bf94ddc15343f5addc9686294d6f1d67734e 100644
--- a/src/Settings/SettingsManager.cc
+++ b/src/Settings/SettingsManager.cc
@@ -26,7 +26,9 @@ SettingsManager::SettingsManager(QGCApplication* app, QGCToolbox* toolbox)
     , _flyViewSettings              (nullptr)
     , _planViewSettings             (nullptr)
     , _brandImageSettings           (nullptr)
+#if !defined(NO_ARDUPILOT_DIALECT)
     , _apmMavlinkStreamRateSettings (nullptr)
+#endif
 {
 
 }
@@ -46,7 +48,9 @@ void SettingsManager::setToolbox(QGCToolbox *toolbox)
     _flyViewSettings =              new FlyViewSettings     (this);
     _planViewSettings =             new PlanViewSettings    (this);
     _brandImageSettings =           new BrandImageSettings  (this);
+#if !defined(NO_ARDUPILOT_DIALECT)
     _apmMavlinkStreamRateSettings = new APMMavlinkStreamRateSettings     (this);
+#endif
 #if defined(QGC_AIRMAP_ENABLED)
     _airMapSettings =               new AirMapSettings      (this);
 #endif
diff --git a/src/Settings/SettingsManager.h b/src/Settings/SettingsManager.h
index 47d63b3ef9aa9479d56c14e00c0a7ee04c1de84a..c0dd63c4fd562ef51b0859fa8542c65ca4d2ba30 100644
--- a/src/Settings/SettingsManager.h
+++ b/src/Settings/SettingsManager.h
@@ -49,8 +49,9 @@ public:
     Q_PROPERTY(QObject* flyViewSettings                 READ flyViewSettings                CONSTANT)
     Q_PROPERTY(QObject* planViewSettings                READ planViewSettings               CONSTANT)
     Q_PROPERTY(QObject* brandImageSettings              READ brandImageSettings             CONSTANT)
+#if !defined(NO_ARDUPILOT_DIALECT)
     Q_PROPERTY(QObject* apmMavlinkStreamRateSettings    READ apmMavlinkStreamRateSettings   CONSTANT)
-
+#endif
     // Override from QGCTool
     virtual void setToolbox(QGCToolbox *toolbox);
 
@@ -66,8 +67,9 @@ public:
     FlyViewSettings*                flyViewSettings             (void) { return _flyViewSettings; }
     PlanViewSettings*               planViewSettings            (void) { return _planViewSettings; }
     BrandImageSettings*             brandImageSettings          (void) { return _brandImageSettings; }
+#if !defined(NO_ARDUPILOT_DIALECT)
     APMMavlinkStreamRateSettings*   apmMavlinkStreamRateSettings(void) { return _apmMavlinkStreamRateSettings; }
-
+#endif
 private:
 #if defined(QGC_AIRMAP_ENABLED)
     AirMapSettings*         _airMapSettings;
@@ -81,7 +83,9 @@ private:
     FlyViewSettings*                _flyViewSettings;
     PlanViewSettings*               _planViewSettings;
     BrandImageSettings*             _brandImageSettings;
+#if !defined(NO_ARDUPILOT_DIALECT)
     APMMavlinkStreamRateSettings*   _apmMavlinkStreamRateSettings;
+#endif
 };
 
 #endif