diff --git a/libraries/GCS_MAVLink/GCS.cpp b/libraries/GCS_MAVLink/GCS.cpp index a31c35f0115e5f..609b91a17c017f 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; } +#if 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 0ad5337c31103d..2e2b4b1e0c1100 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;