mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-31 04:58:30 -04:00
AP_Compass: fixed raw_field init in AK8963 driver
thanks to Peter for spotting this
This commit is contained in:
parent
5710697847
commit
079161ef3a
@ -240,7 +240,7 @@ void AP_Compass_AK8963::_update()
|
||||
struct AP_AK8963_SerialBus::raw_value rv;
|
||||
float mag_x, mag_y, mag_z;
|
||||
// get raw_field - sensor frame, uncorrected
|
||||
Vector3f raw_field = Vector3f(mag_x, mag_y, mag_z);
|
||||
Vector3f raw_field;
|
||||
uint32_t time_us = hal.scheduler->micros();
|
||||
|
||||
|
||||
@ -268,6 +268,8 @@ void AP_Compass_AK8963::_update()
|
||||
goto fail;
|
||||
}
|
||||
|
||||
raw_field = Vector3f(mag_x, mag_y, mag_z);
|
||||
|
||||
// rotate raw_field from sensor frame to body frame
|
||||
rotate_field(raw_field, _compass_instance);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user