mavlink_receiver: only switch outgoing MAVLink version to 2 if it was 1 before

to avoid the message that comes with it being spammed.
This commit is contained in:
Matthias Grob 2025-10-14 17:36:48 +02:00
parent 4842c542b8
commit 7706aae67d

View File

@ -3229,7 +3229,8 @@ MavlinkReceiver::run()
if (mavlink_parse_char(_mavlink.get_channel(), buf[i], &msg, &_status)) {
// If we receive a complete MAVLink 2 packet, also switch the outgoing protocol version
if (!(_mavlink.get_status()->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1)) {
if (!(_mavlink.get_status()->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1)
&& (_mavlink.get_status()->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1)) {
PX4_INFO("Upgrade to MAVLink v2 because of incoming packet");
_mavlink.set_protocol_version(2);
}