diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 635b9538d0..cd7b3a2e5d 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -3281,6 +3281,7 @@ MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration_baro() MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration(const mavlink_command_long_t &packet) { + EXPECT_DELAY_MS(30000); if (is_equal(packet.param1,1.0f)) { if (!calibrate_gyros()) { return MAV_RESULT_FAILED;