mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-16 13:07:34 +08:00
Re-instate UDP handling for MAVLink app
This commit is contained in:
@@ -1817,8 +1817,8 @@ MavlinkReceiver::receive_thread(void *arg)
|
||||
if ((srcaddr_last->sin_addr.s_addr == htonl(localhost) && srcaddr.sin_addr.s_addr != htonl(localhost))
|
||||
|| (_mavlink->get_mode() == Mavlink::MAVLINK_MODE_ONBOARD && !_mavlink->get_client_source_initialized())) {
|
||||
// if we were sending to localhost before but have a new host then accept him
|
||||
//memcpy(srcaddr_last, &srcaddr, sizeof(*srcaddr_last));
|
||||
//PX4_WARN("XXX: not really updating: UDP source addr changed: %s", inet_ntoa(srcaddr.sin_addr));
|
||||
srcaddr_last->sin_addr.s_addr = srcaddr.sin_addr.s_addr;
|
||||
srcaddr_last->sin_port = srcaddr.sin_port;
|
||||
_mavlink->set_client_source_initialized();
|
||||
}
|
||||
#endif
|
||||
|
||||
Reference in New Issue
Block a user