From 799ccb32e2e06a82e8231106ab218f5d048af457 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 4 Oct 2023 19:56:26 +1100 Subject: [PATCH] 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 --- libraries/AP_InertialSensor/AP_InertialSensor_BMI088.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.cpp index dcbbf22046..aa839b6b4e 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.cpp @@ -400,7 +400,7 @@ void AP_InertialSensor_BMI088::read_fifo_gyro(void) } const float scale = radians(2000.0f) / 32767.0f; 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]; if (num_frames & 0x80) {