From 3a166247c1fa075da7ae09172067e12424fa5484 Mon Sep 17 00:00:00 2001 From: Ludovic Vanasse Date: Tue, 25 Apr 2023 17:48:42 -0400 Subject: [PATCH] Add condition for Iridium mode to not send params change after a time In the mavlink_receiver code, after a while it will try to resend some parameter update through the MAVLink instance. But for Iridium links those are not a good idea. So this adds a condition that prevent the sending if the MAVLink instance is in Iridium mode. Related to issue #21496 --- src/modules/mavlink/mavlink_receiver.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index d0a0791d12..767ec7d02f 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -3267,7 +3267,9 @@ MavlinkReceiver::run() _mission_manager.check_active_mission(); _mission_manager.send(); - _parameters_manager.send(); + if (_mavlink->get_mode() != Mavlink::MAVLINK_MODE::MAVLINK_MODE_IRIDIUM) { + _parameters_manager.send(); + } if (_mavlink->ftp_enabled()) { _mavlink_ftp.send();