diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 9432d24b5b0a5269cd92d1ecd9ead4de660681a7..3854e84d71c2e2c301b94b22e84ca64a6f3f84d1 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -516,10 +516,10 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id, } #if HIL_MODE != HIL_MODE_SENSORS - // if we don't have at least 1ms remaining before the main loop + // if we don't have at least 250 micros remaining before the main loop // wants to fire then don't send a mavlink message. We want to // prioritise the main flight control loop over communications - if (scheduler.time_available_usec() < 800 && motors.armed()) { + if (scheduler.time_available_usec() < 250 && motors.armed()) { gcs_out_of_time = true; return false; }