AP_HAL: Allow APMSockets to autodetect Broadcast IPs
This commit is contained in:
parent
bf6bd3a023
commit
e8c852f0d4
@ -119,6 +119,8 @@ bool SocketAPM::connect(const char *address, uint16_t port)
|
||||
if (ret == -1) {
|
||||
goto fail_mc;
|
||||
}
|
||||
} else if (datagram && sockaddr.sin_addr.s_addr == INADDR_BROADCAST) {
|
||||
set_broadcast();
|
||||
}
|
||||
|
||||
ret = CALL_PREFIX(connect)(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr));
|
||||
|
Loading…
Reference in New Issue
Block a user