diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 81fe37123d..8f2784572e 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1378,9 +1378,9 @@ static void update_GPS(void) ground_start_count = 5; }else{ - if(g.compass_enabled) { + if (g.compass_enabled) { // Set compass declination automatically - compass.set_initial_location(g_gps->latitude, g_gps->longitude, (FORCE_AUTOMATIC_DECLINATION_UPDATE == ENABLED)); + compass.set_initial_location(g_gps->latitude, g_gps->longitude); } // save home to eeprom (we must have a good fix to have reached this point) init_home(); diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 04c84a1011..6670088ba3 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -425,11 +425,6 @@ # define GROUND_START_DELAY 3 #endif -#ifndef FORCE_AUTOMATIC_DECLINATION_UPDATE - #define FORCE_AUTOMATIC_DECLINATION_UPDATE DISABLED -#endif - - ////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////// // FLIGHT AND NAVIGATION CONTROL