diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index b0fc2449cf..81fe37123d 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -95,10 +95,7 @@ http://code.google.com/p/ardupilot-mega/downloads/list #include "Parameters.h" #include "GCS.h" -#if AUTOMATIC_DECLINATION == ENABLED -// this is in an #if to avoid the static data #include // ArduPilot Mega Declination Helper Library -#endif //////////////////////////////////////////////////////////////////////////////// // Serial ports @@ -1381,12 +1378,10 @@ static void update_GPS(void) ground_start_count = 5; }else{ -#if AUTOMATIC_DECLINATION == ENABLED if(g.compass_enabled) { // Set compass declination automatically - compass.set_initial_location(g_gps->latitude, g_gps->longitude, false); + compass.set_initial_location(g_gps->latitude, g_gps->longitude, (FORCE_AUTOMATIC_DECLINATION_UPDATE == ENABLED)); } -#endif // save home to eeprom (we must have a good fix to have reached this point) init_home(); ground_start_count = 0; diff --git a/ArduCopter/config.h b/ArduCopter/config.h index c9c08e178e..04c84a1011 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -425,8 +425,8 @@ # define GROUND_START_DELAY 3 #endif -#ifndef AUTOMATIC_DECLINATION - #define AUTOMATIC_DECLINATION DISABLED +#ifndef FORCE_AUTOMATIC_DECLINATION_UPDATE + #define FORCE_AUTOMATIC_DECLINATION_UPDATE DISABLED #endif