diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde
index 0744b52855547d704cb82426b33d819521e33d39..0671fd2090c36924852108988c32ed4db5e50b1d 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