HAL_PX4: even larger tx buffer size for faster log transfer

This commit is contained in:
Andrew Tridgell 2013-12-28 16:01:48 +11:00
parent 22bdee8727
commit a95868e124

View File

@ -48,7 +48,7 @@ void PX4UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
uint16_t min_tx_buffer = 512;
uint16_t min_rx_buffer = 512;
if (strcmp(_devpath, "/dev/ttyACM0") == 0) {
min_tx_buffer = 4096;
min_tx_buffer = 16384;
min_rx_buffer = 1024;
}
// on PX4 we have enough memory to have a larger transmit and