From 7202aa00da1adee1c4b8ead56fa72afb99e4eb2f Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 16 Aug 2014 10:45:11 +0900 Subject: [PATCH] Copter: remove compass learn of offsets This saves 1k of flash and the interference on most copters makes this option unusable anyway. --- ArduCopter/ArduCopter.pde | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 3cd6fd9907..298fe7880c 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1087,9 +1087,7 @@ static void update_batt_compass(void) if(g.compass_enabled) { // update compass with throttle value - used for compassmot compass.set_throttle((float)g.rc_3.servo_out/1000.0f); - if (compass.read()) { - compass.learn_offsets(); - } + compass.read(); // log compass information if (g.log_bitmask & MASK_LOG_COMPASS) { Log_Write_Compass();