mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_SITL: correct return values on UARTDriver write call
This commit is contained in:
parent
0b20328756
commit
32659fd3b6
@ -269,29 +269,27 @@ size_t UARTDriver::_write(const uint8_t *buffer, size_t size)
|
|||||||
close(_fd);
|
close(_fd);
|
||||||
_fd = -1;
|
_fd = -1;
|
||||||
_connected = false;
|
_connected = false;
|
||||||
|
return 0;
|
||||||
}
|
}
|
||||||
// these have no effect
|
// these have no effect
|
||||||
tcdrain(_fd);
|
tcdrain(_fd);
|
||||||
|
return nwritten;
|
||||||
} else {
|
} else {
|
||||||
/*
|
/*
|
||||||
simulate byte loss at the link layer
|
simulate byte loss at the link layer
|
||||||
*/
|
*/
|
||||||
size_t nwrite = size;
|
uint8_t lost_byte = 0;
|
||||||
#if !defined(HAL_BUILD_AP_PERIPH)
|
#if !defined(HAL_BUILD_AP_PERIPH)
|
||||||
SITL::SIM *_sitl = AP::sitl();
|
SITL::SIM *_sitl = AP::sitl();
|
||||||
|
|
||||||
if (_sitl && _sitl->uart_byte_loss_pct > 0) {
|
if (_sitl && _sitl->uart_byte_loss_pct > 0) {
|
||||||
if (fabsf(rand_float()) < _sitl->uart_byte_loss_pct.get() * 0.01 * size) {
|
if (fabsf(rand_float()) < _sitl->uart_byte_loss_pct.get() * 0.01 * size) {
|
||||||
nwrite--;
|
lost_byte = 1;
|
||||||
}
|
|
||||||
if (nwrite == 0) {
|
|
||||||
return size;
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif // HAL_BUILD_AP_PERIPH
|
#endif // HAL_BUILD_AP_PERIPH
|
||||||
_writebuffer.write(buffer, nwrite);
|
return _writebuffer.write(buffer, size - lost_byte) + lost_byte;
|
||||||
}
|
}
|
||||||
return size;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user