HAL_ChibiOS: scale uart rx buffer size with baudrate
this ensures we have enough buffer space for a RTK GPS, as well as for high speed comms with a companion computer
This commit is contained in:
parent
52e0e5e223
commit
30e51c9f64
@ -146,6 +146,14 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
|||||||
uint16_t min_tx_buffer = HAL_UART_MIN_TX_SIZE;
|
uint16_t min_tx_buffer = HAL_UART_MIN_TX_SIZE;
|
||||||
uint16_t min_rx_buffer = HAL_UART_MIN_RX_SIZE;
|
uint16_t min_rx_buffer = HAL_UART_MIN_RX_SIZE;
|
||||||
|
|
||||||
|
/*
|
||||||
|
increase min RX size to ensure we can receive a fully utilised
|
||||||
|
UART if we are running our receive loop at 40Hz. This means 25ms
|
||||||
|
of data. Assumes 10 bits per byte, which is normal for most
|
||||||
|
protocols
|
||||||
|
*/
|
||||||
|
min_rx_buffer = MAX(min_rx_buffer, b/(40*10));
|
||||||
|
|
||||||
if (sdef.is_usb) {
|
if (sdef.is_usb) {
|
||||||
// give more buffer space for log download on USB
|
// give more buffer space for log download on USB
|
||||||
min_tx_buffer *= 4;
|
min_tx_buffer *= 4;
|
||||||
|
Loading…
Reference in New Issue
Block a user