Skip to content

Commit

Permalink
AP_InertialSensor: fixed the error value for BMI088
Browse files Browse the repository at this point in the history
the bad value is -32767 not 0xffff (which is -1)

-32767 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:
ArduPilot#23033
  • Loading branch information
tridge committed Oct 4, 2023
1 parent 5ce731f commit ec959c0
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion libraries/AP_InertialSensor/AP_InertialSensor_BMI088.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand Down

0 comments on commit ec959c0

Please sign in to comment.