From e79023ceeeb68ae84be758599d128c0565f34b98 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 14 Jul 2013 17:28:34 +1000 Subject: [PATCH] Plane: fixed problem with slow ground station connects don't trigger the "scheduler out of time" code when in the delay callback Thanks to Marijm Slootweg for noticing this! --- ArduPlane/GCS_Mavlink.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index f7f87516c6..02d25683ae 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -546,7 +546,7 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id, // if we don't have at least 1ms 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() < 1200) { + if (!in_mavlink_delay && scheduler.time_available_usec() < 1200) { gcs_out_of_time = true; return false; }