HAL_SITL: fixed tcp client mode

This commit is contained in:
Andrew Tridgell 2016-05-30 16:42:28 +10:00
parent 475579e8ff
commit 04f87a452e

View File

@ -271,7 +271,7 @@ void UARTDriver::_tcp_start_client(const char *address, uint16_t port)
#ifdef HAVE_SOCK_SIN_LEN #ifdef HAVE_SOCK_SIN_LEN
sockaddr.sin_len = sizeof(sockaddr); sockaddr.sin_len = sizeof(sockaddr);
#endif #endif
sockaddr.sin_port = port; sockaddr.sin_port = htons(port);
sockaddr.sin_family = AF_INET; sockaddr.sin_family = AF_INET;
sockaddr.sin_addr.s_addr = inet_addr(address); sockaddr.sin_addr.s_addr = inet_addr(address);