|
|
@ -1049,10 +1049,10 @@ Mavlink::init_udp() |
|
|
|
/* set default target address, but not for onboard mode (will be set on first received packet) */ |
|
|
|
/* set default target address, but not for onboard mode (will be set on first received packet) */ |
|
|
|
memset((char *)&_src_addr, 0, sizeof(_src_addr)); |
|
|
|
memset((char *)&_src_addr, 0, sizeof(_src_addr)); |
|
|
|
if (_mode != MAVLINK_MODE_ONBOARD) { |
|
|
|
if (_mode != MAVLINK_MODE_ONBOARD) { |
|
|
|
set_client_source_initialized(); |
|
|
|
|
|
|
|
_src_addr.sin_family = AF_INET; |
|
|
|
_src_addr.sin_family = AF_INET; |
|
|
|
inet_aton("127.0.0.1", &_src_addr.sin_addr); |
|
|
|
inet_aton("127.0.0.1", &_src_addr.sin_addr); |
|
|
|
_src_addr.sin_port = htons(DEFAULT_REMOTE_PORT_UDP); |
|
|
|
_src_addr.sin_port = htons(DEFAULT_REMOTE_PORT_UDP); |
|
|
|
|
|
|
|
set_client_source_initialized(); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
/* default broadcast address */ |
|
|
|
/* default broadcast address */ |
|
|
|