diff --git a/libraries/AP_HAL_SITL/UARTDriver.cpp b/libraries/AP_HAL_SITL/UARTDriver.cpp index 3dbc11b9bd..9634b237be 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.cpp +++ b/libraries/AP_HAL_SITL/UARTDriver.cpp @@ -226,7 +226,10 @@ void UARTDriver::_tcp_start_connection(uint16_t port, bool wait_for_connection) } /* we want to be able to re-use ports quickly */ - setsockopt(_listen_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)); + if (setsockopt(_listen_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)) == -1) { + fprintf(stderr, "setsockopt failed: %s\n", strerror(errno)); + exit(1); + } fprintf(stderr, "bind port %u for %u\n", (unsigned)ntohs(sockaddr.sin_port),