mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
HAL_SITL: prevent abort on select with -1 fd
This commit is contained in:
parent
9bb251a3fa
commit
097c2011e1
@ -385,6 +385,9 @@ void UARTDriver::_set_nonblocking(int fd)
|
||||
|
||||
void UARTDriver::_timer_tick(void)
|
||||
{
|
||||
if (!_connected) {
|
||||
return;
|
||||
}
|
||||
uint32_t navail;
|
||||
ssize_t nwritten;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user