Unverified Commit 9c6b1ea7 authored by Gus Grubba's avatar Gus Grubba Committed by GitHub

Merge pull request #7259 from mavlink/excludeArduPilot

Exclude ArduPilot code when not used
parents 3e04eab0 4f05bdeb
......@@ -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
......
......@@ -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 {
......
......@@ -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
......
......@@ -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
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