mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_SITL: ensure reboot command ACK is written out in SITL
This commit is contained in:
parent
1bda79dd72
commit
5ebe505f2c
@ -196,6 +196,26 @@ bool UARTDriver::discard_input(void)
|
|||||||
|
|
||||||
void UARTDriver::flush(void)
|
void UARTDriver::flush(void)
|
||||||
{
|
{
|
||||||
|
// flush the write buffer - but don't fail and don't
|
||||||
|
// infinitely-loop. This is not a good definition of "flush", but
|
||||||
|
// it was judged that we had to return from this function even if
|
||||||
|
// we hadn't actually done our job.
|
||||||
|
uint32_t start_ms = AP_HAL::millis();
|
||||||
|
while (AP_HAL::millis() - start_ms < 1000) {
|
||||||
|
if (_writebuffer.available() == 0) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
_timer_tick();
|
||||||
|
}
|
||||||
|
|
||||||
|
// ensure that the outbound TCP queue is also empty...
|
||||||
|
start_ms = AP_HAL::millis();
|
||||||
|
while (AP_HAL::millis() - start_ms < 1000) {
|
||||||
|
if (((HALSITL::UARTDriver*)hal.serial(0))->get_system_outqueue_length() == 0) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
usleep(1000);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// size_t UARTDriver::write(uint8_t c)
|
// size_t UARTDriver::write(uint8_t c)
|
||||||
|
Loading…
Reference in New Issue
Block a user