diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index ec1631231b..90e63b5589 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -258,11 +258,11 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id) return false; } - // if we don't have at least 1ms remaining before the main loop + // if we don't have at least 0.2ms 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 (!hal.scheduler->in_delay_callback() && - rover.scheduler.time_available_usec() < 1200) { + rover.scheduler.time_available_usec() < 200) { gcs().set_out_of_time(true); return false; }