diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index 1c766e182f..ee4f024ed2 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -90,3 +90,5 @@ // #define MOT_7 CH_7 // #define MOT_8 CH_8 +// Enabling this will use the GPS lat/long coordinate to get the compass declination +//#define AUTOMATIC_DECLINATION ENABLED \ No newline at end of file diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 4813348168..31b7463b60 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -425,6 +425,10 @@ # define GROUND_START_DELAY 3 #endif +#ifndef AUTOMATIC_DECLINATION + #define AUTOMATIC_DECLINATION DISABLED +#endif + ////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////// diff --git a/ArduPlane/APM_Config.h b/ArduPlane/APM_Config.h index 0b40f0e887..146dead877 100644 --- a/ArduPlane/APM_Config.h +++ b/ArduPlane/APM_Config.h @@ -39,3 +39,6 @@ #define AIRSPEED_CRUISE 25 #define THROTTLE_FAILSAFE ENABLED */ + +// Enabling this will use the GPS lat/long coordinate to get the compass declination +//#define AUTOMATIC_DECLINATION ENABLED diff --git a/ArduPlane/config.h b/ArduPlane/config.h index 43141cdce6..490fdb0631 100644 --- a/ArduPlane/config.h +++ b/ArduPlane/config.h @@ -418,6 +418,9 @@ # define GROUND_START_DELAY 0 #endif +#ifndef AUTOMATIC_DECLINATION + #define AUTOMATIC_DECLINATION DISABLED +#endif ////////////////////////////////////////////////////////////////////////////// // ENABLE_AIR_START