mirror of https://github.com/ArduPilot/ardupilot
HAL_SITL: fixed segv on cygwin
This commit is contained in:
parent
d477905fbd
commit
fc9283964a
|
@ -367,6 +367,9 @@ void UARTDriver::_check_connection(void)
|
||||||
*/
|
*/
|
||||||
bool UARTDriver::_select_check(int fd)
|
bool UARTDriver::_select_check(int fd)
|
||||||
{
|
{
|
||||||
|
if (fd == -1) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
fd_set fds;
|
fd_set fds;
|
||||||
struct timeval tv;
|
struct timeval tv;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue