mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_HAL_PX4: Clear UART buffers when opening a port
This commit is contained in:
parent
7043738f3b
commit
512939a839
@ -71,14 +71,16 @@ void PX4UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
|||||||
thrashing of the heap once we are up. The ttyACM0 driver may not
|
thrashing of the heap once we are up. The ttyACM0 driver may not
|
||||||
connect for some time after boot
|
connect for some time after boot
|
||||||
*/
|
*/
|
||||||
|
while (_in_timer) {
|
||||||
|
hal.scheduler->delay(1);
|
||||||
|
}
|
||||||
if (rxS != _readbuf.get_size()) {
|
if (rxS != _readbuf.get_size()) {
|
||||||
_initialised = false;
|
_initialised = false;
|
||||||
while (_in_timer) {
|
|
||||||
hal.scheduler->delay(1);
|
|
||||||
}
|
|
||||||
|
|
||||||
_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();
|
||||||
|
}
|
||||||
|
|
||||||
if (b != 0) {
|
if (b != 0) {
|
||||||
_baudrate = b;
|
_baudrate = b;
|
||||||
@ -87,13 +89,16 @@ void PX4UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
|||||||
/*
|
/*
|
||||||
allocate the write buffer
|
allocate the write buffer
|
||||||
*/
|
*/
|
||||||
|
while (_in_timer) {
|
||||||
|
hal.scheduler->delay(1);
|
||||||
|
}
|
||||||
if (txS != _writebuf.get_size()) {
|
if (txS != _writebuf.get_size()) {
|
||||||
_initialised = false;
|
_initialised = false;
|
||||||
while (_in_timer) {
|
|
||||||
hal.scheduler->delay(1);
|
|
||||||
}
|
|
||||||
_writebuf.set_size(txS);
|
_writebuf.set_size(txS);
|
||||||
}
|
}
|
||||||
|
if (hal.console != this) { // don't clear USB buffers (allows early startup messages to escape)
|
||||||
|
_writebuf.clear();
|
||||||
|
}
|
||||||
|
|
||||||
if (_fd == -1) {
|
if (_fd == -1) {
|
||||||
_fd = open(_devpath, O_RDWR);
|
_fd = open(_devpath, O_RDWR);
|
||||||
|
Loading…
Reference in New Issue
Block a user