AP_Compass: LEARN param default to 0 for all vehicles

This commit is contained in:
Randy Mackay 2019-10-23 12:23:41 +09:00 committed by Andrew Tridgell
parent 8d058d58be
commit 01c36fa6aa

View File

@ -30,10 +30,8 @@
extern const AP_HAL::HAL& hal;
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
#ifndef COMPASS_LEARN_DEFAULT
#define COMPASS_LEARN_DEFAULT Compass::LEARN_NONE
#else
#define COMPASS_LEARN_DEFAULT Compass::LEARN_INTERNAL
#endif
#ifndef AP_COMPASS_OFFSETS_MAX_DEFAULT