mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_SITL: remove race in SITL::UARTDriver::_write
txspace could change if another thread is involved
This commit is contained in:
parent
4f69f9cc23
commit
efc7b4b6ee
@ -256,8 +256,9 @@ void UARTDriver::_flush(void)
|
||||
|
||||
size_t UARTDriver::_write(const uint8_t *buffer, size_t size)
|
||||
{
|
||||
if (txspace() <= size) {
|
||||
size = txspace();
|
||||
const auto _txspace = txspace();
|
||||
if (_txspace < size) {
|
||||
size = _txspace;
|
||||
}
|
||||
if (size <= 0) {
|
||||
return 0;
|
||||
|
Loading…
Reference in New Issue
Block a user