MAVLink: Improve network handling

This commit is contained in:
Lorenz Meier
2016-02-09 12:50:45 +01:00
parent fb8b981015
commit 3e02bb1070
2 changed files with 4 additions and 6 deletions

View File

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

View File

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