diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index cdccd4dfedff019d48d19a6e04c3824335c793ae..8c8ce9b3a7fe19561b2166d046f260493dc3c572 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -432,7 +432,7 @@ public: const in_addr compute_broadcast_addr(const in_addr &host_addr, const in_addr &netmask_addr); - struct sockaddr_in *get_client_source_address() { return &_src_addr; } + struct sockaddr_in &get_client_source_address() { return _src_addr; } void set_client_source_initialized() { _src_addr_initialized = true; } diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 957e0b0a710c906fbac87a0a123370f2c14c0ecb..cbf58421194945f3aad9e178add17f676812e701 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -2546,7 +2546,7 @@ MavlinkReceiver::receive_thread(void *arg) // could be TCP or other protocol } - struct sockaddr_in *srcaddr_last = _mavlink->get_client_source_address(); + struct sockaddr_in &srcaddr_last = _mavlink->get_client_source_address(); int localhost = (127 << 24) + 1; @@ -2558,9 +2558,9 @@ MavlinkReceiver::receive_thread(void *arg) hrt_abstime stime = _mavlink->get_start_time(); if ((stime != 0 && (hrt_elapsed_time(&stime) > 3 * 1000 * 1000)) - || (srcaddr_last->sin_addr.s_addr == htonl(localhost))) { - srcaddr_last->sin_addr.s_addr = srcaddr.sin_addr.s_addr; - srcaddr_last->sin_port = srcaddr.sin_port; + || (srcaddr_last.sin_addr.s_addr == htonl(localhost))) { + srcaddr_last.sin_addr.s_addr = srcaddr.sin_addr.s_addr; + srcaddr_last.sin_port = srcaddr.sin_port; _mavlink->set_client_source_initialized(); PX4_INFO("partner IP: %s", inet_ntoa(srcaddr.sin_addr)); }