AP_HAL: allow for broadcast packets on UDP IPv4

This commit is contained in:
Andrew Tridgell 2015-07-29 16:46:33 +10:00 committed by Randy Mackay
parent 28bdeaf5d9
commit dfdedb3f33
2 changed files with 22 additions and 2 deletions

View File

@ -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

View File

@ -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);