From 116b51f51a353efa8e3891f9c44d6e48049eb595 Mon Sep 17 00:00:00 2001 From: Stephen Dade Date: Mon, 4 Mar 2024 22:59:45 +1100 Subject: [PATCH] GCS_MAVLink: dont send timesync or on active channels for high latency links --- libraries/GCS_MAVLink/GCS.cpp | 5 +++++ libraries/GCS_MAVLink/GCS_Common.cpp | 4 ++++ 2 files changed, 9 insertions(+) diff --git a/libraries/GCS_MAVLink/GCS.cpp b/libraries/GCS_MAVLink/GCS.cpp index a31c35f0115e5f..e67231b6df1214 100644 --- a/libraries/GCS_MAVLink/GCS.cpp +++ b/libraries/GCS_MAVLink/GCS.cpp @@ -99,6 +99,11 @@ void GCS::send_to_active_channels(uint32_t msgid, const char *pkt) if (!c.is_active()) { continue; } +#ifdef HAL_HIGH_LATENCY2_ENABLED + if (c.is_high_latency_link) { + continue; + } +#endif // size checks done by this method: c.send_message(pkt, entry); } diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index b04f34bd751f86..21f721bcafb88d 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1851,7 +1851,11 @@ GCS_MAVLINK::update_receive(uint32_t max_time_us) // send a timesync message every 10 seconds; this is for data // collection purposes +#if HAL_HIGH_LATENCY2_ENABLED + if (tnow - _timesync_request.last_sent_ms > _timesync_request.interval_ms && !is_private() && !is_high_latency_link) { +#else if (tnow - _timesync_request.last_sent_ms > _timesync_request.interval_ms && !is_private()) { +#endif if (HAVE_PAYLOAD_SPACE(chan, TIMESYNC)) { send_timesync(); _timesync_request.last_sent_ms = tnow;