mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
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
This commit is contained in:
parent
b21ad6af14
commit
3a166247c1
@ -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();
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user