AP_Compass: Set default learn parameter to disabled for Sub

This commit is contained in:
Jacob Walser 2016-12-09 18:15:12 -05:00 committed by Andrew Tridgell
parent 48d5bf7cff
commit 7121910fa7

View File

@ -21,7 +21,7 @@
extern AP_HAL::HAL& hal;
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
#define COMPASS_LEARN_DEFAULT Compass::LEARN_NONE
#else
#define COMPASS_LEARN_DEFAULT Compass::LEARN_INTERNAL