Copter: give UARTA 512 bytes

this reduces load by allowing more contiguous writes to the serial
buffers
This commit is contained in:
Andrew Tridgell 2013-10-08 22:05:19 +11:00 committed by Randy Mackay
parent d60a68fd9c
commit 64d34dc125
1 changed files with 1 additions and 1 deletions

View File

@ -92,7 +92,7 @@ static void init_ardupilot()
hal.uartA->begin(SERIAL0_BAUD, 256, 256);
#else
// use a bit less for non-HIL operation
hal.uartA->begin(SERIAL0_BAUD, 128, 128);
hal.uartA->begin(SERIAL0_BAUD, 512, 128);
#endif
// GPS serial port.