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