AP_HAL_ChibiOS: Clear UART buffers when opening a port

This commit is contained in:
Michael du Breuil 2018-06-20 01:26:20 -07:00 committed by Francisco Ferreira
parent 037e53ba8a
commit 153ee6ca8e
1 changed files with 12 additions and 7 deletions

View File

@ -148,14 +148,16 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
thrashing of the heap once we are up. The ttyACM0 driver may not
connect for some time after boot
*/
while (_in_timer) {
hal.scheduler->delay(1);
}
if (rxS != _readbuf.get_size()) {
_initialised = false;
while (_in_timer) {
hal.scheduler->delay(1);
}
_readbuf.set_size(rxS);
}
if (hal.console != this) { // don't clear USB buffers (allows early startup messages to escape)
_readbuf.clear();
}
if (b != 0) {
_baudrate = b;
@ -173,13 +175,16 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
/*
allocate the write buffer
*/
while (_in_timer) {
hal.scheduler->delay(1);
}
if (txS != _writebuf.get_size()) {
_initialised = false;
while (_in_timer) {
hal.scheduler->delay(1);
}
_writebuf.set_size(txS);
}
if (hal.console != this) { // don't clear USB buffers (allows early startup messages to escape)
_writebuf.clear();
}
if (sdef.is_usb) {
#ifdef HAVE_USB_SERIAL