Browse Source

AP_HAL_SITL: check return value of setsockopt

mission-4.1.18
Peter Barker 7 years ago committed by Randy Mackay
parent
commit
7d271e0f3c
  1. 5
      libraries/AP_HAL_SITL/UARTDriver.cpp

5
libraries/AP_HAL_SITL/UARTDriver.cpp

@ -226,7 +226,10 @@ void UARTDriver::_tcp_start_connection(uint16_t port, bool wait_for_connection) @@ -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),

Loading…
Cancel
Save