Browse Source

HAL_PX4: even larger tx buffer size for faster log transfer

mission-4.1.18
Andrew Tridgell 11 years ago
parent
commit
a95868e124
  1. 2
      libraries/AP_HAL_PX4/UARTDriver.cpp

2
libraries/AP_HAL_PX4/UARTDriver.cpp

@ -48,7 +48,7 @@ void PX4UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) @@ -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

Loading…
Cancel
Save