diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde
index 6ffa34d635ca05b9d416d6426e0337bcf037b934..7ecf42bbbba1e6b1a4e188e3c14b5907bc1161aa 100644
--- a/ArduCopter/ArduCopter.pde
+++ b/ArduCopter/ArduCopter.pde
@@ -315,8 +315,8 @@ static int16_t y_rate_error;
 static byte 	control_mode		= STABILIZE;
 static byte 	old_control_mode	= STABILIZE;
 static byte 	oldSwitchPosition;					// for remembering the control mode switch
-static int16_t  motor_out[8];
-static int16_t  motor_filtered[8];					// added to try and deal with biger motors
+static int16_t  motor_out[11];
+static int16_t  motor_filtered[11];					// added to try and deal with biger motors
 static bool		do_simple 			= false;
 
 static int16_t rc_override[8] = {0,0,0,0,0,0,0,0};
diff --git a/libraries/FastSerial/FastSerial.cpp b/libraries/FastSerial/FastSerial.cpp
index 5312f3d6bfd5a87a2858ac7e267454442f706807..75c8e850f0ebb45829cb88d9776d3b0dad392ea9 100644
--- a/libraries/FastSerial/FastSerial.cpp
+++ b/libraries/FastSerial/FastSerial.cpp
@@ -194,7 +194,7 @@ void FastSerial::flush(void)
 	// don't reverse this or there may be problems if the TX interrupt
 	// occurs after reading the value of _txBuffer->tail but before writing
 	// the value to _txBuffer->head.
-	_txBuffer->tail = _rxBuffer->head;
+	_txBuffer->tail = _txBuffer->head;
 }
 
 void FastSerial::write(uint8_t c)