HAL_ChibiOS: don't clear buffers if no baudrate change

This commit is contained in:
Andrew Tridgell 2018-07-12 09:01:37 +10:00
parent 374c46bd57
commit 50f7e55f0b
1 changed files with 11 additions and 4 deletions

View File

@ -155,13 +155,19 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
_initialised = false;
_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 (clear_buffers) {
_readbuf.clear();
}
if (rx_bounce_buf == nullptr) {
rx_bounce_buf = (uint8_t *)hal.util->malloc_type(RX_BOUNCE_BUFSIZE, AP_HAL::Util::MEM_DMA_SAFE);
@ -182,7 +188,8 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
_initialised = false;
_writebuf.set_size(txS);
}
if (hal.console != this) { // don't clear USB buffers (allows early startup messages to escape)
if (clear_buffers) {
_writebuf.clear();
}