AP_Compass: work around poor magnetic setup on Disco

bring compass offsets into line with what the calibrator can handle
This commit is contained in:
Andrew Tridgell 2016-06-16 12:43:45 +10:00
parent 39dac57b56
commit 018d8f732a

View File

@ -258,6 +258,18 @@ void AP_Compass_AK8963::_update()
// rotate raw_field from sensor frame to body frame
rotate_field(raw_field, _compass_instance);
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
/*
the disco has a very challenging magnetic environment around the
AK8975. The offsets are very large, and prevent calibration
completing even with a large fitness. The following brings the
values to within range of what the on-board calibrator can
handle
*/
raw_field.x -= 350;
raw_field.z -= 1800;
#endif
// publish raw_field (uncorrected point sample) for calibration use
publish_raw_field(raw_field, time_us, _compass_instance);