mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: removed disco special compass offsets
not needed any more with newer hardware
This commit is contained in:
parent
9b8b45b218
commit
f82827ce79
|
@ -258,18 +258,6 @@ 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);
|
||||
|
||||
|
|
Loading…
Reference in New Issue