diff --git a/libraries/AP_Airspeed/Airspeed_Calibration.cpp b/libraries/AP_Airspeed/Airspeed_Calibration.cpp index 0374521df8..16170f9c81 100644 --- a/libraries/AP_Airspeed/Airspeed_Calibration.cpp +++ b/libraries/AP_Airspeed/Airspeed_Calibration.cpp @@ -164,11 +164,13 @@ void AP_Airspeed::update_calibration(const Vector3f &vground, int16_t max_airspe for (uint8_t i=0; i