From f986f1366ff55859bb96764a09fc3e28d83ec776 Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Mon, 28 May 2018 16:43:39 +0200 Subject: [PATCH] AP_HAL_SITL: set close-on-exec flag on uart socket --- libraries/AP_HAL_SITL/UARTDriver.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_SITL/UARTDriver.cpp b/libraries/AP_HAL_SITL/UARTDriver.cpp index 99726063f5..ef9be643f1 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.cpp +++ b/libraries/AP_HAL_SITL/UARTDriver.cpp @@ -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);