From 26cab97be2f667cf3dea5d70948243316ea3d8e3 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 13 Nov 2023 11:01:34 +1100 Subject: [PATCH] AP_HAL: fixed build --- libraries/AP_HAL/utility/Socket.cpp | 38 ++++++++++++----------------- libraries/AP_HAL/utility/Socket.h | 5 +--- 2 files changed, 16 insertions(+), 27 deletions(-) diff --git a/libraries/AP_HAL/utility/Socket.cpp b/libraries/AP_HAL/utility/Socket.cpp index 1e8e6957cff6df..0cb09f63b44929 100644 --- a/libraries/AP_HAL/utility/Socket.cpp +++ b/libraries/AP_HAL/utility/Socket.cpp @@ -23,20 +23,6 @@ #include "Socket.h" #include -#if AP_NETWORKING_BACKEND_CHIBIOS -#include -#include - -// not defined/implememnted in LwIP. -#ifndef F_SETFD -#define F_SETFD 2 -#endif - -/* For F_[GET|SET]FD. */ -#define FD_CLOEXEC 1 /* Actually anything with low bit set goes */ - -#endif - /* constructor */ @@ -49,7 +35,9 @@ SocketAPM::SocketAPM(bool _datagram, int _fd) : datagram(_datagram), fd(_fd) { +#ifdef FD_CLOEXEC fcntl(fd, F_SETFD, FD_CLOEXEC); +#endif if (!datagram) { int one = 1; setsockopt(fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one)); @@ -60,7 +48,7 @@ SocketAPM::~SocketAPM() { if (fd != -1) { #if AP_NETWORKING_BACKEND_CHIBIOS - lwip_close(fd); + ::lwip_close(fd); #else ::close(fd); #endif @@ -89,7 +77,7 @@ bool SocketAPM::connect(const char *address, uint16_t port) make_sockaddr(address, port, sockaddr); #if AP_NETWORKING_BACKEND_CHIBIOS - if (lwip_connect(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)) != 0) { + if (::lwip_connect(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)) != 0) { #else if (::connect(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)) != 0) { #endif @@ -109,7 +97,7 @@ bool SocketAPM::connect_timeout(const char *address, uint16_t port, uint32_t tim set_blocking(false); #if AP_NETWORKING_BACKEND_CHIBIOS - int ret = lwip_connect(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); + int ret = ::lwip_connect(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); #else int ret = ::connect(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); #endif @@ -141,7 +129,7 @@ bool SocketAPM::bind(const char *address, uint16_t port) make_sockaddr(address, port, sockaddr); #if AP_NETWORKING_BACKEND_CHIBIOS - if (lwip_bind(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)) != 0) { + if (::lwip_bind(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)) != 0) { #else if (::bind(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)) != 0) { #endif @@ -179,7 +167,11 @@ bool SocketAPM::set_blocking(bool blocking) const */ bool SocketAPM::set_cloexec() const { +#ifdef FD_CLOEXEC return (fcntl(fd, F_SETFD, FD_CLOEXEC) != -1); +#else + return false; +#endif } /* @@ -188,7 +180,7 @@ bool SocketAPM::set_cloexec() const ssize_t SocketAPM::send(const void *buf, size_t size) const { #if AP_NETWORKING_BACKEND_CHIBIOS - return lwip_send(fd, buf, size, 0); + return ::lwip_send(fd, buf, size, 0); #else return ::send(fd, buf, size, 0); #endif @@ -202,7 +194,7 @@ ssize_t SocketAPM::sendto(const void *buf, size_t size, const char *address, uin struct sockaddr_in sockaddr; make_sockaddr(address, port, sockaddr); #if AP_NETWORKING_BACKEND_CHIBIOS - return lwip_sendto(fd, buf, size, 0, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); + return ::lwip_sendto(fd, buf, size, 0, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); #else return ::sendto(fd, buf, size, 0, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); #endif @@ -218,7 +210,7 @@ ssize_t SocketAPM::recv(void *buf, size_t size, uint32_t timeout_ms) } socklen_t len = sizeof(in_addr); #if AP_NETWORKING_BACKEND_CHIBIOS - return lwip_recvfrom(fd, buf, size, MSG_DONTWAIT, (sockaddr *)&in_addr, &len); + return ::lwip_recvfrom(fd, buf, size, MSG_DONTWAIT, (sockaddr *)&in_addr, &len); #else return ::recvfrom(fd, buf, size, MSG_DONTWAIT, (sockaddr *)&in_addr, &len); #endif @@ -286,7 +278,7 @@ bool SocketAPM::pollout(uint32_t timeout_ms) bool SocketAPM::listen(uint16_t backlog) const { #if AP_NETWORKING_BACKEND_CHIBIOS - return lwip_listen(fd, (int)backlog) == 0; + return ::lwip_listen(fd, (int)backlog) == 0; #else return ::listen(fd, (int)backlog) == 0; #endif @@ -303,7 +295,7 @@ SocketAPM *SocketAPM::accept(uint32_t timeout_ms) } #if AP_NETWORKING_BACKEND_CHIBIOS - int newfd = lwip_accept(fd, nullptr, nullptr); + int newfd = ::lwip_accept(fd, nullptr, nullptr); #else int newfd = ::accept(fd, nullptr, nullptr); #endif diff --git a/libraries/AP_HAL/utility/Socket.h b/libraries/AP_HAL/utility/Socket.h index 40be86b47e5223..a20cbbda0e9e45 100644 --- a/libraries/AP_HAL/utility/Socket.h +++ b/libraries/AP_HAL/utility/Socket.h @@ -33,6 +33,7 @@ #include #elif AP_NETWORKING_BACKEND_CHIBIOS #include +#include #endif class SocketAPM { @@ -71,11 +72,7 @@ class SocketAPM { private: bool datagram; -#if AP_NETWORKING_BACKEND_CHIBIOS - typedef struct sockaddr_in in_addr; -#else struct sockaddr_in in_addr {}; -#endif int fd = -1;