mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: Don't use geomag data when user specifies declination
This commit is contained in:
parent
211fdde755
commit
c04b31d9c0
|
@ -609,7 +609,7 @@ void NavEKF3_core::readGpsData()
|
|||
|
||||
if (gpsGoodToAlign && !have_table_earth_field) {
|
||||
const Compass *compass = _ahrs->get_compass();
|
||||
if (compass && compass->have_scale_factor(magSelectIndex)) {
|
||||
if (compass && compass->have_scale_factor(magSelectIndex) && compass->auto_declination_enabled()) {
|
||||
table_earth_field_ga = AP_Declination::get_earth_field_ga(gpsloc);
|
||||
table_declination = radians(AP_Declination::get_declination(gpsloc.lat*1.0e-7,
|
||||
gpsloc.lng*1.0e-7));
|
||||
|
|
Loading…
Reference in New Issue