mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AP_Compass: convert AK8963 measurements to uT
AK8963 is configured in 16-bit ADC mode which implies sensitivity of 0.15 uT/LSb. Knowing this fact we can convert the measurements to the proper units. The change will make users recalibrate their compasses.
This commit is contained in:
parent
c207d8c6a8
commit
693613aa0f
@ -204,9 +204,11 @@ void AP_Compass_AK8963::read()
|
||||
|
||||
hal.scheduler->suspend_timer_procs();
|
||||
auto field = _get_filtered_field();
|
||||
|
||||
_reset_filter();
|
||||
hal.scheduler->resume_timer_procs();
|
||||
_make_factory_sensitivity_adjustment(field);
|
||||
_make_adc_sensitivity_adjustment(field);
|
||||
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
||||
field.rotate(ROTATION_YAW_90);
|
||||
@ -234,6 +236,13 @@ void AP_Compass_AK8963::_reset_filter()
|
||||
_accum_count = 0;
|
||||
}
|
||||
|
||||
void AP_Compass_AK8963::_make_adc_sensitivity_adjustment(Vector3f& field) const
|
||||
{
|
||||
static const float ADC_16BIT_RESOLUTION = 0.15f;
|
||||
|
||||
field *= ADC_16BIT_RESOLUTION;
|
||||
}
|
||||
|
||||
void AP_Compass_AK8963::_make_factory_sensitivity_adjustment(Vector3f& field) const
|
||||
{
|
||||
field.x *= _magnetometer_ASA[0];
|
||||
|
@ -52,6 +52,7 @@ private:
|
||||
static AP_Compass_Backend *_detect(Compass &compass, AP_AK8963_SerialBus *bus);
|
||||
|
||||
void _make_factory_sensitivity_adjustment(Vector3f& field) const;
|
||||
void _make_adc_sensitivity_adjustment(Vector3f& field) const;
|
||||
Vector3f _get_filtered_field() const;
|
||||
void _reset_filter();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user