From eca0940bc7adb427dab655db7000d6c43c7ad5ee Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 29 Jul 2015 16:46:33 +1000 Subject: [PATCH] AP_HAL: allow for broadcast packets on UDP IPv4 --- libraries/AP_HAL/utility/Socket.cpp | 18 ++++++++++++++++-- libraries/AP_HAL/utility/Socket.h | 6 ++++++ 2 files changed, 22 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL/utility/Socket.cpp b/libraries/AP_HAL/utility/Socket.cpp index ac0ecf5b5c..5ecf2b6a04 100644 --- a/libraries/AP_HAL/utility/Socket.cpp +++ b/libraries/AP_HAL/utility/Socket.cpp @@ -136,10 +136,24 @@ ssize_t SocketAPM::recv(void *buf, size_t size, uint32_t timeout_ms) if (!pollin(timeout_ms)) { return -1; } - - return ::recvfrom(fd, buf, size, MSG_DONTWAIT, NULL, NULL); + socklen_t len = sizeof(in_addr); + return ::recvfrom(fd, buf, size, MSG_DONTWAIT, (sockaddr *)&in_addr, &len); } +/* + return the IP address and port of the last received packet + */ +void SocketAPM::last_recv_address(const char *&ip_addr, uint16_t &port) +{ + ip_addr = inet_ntoa(in_addr.sin_addr); + port = ntohs(in_addr.sin_port); +} + +void SocketAPM::set_broadcast(void) +{ + int one = 1; + setsockopt(fd,SOL_SOCKET,SO_BROADCAST,(char *)&one,sizeof(one)); +} /* return true if there is pending data for input diff --git a/libraries/AP_HAL/utility/Socket.h b/libraries/AP_HAL/utility/Socket.h index 3dcd447c65..96d74027be 100644 --- a/libraries/AP_HAL/utility/Socket.h +++ b/libraries/AP_HAL/utility/Socket.h @@ -41,11 +41,15 @@ public: bool bind(const char *address, uint16_t port); void reuseaddress(); void set_blocking(bool blocking); + void set_broadcast(void); ssize_t send(const void *pkt, size_t size); ssize_t sendto(const void *buf, size_t size, const char *address, uint16_t port); ssize_t recv(void *pkt, size_t size, uint32_t timeout_ms); + // return the IP address and port of the last received packet + void last_recv_address(const char *&ip_addr, uint16_t &port); + // return true if there is pending data for input bool pollin(uint32_t timeout_ms); @@ -61,6 +65,8 @@ public: private: bool datagram; + struct sockaddr_in in_addr {}; + int fd = -1; void make_sockaddr(const char *address, uint16_t port, struct sockaddr_in &sockaddr);