From dcee5e96931203960f9fe4126a90008e5049ff3f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 13 Feb 2024 15:15:21 +1100 Subject: [PATCH] AP_InertialSensor: fixed accel cal simple to remove unused IMUs when we change EAHRS_SENSORS to remove use of IMU from an external AHRS we need to be able to zero the accel and gyro offsets to get prearms to pass --- libraries/AP_InertialSensor/AP_InertialSensor.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index 37504d8897..e5f7152a97 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -2464,7 +2464,7 @@ MAV_RESULT AP_InertialSensor::simple_accel_cal() } // remove existing accel offsets and scaling - for (uint8_t k=0; k