mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
HAL_ChibiOS: don't extend alloc of iomcu uart
This commit is contained in:
parent
6e01c1c19b
commit
9554103418
@ -156,7 +156,18 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
of data. Assumes 10 bits per byte, which is normal for most
|
||||
protocols
|
||||
*/
|
||||
min_rx_buffer = MAX(min_rx_buffer, b/(40*10));
|
||||
bool rx_size_by_baudrate = true;
|
||||
#if HAL_WITH_IO_MCU
|
||||
if (this == &uart_io) {
|
||||
// iomcu doesn't need extra space, just speed
|
||||
rx_size_by_baudrate = false;
|
||||
min_tx_buffer = 0;
|
||||
min_rx_buffer = 0;
|
||||
}
|
||||
#endif
|
||||
if (rx_size_by_baudrate) {
|
||||
min_rx_buffer = MAX(min_rx_buffer, b/(40*10));
|
||||
}
|
||||
|
||||
if (sdef.is_usb) {
|
||||
// give more buffer space for log download on USB
|
||||
|
Loading…
Reference in New Issue
Block a user