AP_Compass: AK8963: fix where to apply sensitivity adjustments
The function rotate_field() can change the values axes and the function correct_field() applies offsets (which are already in milligauss). Thus any sensitivity adjustment must be done for two reasons: (1) The offsets must be applied to the values already in milligauss; (2) The factory sensitivity adjustment values are per axis, if any rotation that switches axes is applied, that'll mess with the adjustment. Experiments showed that before this patch the length of the mag field reported quite different from the expected. After this patch, the same experiments showed reasonable values.
This commit is contained in:
parent
6198e81bb3
commit
b603641d7c
@ -211,9 +211,6 @@ void AP_Compass_AK8963::read()
|
|||||||
|
|
||||||
_reset_filter();
|
_reset_filter();
|
||||||
hal.scheduler->resume_timer_procs();
|
hal.scheduler->resume_timer_procs();
|
||||||
_make_factory_sensitivity_adjustment(field);
|
|
||||||
_make_adc_sensitivity_adjustment(field);
|
|
||||||
|
|
||||||
publish_filtered_field(field, _compass_instance);
|
publish_filtered_field(field, _compass_instance);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -279,6 +276,9 @@ void AP_Compass_AK8963::_update()
|
|||||||
}
|
}
|
||||||
|
|
||||||
raw_field = Vector3f(mag_x, mag_y, mag_z);
|
raw_field = Vector3f(mag_x, mag_y, mag_z);
|
||||||
|
|
||||||
|
_make_factory_sensitivity_adjustment(raw_field);
|
||||||
|
_make_adc_sensitivity_adjustment(raw_field);
|
||||||
raw_field *= AK8963_MILLIGAUSS_SCALE;
|
raw_field *= AK8963_MILLIGAUSS_SCALE;
|
||||||
|
|
||||||
// rotate raw_field from sensor frame to body frame
|
// rotate raw_field from sensor frame to body frame
|
||||||
|
Loading…
Reference in New Issue
Block a user