AP_InertialSensor: fixed the error value for BMI088

the bad value is -32768 not 0xffff (which is -1)

-32768 badly corrupts the low-pass filter, and is what we see in logs
(a large negative spike on all 3 axes)

update to bug fix from:
https://github.com/ArduPilot/ardupilot/pull/23033
This commit is contained in:
Andrew Tridgell 2023-10-04 19:56:26 +11:00
parent 26b6a1b7b8
commit 799ccb32e2
1 changed files with 1 additions and 1 deletions

View File

@ -400,7 +400,7 @@ void AP_InertialSensor_BMI088::read_fifo_gyro(void)
} }
const float scale = radians(2000.0f) / 32767.0f; const float scale = radians(2000.0f) / 32767.0f;
const uint8_t max_frames = 8; const uint8_t max_frames = 8;
const Vector3i bad_frame{int16_t(0xffff), int16_t(0xffff), int16_t(0xffff)}; const Vector3i bad_frame{INT16_MIN,INT16_MIN,INT16_MIN};
Vector3i data[max_frames]; Vector3i data[max_frames];
if (num_frames & 0x80) { if (num_frames & 0x80) {