mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_Declination: disable library when AUTOMATIC_DECLINATION is not ENABLED
unfortunately this library was causing avrdude to fail to load the hex to my APM2. Until we work out why, it's disabled.
This commit is contained in:
parent
42a29169f0
commit
1e47ab26f2
@ -66,7 +66,6 @@ http://code.google.com/p/ardupilot-mega/downloads/list
|
||||
#include <AP_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
|
||||
#include <AP_AnalogSource.h>
|
||||
#include <AP_Baro.h>
|
||||
#include <AP_Declination.h> // ArduPilot Mega Declination Helper Library
|
||||
#include <AP_Compass.h> // ArduPilot Mega Magnetometer Library
|
||||
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||
#include <AP_InertialSensor.h> // ArduPilot Mega Inertial Sensor (accel & gyro) Library
|
||||
@ -97,6 +96,11 @@ 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
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
@ -1375,17 +1379,12 @@ static void update_GPS(void)
|
||||
ground_start_count = 5;
|
||||
|
||||
}else{
|
||||
// If we have a compass installed
|
||||
if(g.compass_enabled)
|
||||
{
|
||||
#if AUTOMATIC_DECLINATION == ENABLED
|
||||
if(g.compass_enabled) {
|
||||
// Set compass declination automatically
|
||||
if(compass.set_initial_location(g_gps->latitude, g_gps->longitude, AUTOMATIC_DECLINATION == ENABLED))
|
||||
{
|
||||
// Report if an update was made
|
||||
report_compass();
|
||||
}
|
||||
compass.set_initial_location(g_gps->latitude, g_gps->longitude, false);
|
||||
}
|
||||
|
||||
#endif
|
||||
// save home to eeprom (we must have a good fix to have reached this point)
|
||||
init_home();
|
||||
ground_start_count = 0;
|
||||
|
@ -36,7 +36,6 @@ version 2.1 of the License, or (at your option) any later version.
|
||||
#include <AP_AnalogSource.h>// ArduPilot Mega polymorphic analog getter
|
||||
#include <AP_PeriodicProcess.h> // ArduPilot Mega TimerProcess
|
||||
#include <AP_Baro.h> // ArduPilot barometer library
|
||||
#include <AP_Declination.h> // ArduPilot Mega Declination Helper Library
|
||||
#include <AP_Compass.h> // ArduPilot Mega Magnetometer Library
|
||||
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||
#include <AP_InertialSensor.h> // Inertial Sensor (uncalibated IMU) Library
|
||||
@ -61,6 +60,11 @@ version 2.1 of the License, or (at your option) any later version.
|
||||
#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
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
@ -975,17 +979,12 @@ static void update_GPS(void)
|
||||
init_home();
|
||||
}
|
||||
|
||||
// If we have a compass installed
|
||||
if(g.compass_enabled)
|
||||
{
|
||||
#if AUTOMATIC_DECLINATION == ENABLED
|
||||
if (g.compass_enabled) {
|
||||
// Set compass declination automatically
|
||||
if(compass.set_initial_location(g_gps->latitude, g_gps->longitude, AUTOMATIC_DECLINATION == ENABLED))
|
||||
{
|
||||
// Report if an update was made
|
||||
report_compass();
|
||||
}
|
||||
compass.set_initial_location(g_gps->latitude, g_gps->longitude, false);
|
||||
}
|
||||
|
||||
#endif
|
||||
ground_start_count = 0;
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user