mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_HAL_SITL: use FD_CLOEXEC instead of linux SOCK_CLOEXEC for socket
This commit is contained in:
parent
56cc0d3ef7
commit
30e0c7f746
@ -222,11 +222,16 @@ void UARTDriver::_tcp_start_connection(uint16_t port, bool wait_for_connection)
|
||||
}
|
||||
sockaddr.sin_family = AF_INET;
|
||||
|
||||
_listen_fd = socket(AF_INET, SOCK_STREAM | SOCK_CLOEXEC, 0);
|
||||
_listen_fd = socket(AF_INET, SOCK_STREAM, 0);
|
||||
if (_listen_fd == -1) {
|
||||
fprintf(stderr, "socket failed - %s\n", strerror(errno));
|
||||
exit(1);
|
||||
}
|
||||
ret = fcntl(_listen_fd, F_SETFD, FD_CLOEXEC);
|
||||
if (ret == -1) {
|
||||
fprintf(stderr, "fcntl failed on setting FD_CLOEXEC - %s\n", strerror(errno));
|
||||
exit(1);
|
||||
}
|
||||
|
||||
/* we want to be able to re-use ports quickly */
|
||||
if (setsockopt(_listen_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)) == -1) {
|
||||
@ -300,11 +305,16 @@ 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 | SOCK_CLOEXEC, 0);
|
||||
_fd = socket(AF_INET, SOCK_STREAM, 0);
|
||||
if (_fd == -1) {
|
||||
fprintf(stderr, "socket failed - %s\n", strerror(errno));
|
||||
exit(1);
|
||||
}
|
||||
ret = fcntl(_fd, F_SETFD, FD_CLOEXEC);
|
||||
if (ret == -1) {
|
||||
fprintf(stderr, "fcntl failed on setting FD_CLOEXEC - %s\n", strerror(errno));
|
||||
exit(1);
|
||||
}
|
||||
|
||||
/* we want to be able to re-use ports quickly */
|
||||
setsockopt(_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one));
|
||||
|
Loading…
Reference in New Issue
Block a user