mirror of https://github.com/ArduPilot/ardupilot
AP_Declination: Added call to compass.set_initial_location if the compass is enabled when the 3D fix is obtained.
Signed-off-by: Andrew Tridgell <tridge@samba.org>
This commit is contained in:
parent
566bbed7ad
commit
2e1cacd67f
|
@ -35,6 +35,7 @@ Jean-Louis Naudin :Auto Landing
|
||||||
Sandro Benigno :Camera support
|
Sandro Benigno :Camera support
|
||||||
Olivier Adler :PPM Encoder
|
Olivier Adler :PPM Encoder
|
||||||
John Arne Birkeland :PPM Encoder
|
John Arne Birkeland :PPM Encoder
|
||||||
|
Adam M Rivera :Auto Compass Declination
|
||||||
|
|
||||||
And much more so PLEASE PM me on DIYDRONES to add your contribution to the List
|
And much more so PLEASE PM me on DIYDRONES to add your contribution to the List
|
||||||
|
|
||||||
|
@ -65,6 +66,7 @@ http://code.google.com/p/ardupilot-mega/downloads/list
|
||||||
#include <AP_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
|
#include <AP_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
|
||||||
#include <AP_AnalogSource.h>
|
#include <AP_AnalogSource.h>
|
||||||
#include <AP_Baro.h>
|
#include <AP_Baro.h>
|
||||||
|
#include <AP_Declination.h> // ArduPilot Mega Declination Helper Library
|
||||||
#include <AP_Compass.h> // ArduPilot Mega Magnetometer Library
|
#include <AP_Compass.h> // ArduPilot Mega Magnetometer Library
|
||||||
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||||
#include <AP_InertialSensor.h> // ArduPilot Mega Inertial Sensor (accel & gyro) Library
|
#include <AP_InertialSensor.h> // ArduPilot Mega Inertial Sensor (accel & gyro) Library
|
||||||
|
@ -238,7 +240,6 @@ static GPS *g_gps_null;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
AP_TimerProcess timer_scheduler;
|
AP_TimerProcess timer_scheduler;
|
||||||
|
|
||||||
#elif HIL_MODE == HIL_MODE_SENSORS
|
#elif HIL_MODE == HIL_MODE_SENSORS
|
||||||
// sensor emulators
|
// sensor emulators
|
||||||
AP_ADC_HIL adc;
|
AP_ADC_HIL adc;
|
||||||
|
@ -1374,6 +1375,17 @@ static void update_GPS(void)
|
||||||
ground_start_count = 5;
|
ground_start_count = 5;
|
||||||
|
|
||||||
}else{
|
}else{
|
||||||
|
// If we have a compass installed
|
||||||
|
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();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// save home to eeprom (we must have a good fix to have reached this point)
|
// save home to eeprom (we must have a good fix to have reached this point)
|
||||||
init_home();
|
init_home();
|
||||||
ground_start_count = 0;
|
ground_start_count = 0;
|
||||||
|
@ -1391,7 +1403,6 @@ static void update_GPS(void)
|
||||||
//update_altitude();
|
//update_altitude();
|
||||||
alt_sensor_flag = true;
|
alt_sensor_flag = true;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -36,6 +36,7 @@ version 2.1 of the License, or (at your option) any later version.
|
||||||
#include <AP_AnalogSource.h>// ArduPilot Mega polymorphic analog getter
|
#include <AP_AnalogSource.h>// ArduPilot Mega polymorphic analog getter
|
||||||
#include <AP_PeriodicProcess.h> // ArduPilot Mega TimerProcess
|
#include <AP_PeriodicProcess.h> // ArduPilot Mega TimerProcess
|
||||||
#include <AP_Baro.h> // ArduPilot barometer library
|
#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_Compass.h> // ArduPilot Mega Magnetometer Library
|
||||||
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||||
#include <AP_InertialSensor.h> // Inertial Sensor (uncalibated IMU) Library
|
#include <AP_InertialSensor.h> // Inertial Sensor (uncalibated IMU) Library
|
||||||
|
@ -974,6 +975,17 @@ static void update_GPS(void)
|
||||||
init_home();
|
init_home();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// If we have a compass installed
|
||||||
|
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();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
ground_start_count = 0;
|
ground_start_count = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue