Skip to content

Commit

Permalink
GCS_MAVLink: filter out additional messages for High Latency link
Browse files Browse the repository at this point in the history
  • Loading branch information
stephendade committed Mar 8, 2024
1 parent 9fc068d commit b9c1a1a
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 0 deletions.
5 changes: 5 additions & 0 deletions libraries/GCS_MAVLink/GCS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
Expand Down
4 changes: 4 additions & 0 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down

0 comments on commit b9c1a1a

Please sign in to comment.