mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
GCS_MAVLink: filter out additional messages for High Latency link
This commit is contained in:
parent
84a5a52351
commit
faf2ae3a9c
@ -99,6 +99,11 @@ void GCS::send_to_active_channels(uint32_t msgid, const char *pkt)
|
|||||||
if (!c.is_active()) {
|
if (!c.is_active()) {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
#if HAL_HIGH_LATENCY2_ENABLED
|
||||||
|
if (c.is_high_latency_link) {
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
// size checks done by this method:
|
// size checks done by this method:
|
||||||
c.send_message(pkt, entry);
|
c.send_message(pkt, entry);
|
||||||
}
|
}
|
||||||
|
@ -1856,7 +1856,11 @@ GCS_MAVLINK::update_receive(uint32_t max_time_us)
|
|||||||
|
|
||||||
// send a timesync message every 10 seconds; this is for data
|
// send a timesync message every 10 seconds; this is for data
|
||||||
// collection purposes
|
// 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()) {
|
if (tnow - _timesync_request.last_sent_ms > _timesync_request.interval_ms && !is_private()) {
|
||||||
|
#endif
|
||||||
if (HAVE_PAYLOAD_SPACE(chan, TIMESYNC)) {
|
if (HAVE_PAYLOAD_SPACE(chan, TIMESYNC)) {
|
||||||
send_timesync();
|
send_timesync();
|
||||||
_timesync_request.last_sent_ms = tnow;
|
_timesync_request.last_sent_ms = tnow;
|
||||||
|
Loading…
Reference in New Issue
Block a user