mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
AP_HAL_SITL: set close-on-exec flag on uart socket
This commit is contained in:
parent
e520d4fe42
commit
f986f1366f
@ -222,7 +222,7 @@ void UARTDriver::_tcp_start_connection(uint16_t port, bool wait_for_connection)
|
||||
}
|
||||
sockaddr.sin_family = AF_INET;
|
||||
|
||||
_listen_fd = socket(AF_INET, SOCK_STREAM, 0);
|
||||
_listen_fd = socket(AF_INET, SOCK_STREAM | SOCK_CLOEXEC, 0);
|
||||
if (_listen_fd == -1) {
|
||||
fprintf(stderr, "socket failed - %s\n", strerror(errno));
|
||||
exit(1);
|
||||
@ -300,7 +300,7 @@ void UARTDriver::_tcp_start_client(const char *address, uint16_t port)
|
||||
sockaddr.sin_family = AF_INET;
|
||||
sockaddr.sin_addr.s_addr = inet_addr(address);
|
||||
|
||||
_fd = socket(AF_INET, SOCK_STREAM, 0);
|
||||
_fd = socket(AF_INET, SOCK_STREAM | SOCK_CLOEXEC, 0);
|
||||
if (_fd == -1) {
|
||||
fprintf(stderr, "socket failed - %s\n", strerror(errno));
|
||||
exit(1);
|
||||
|
Loading…
Reference in New Issue
Block a user