From a0fe53414c99d99920e1bd256b5a8120e2789893 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 26 Feb 2023 10:25:14 +1100 Subject: [PATCH] AP_InertialSensor: removed the error count on BMI088 0xff data this error happens often enough that it is frustrating for users who can't arm, which just encourages use of forced arming. logs show this happening at a rate of once every few seconds, which doesn't impact on the usability of the gyro (which is at 2kHz), but does prevent arming with this error incremement --- libraries/AP_InertialSensor/AP_InertialSensor_BMI088.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.cpp index 9474a952ab..dcbbf22046 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.cpp @@ -429,7 +429,6 @@ void AP_InertialSensor_BMI088::read_fifo_gyro(void) // data is 16 bits with 2000dps range for (uint8_t i = 0; i < num_frames; i++) { if (data[i] == bad_frame) { - _inc_gyro_error_count(gyro_instance); continue; } Vector3f gyro(data[i].x, data[i].y, data[i].z);