diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index acbf351af2..66066e1717 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -587,7 +587,6 @@ void Plane::startup_INS_ground(void) if (ins.gyro_calibration_timing() != AP_InertialSensor::GYRO_CAL_NEVER) { gcs().send_text(MAV_SEVERITY_ALERT, "Beginning INS calibration. Do not move plane"); - hal.scheduler->delay(100); } else { gcs().send_text(MAV_SEVERITY_ALERT, "Skipping INS calibration"); }