Browse Source

HAL_VRBrain: don't clear buffers on no baud change

mission-4.1.18
Andrew Tridgell 7 years ago
parent
commit
48747be494
  1. 18
      libraries/AP_HAL_VRBRAIN/UARTDriver.cpp

18
libraries/AP_HAL_VRBRAIN/UARTDriver.cpp

@ -77,15 +77,24 @@ void VRBRAINUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) @@ -77,15 +77,24 @@ void VRBRAINUARTDriver::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 (b != 0) {
_baudrate = b;
}
if (clear_buffers) {
_readbuf.clear();
}
/*
allocate the write buffer
*/
@ -96,7 +105,8 @@ void VRBRAINUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) @@ -96,7 +105,8 @@ void VRBRAINUARTDriver::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();
}

Loading…
Cancel
Save