mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: use a larger TX buffer on USB
this is needed for fast log download on vehicles with 50Hz main loop
This commit is contained in:
parent
3ae4cfbf22
commit
7897fbc3c1
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue