From 8ea3e686202b3614c094bbb4fc28fec419be9192 Mon Sep 17 00:00:00 2001
From: Randy Mackay <rmackay9@yahoo.com>
Date: Wed, 23 Oct 2013 14:11:28 +0900
Subject: [PATCH] Copter: bug fix for loading missions while armed

---
 ArduCopter/GCS_Mavlink.pde | 4 ++--
 1 file changed, 2 insertions(+), 2 deletions(-)

diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde
index 9432d24b5..3854e84d7 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;
     }
-- 
GitLab