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
This commit is contained in:
Andrew Tridgell 2023-02-26 10:25:14 +11:00
parent def81b9a1a
commit a0fe53414c
1 changed files with 0 additions and 1 deletions

View File

@ -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);