mirror of https://github.com/ArduPilot/ardupilot
HAL_PX4: recover 12k of ram from USB buffers
faster NuttX means we don't need such larger buffers
This commit is contained in:
parent
16f09a6eae
commit
7cd7ff89fd
|
@ -50,7 +50,7 @@ void PX4UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
|||
uint16_t min_tx_buffer = 1024;
|
||||
uint16_t min_rx_buffer = 512;
|
||||
if (strcmp(_devpath, "/dev/ttyACM0") == 0) {
|
||||
min_tx_buffer = 16384;
|
||||
min_tx_buffer = 4096;
|
||||
min_rx_buffer = 1024;
|
||||
}
|
||||
// on PX4 we have enough memory to have a larger transmit and
|
||||
|
|
Loading…
Reference in New Issue