From 0985327331d53aa9d9692ad4b0e210ffdae06747 Mon Sep 17 00:00:00 2001
From: Andrew Tridgell <tridge@samba.org>
Date: Fri, 30 Mar 2012 17:05:44 +1100
Subject: [PATCH] ACM: use set_blocking_writes(false) when we arm motors

---
 ArduCopter/motors.pde | 8 ++++++++
 1 file changed, 8 insertions(+)

diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde
index 0744b5285..0671fd209 100644
--- a/ArduCopter/motors.pde
+++ b/ArduCopter/motors.pde
@@ -75,6 +75,14 @@ static void init_arm_motors()
 	gcs_send_text_P(SEVERITY_HIGH, PSTR("ARMING MOTORS"));
 	#endif
 
+    // we don't want writes to the serial port to cause us to pause
+    // mid-flight, so set the serial ports non-blocking once we arm
+    // the motors
+    Serial.set_blocking_writes(false);
+    if (gcs3.initialised) {
+        Serial3.set_blocking_writes(false);
+    }
+
 	motor_armed 	= true;
 
 	#if PIEZO_ARMING == 1
-- 
GitLab