diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 7c4ce9debb..704f01bd24 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1052,12 +1052,9 @@ Mavlink::init_udp() /* set default target address, but not for onboard mode (will be set on first received packet) */ memset((char *)&_src_addr, 0, sizeof(_src_addr)); - if (_mode != MAVLINK_MODE_ONBOARD) { - _src_addr.sin_family = AF_INET; - inet_aton("127.0.0.1", &_src_addr.sin_addr); - _src_addr.sin_port = htons(_remote_port); - set_client_source_initialized(); - } + _src_addr.sin_family = AF_INET; + inet_aton("127.0.0.1", &_src_addr.sin_addr); + _src_addr.sin_port = htons(_remote_port); /* default broadcast address */ memset((char *)&_bcast_addr, 0, sizeof(_bcast_addr)); diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 5c2bed9bb5..03fed9e23d 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -1825,6 +1825,7 @@ MavlinkReceiver::receive_thread(void *arg) srcaddr_last->sin_addr.s_addr = srcaddr.sin_addr.s_addr; srcaddr_last->sin_port = srcaddr.sin_port; _mavlink->set_client_source_initialized(); + warnx("changing partner IP to: %s", inet_ntoa(srcaddr.sin_addr)); } } #endif