mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_HAL_SITL: set cloexec on port 5760
This commit is contained in:
parent
e3b68876a9
commit
574a2b3652
@ -272,6 +272,7 @@ void UARTDriver::_tcp_start_connection(uint16_t port, bool wait_for_connection)
|
|||||||
}
|
}
|
||||||
setsockopt(_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one));
|
setsockopt(_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one));
|
||||||
setsockopt(_fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one));
|
setsockopt(_fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one));
|
||||||
|
fcntl(_fd, F_SETFD, FD_CLOEXEC);
|
||||||
_connected = true;
|
_connected = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user