mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Compass: HMC5843: apply HMC5883L "arrow" rotation only if external
That rotation is done because of the "arrow" pointing the sensor direction in 3DR GPS+Compass kit (which isn't natural to the sensor orientation, by the way). Thus, do that rotation only for external HMC5883L compasses.
This commit is contained in:
parent
35cddc7af0
commit
91246ad8af
@ -242,7 +242,8 @@ void AP_Compass_HMC5843::accumulate()
|
|||||||
raw_field *= _gain_scale;
|
raw_field *= _gain_scale;
|
||||||
|
|
||||||
// rotate to the desired orientation
|
// rotate to the desired orientation
|
||||||
if (_product_id == AP_COMPASS_TYPE_HMC5883L) {
|
if (is_external(_compass_instance) &&
|
||||||
|
_product_id == AP_COMPASS_TYPE_HMC5883L) {
|
||||||
raw_field.rotate(ROTATION_YAW_90);
|
raw_field.rotate(ROTATION_YAW_90);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user