mirror of https://github.com/ArduPilot/ardupilot
ACM: removed FORCE_AUTOMATIC_DECLINATION_UPDATE
we now have the EEPROM option COMPASS_AUTODEC instead
This commit is contained in:
parent
504c53f746
commit
0bc604f030
|
@ -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();
|
||||
|
|
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue