Browse Source

ArduCopter: Changed implementation of configuration value for automatic declination. There is now a FORCE_AUTOMATIC_DECLINATION_UPDATE that when enabled will update the declination on every GPS 3D fix regardless of whether or not the user saved a value to the EEPROM. By default the declination will only be set by the automatic declination routine if the user has not saved a declination to the EEPROM.

master
Adam M Rivera 13 years ago committed by Andrew Tridgell
parent
commit
51b70e4d36
  1. 7
      ArduCopter/ArduCopter.pde
  2. 4
      ArduCopter/config.h

7
ArduCopter/ArduCopter.pde

@ -95,10 +95,7 @@ http://code.google.com/p/ardupilot-mega/downloads/list @@ -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 <AP_Declination.h> // ArduPilot Mega Declination Helper Library
#endif
////////////////////////////////////////////////////////////////////////////////
// Serial ports
@ -1381,12 +1378,10 @@ static void update_GPS(void) @@ -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;

4
ArduCopter/config.h

@ -425,8 +425,8 @@ @@ -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

Loading…
Cancel
Save