mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
HAL_SITL: fixed multicast UDP on cygwin
this will allow the SITL button on cygwin to work with multicast, allowing for complex vehicle interactions between machines
This commit is contained in:
parent
0bad9451d5
commit
3bcceb9420
@ -568,6 +568,14 @@ void UARTDriver::_udp_start_multicast(const char *address, uint16_t port)
|
|||||||
// close on exec, to allow reboot
|
// close on exec, to allow reboot
|
||||||
fcntl(_mc_fd, F_SETFD, FD_CLOEXEC);
|
fcntl(_mc_fd, F_SETFD, FD_CLOEXEC);
|
||||||
|
|
||||||
|
#if defined(__CYGWIN__) || defined(__CYGWIN64__) || defined(CYGWIN_BUILD)
|
||||||
|
/*
|
||||||
|
on cygwin you need to bind to INADDR_ANY then use the multicast
|
||||||
|
IP_ADD_MEMBERSHIP to get on the right address
|
||||||
|
*/
|
||||||
|
sockaddr.sin_addr.s_addr = htonl(INADDR_ANY);
|
||||||
|
#endif
|
||||||
|
|
||||||
ret = bind(_mc_fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr));
|
ret = bind(_mc_fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr));
|
||||||
if (ret == -1) {
|
if (ret == -1) {
|
||||||
fprintf(stderr, "multicast bind failed on port %u - %s\n",
|
fprintf(stderr, "multicast bind failed on port %u - %s\n",
|
||||||
|
Loading…
Reference in New Issue
Block a user