From 7897fbc3c16f359c0f9859eb5994cd7b7d5bf2c9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 28 Aug 2018 08:49:37 +1000 Subject: [PATCH] HAL_ChibiOS: use a larger TX buffer on USB this is needed for fast log download on vehicles with 50Hz main loop --- libraries/AP_HAL_ChibiOS/UARTDriver.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp index e51e2a62cc..ca1ba9a8b5 100644 --- a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp +++ b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp @@ -131,6 +131,12 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) } uint16_t min_tx_buffer = 1024; uint16_t min_rx_buffer = 512; + + if (sdef.is_usb) { + // give more buffer space for log download on USB + min_tx_buffer *= 4; + } + // on PX4 we have enough memory to have a larger transmit and // receive buffer for all ports. This means we don't get delays // while waiting to write GPS config packets