From 01c36fa6aa29bf58a7a6bab518c12770a59cf5fb Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 23 Oct 2019 12:23:41 +0900 Subject: [PATCH] AP_Compass: LEARN param default to 0 for all vehicles --- libraries/AP_Compass/AP_Compass.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/libraries/AP_Compass/AP_Compass.cpp b/libraries/AP_Compass/AP_Compass.cpp index e8e66082d5..58f90afe35 100644 --- a/libraries/AP_Compass/AP_Compass.cpp +++ b/libraries/AP_Compass/AP_Compass.cpp @@ -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