mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-12 02:48:28 -04:00
HAL_PX4: don't clear buffers if no baudrate change
This commit is contained in:
parent
84624fbbf6
commit
84a6c18c43
@ -78,12 +78,18 @@ void PX4UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
|||||||
_initialised = false;
|
_initialised = false;
|
||||||
_readbuf.set_size(rxS);
|
_readbuf.set_size(rxS);
|
||||||
}
|
}
|
||||||
if (hal.console != this) { // don't clear USB buffers (allows early startup messages to escape)
|
|
||||||
_readbuf.clear();
|
bool clear_buffers = false;
|
||||||
|
if (b != 0) {
|
||||||
|
// clear buffers on baudrate change, but not on the console (which is usually USB)
|
||||||
|
if (_baudrate != b && hal.console != this) {
|
||||||
|
clear_buffers = true;
|
||||||
|
}
|
||||||
|
_baudrate = b;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (b != 0) {
|
if (clear_buffers) {
|
||||||
_baudrate = b;
|
_readbuf.clear();
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -96,7 +102,8 @@ void PX4UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
|||||||
_initialised = false;
|
_initialised = false;
|
||||||
_writebuf.set_size(txS);
|
_writebuf.set_size(txS);
|
||||||
}
|
}
|
||||||
if (hal.console != this) { // don't clear USB buffers (allows early startup messages to escape)
|
|
||||||
|
if (clear_buffers) {
|
||||||
_writebuf.clear();
|
_writebuf.clear();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user