mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_Compass: HMC5843: move hardcoded rotation to before call to rotate_field()
That rotation is set for AP_COMPASS_TYPE_HMC5883L, because it's usually the compass from 3DR GPS+Compass kit, which has an arrow pointing the "correct" direction. That rotation should be done before rotate_field() as it represents the "standard" position for the kit. This patch also makes published values consistent with respect to rotation. Before this, raw fields used in calibration were published with a rotation different from the filtered field when _product_id is AP_COMPASS_TYPE_HMC5883L.
This commit is contained in:
parent
ad91a810b3
commit
35cddc7af0
@ -241,6 +241,11 @@ void AP_Compass_HMC5843::accumulate()
|
||||
Vector3f raw_field = Vector3f(_mag_x, _mag_y, _mag_z);
|
||||
raw_field *= _gain_scale;
|
||||
|
||||
// rotate to the desired orientation
|
||||
if (_product_id == AP_COMPASS_TYPE_HMC5883L) {
|
||||
raw_field.rotate(ROTATION_YAW_90);
|
||||
}
|
||||
|
||||
// rotate raw_field from sensor frame to body frame
|
||||
rotate_field(raw_field, _compass_instance);
|
||||
|
||||
@ -293,12 +298,6 @@ void AP_Compass_HMC5843::read()
|
||||
_accum_count = 0;
|
||||
_mag_x_accum = _mag_y_accum = _mag_z_accum = 0;
|
||||
|
||||
// rotate to the desired orientation
|
||||
// FIXME: wrong way to rotate compass
|
||||
if (_product_id == AP_COMPASS_TYPE_HMC5883L) {
|
||||
field.rotate(ROTATION_YAW_90);
|
||||
}
|
||||
|
||||
publish_filtered_field(field, _compass_instance);
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user