AP_HAL: improved sockaddr_in compatibility

This commit is contained in:
Andrew Tridgell 2023-12-17 14:40:46 +11:00
parent 1bceee1863
commit 8e132e44cf
2 changed files with 27 additions and 22 deletions

View File

@ -55,7 +55,9 @@ static_assert(sizeof(last_in_addr) == sizeof(struct sockaddr_in), "last_in_addr
SocketAPM::SocketAPM(bool _datagram) : SocketAPM::SocketAPM(bool _datagram) :
SocketAPM(_datagram, SocketAPM(_datagram,
CALL_PREFIX(socket)(AF_INET, _datagram?SOCK_DGRAM:SOCK_STREAM, 0)) CALL_PREFIX(socket)(AF_INET, _datagram?SOCK_DGRAM:SOCK_STREAM, 0))
{} {
static_assert(sizeof(SocketAPM::last_in_addr) >= sizeof(struct sockaddr_in), "last_in_addr must be at least sockaddr_in size");
}
SocketAPM::SocketAPM(bool _datagram, int _fd) : SocketAPM::SocketAPM(bool _datagram, int _fd) :
datagram(_datagram), datagram(_datagram),
@ -310,10 +312,10 @@ ssize_t SocketAPM::recv(void *buf, size_t size, uint32_t timeout_ms)
errno = EWOULDBLOCK; errno = EWOULDBLOCK;
return -1; return -1;
} }
socklen_t len = sizeof(last_in_addr); socklen_t len = sizeof(struct sockaddr_in);
int fin = get_read_fd(); int fin = get_read_fd();
ssize_t ret; ssize_t ret;
ret = CALL_PREFIX(recvfrom)(fin, buf, size, MSG_DONTWAIT, (sockaddr *)&last_in_addr, &len); ret = CALL_PREFIX(recvfrom)(fin, buf, size, MSG_DONTWAIT, (sockaddr *)&last_in_addr[0], &len);
if (ret <= 0) { if (ret <= 0) {
if (!datagram && connected && ret == 0) { if (!datagram && connected && ret == 0) {
// remote host has closed connection // remote host has closed connection
@ -330,9 +332,10 @@ ssize_t SocketAPM::recv(void *buf, size_t size, uint32_t timeout_ms)
if (CALL_PREFIX(getsockname)(fd, (struct sockaddr *)&send_addr, &send_len) != 0) { if (CALL_PREFIX(getsockname)(fd, (struct sockaddr *)&send_addr, &send_len) != 0) {
return -1; return -1;
} }
if (last_in_addr.sin_port == send_addr.sin_port && const struct sockaddr_in &sin = *(struct sockaddr_in *)&last_in_addr[0];
last_in_addr.sin_family == send_addr.sin_family && if (sin.sin_port == send_addr.sin_port &&
last_in_addr.sin_addr.s_addr == send_addr.sin_addr.s_addr) { sin.sin_family == send_addr.sin_family &&
sin.sin_addr.s_addr == send_addr.sin_addr.s_addr) {
// discard packets from ourselves // discard packets from ourselves
return -1; return -1;
} }
@ -355,11 +358,13 @@ void SocketAPM::last_recv_address(const char *&ip_addr, uint16_t &port) const
*/ */
const char *SocketAPM::last_recv_address(char *ip_addr_buf, uint8_t buflen, uint16_t &port) const const char *SocketAPM::last_recv_address(char *ip_addr_buf, uint8_t buflen, uint16_t &port) const
{ {
const char *ret = CALL_PREFIX(inet_ntop)(AF_INET, (void*)&last_in_addr.sin_addr, ip_addr_buf, buflen); const struct sockaddr_in &sin = *(struct sockaddr_in *)&last_in_addr[0];
const char *ret = inet_addr_to_str((void*)&sin.sin_addr, ip_addr_buf, buflen);
if (ret == nullptr) { if (ret == nullptr) {
return nullptr; return nullptr;
} }
port = ntohs(last_in_addr.sin_port); port = ntohs(sin.sin_port);
return ret; return ret;
} }
@ -444,8 +449,9 @@ SocketAPM *SocketAPM::accept(uint32_t timeout_ms)
return nullptr; return nullptr;
} }
socklen_t len = sizeof(last_in_addr); struct sockaddr_in &sin = *(struct sockaddr_in *)&last_in_addr[0];
int newfd = CALL_PREFIX(accept)(fd, (sockaddr *)&last_in_addr, &len); socklen_t len = sizeof(sin);
int newfd = CALL_PREFIX(accept)(fd, (sockaddr *)&sin, &len);
if (newfd == -1) { if (newfd == -1) {
return nullptr; return nullptr;
} }
@ -497,4 +503,9 @@ SocketAPM *SocketAPM::duplicate(void)
return ret; return ret;
} }
const char *SocketAPM::inet_addr_to_str(const void *src, char *dst, uint16_t len)
{
return CALL_PREFIX(inet_ntop)(AF_INET, src, dst, len);
}
#endif // AP_NETWORKING_BACKEND_ANY #endif // AP_NETWORKING_BACKEND_ANY

View File

@ -22,10 +22,6 @@
#if AP_NETWORKING_SOCKETS_ENABLED #if AP_NETWORKING_SOCKETS_ENABLED
#if HAL_OS_SOCKETS
struct sockaddr_in;
class SocketAPM { class SocketAPM {
public: public:
SocketAPM(bool _datagram); SocketAPM(bool _datagram);
@ -79,15 +75,14 @@ public:
return connected; return connected;
} }
// access to inet_ntop
static const char *inet_addr_to_str(const void *src, char *dst, uint16_t len);
private: private:
bool datagram; bool datagram;
struct { // we avoid using struct sockaddr_in here to keep support for
uint16_t sin_family; // mixing native sockets and lwip sockets in SITL
uint16_t sin_port; uint32_t last_in_addr[4];
struct {
uint32_t s_addr;
} sin_addr;
} last_in_addr;
bool is_multicast_address(struct sockaddr_in &addr) const; bool is_multicast_address(struct sockaddr_in &addr) const;
int fd = -1; int fd = -1;
@ -100,5 +95,4 @@ private:
void make_sockaddr(const char *address, uint16_t port, struct sockaddr_in &sockaddr); void make_sockaddr(const char *address, uint16_t port, struct sockaddr_in &sockaddr);
}; };
#endif // HAL_OS_SOCKETS
#endif // AP_NETWORKING_SOCKETS_ENABLED #endif // AP_NETWORKING_SOCKETS_ENABLED