From 7cd7ff89fd78a418ce5de036c14bfe46edbf5c07 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 27 Mar 2015 15:08:52 -0700 Subject: [PATCH] HAL_PX4: recover 12k of ram from USB buffers faster NuttX means we don't need such larger buffers --- libraries/AP_HAL_PX4/UARTDriver.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_PX4/UARTDriver.cpp b/libraries/AP_HAL_PX4/UARTDriver.cpp index b7188a125e..201a12bc5c 100644 --- a/libraries/AP_HAL_PX4/UARTDriver.cpp +++ b/libraries/AP_HAL_PX4/UARTDriver.cpp @@ -50,7 +50,7 @@ void PX4UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) uint16_t min_tx_buffer = 1024; uint16_t min_rx_buffer = 512; if (strcmp(_devpath, "/dev/ttyACM0") == 0) { - min_tx_buffer = 16384; + min_tx_buffer = 4096; min_rx_buffer = 1024; } // on PX4 we have enough memory to have a larger transmit and