From c68f0201d87f4f62fa8c64322877eab9015cfd33 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 5 Sep 2024 19:14:54 +1000 Subject: [PATCH] GCS_MAVLink: reject SET_MESSAGE_INTERVAL commands with p3 set this is going to be used for changing the rate of a specific instance of a message at some stage we have to reject it for now so that when the index is used the GCS is told that their message is invalid in this older version of the autopilot --- libraries/GCS_MAVLink/GCS_Common.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index e6318c9e2a15f..cb0b821b8acd0 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -3029,6 +3029,9 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_aux_function(const mavlink_command_int MAV_RESULT GCS_MAVLINK::handle_command_set_message_interval(const mavlink_command_int_t &packet) { + if (!is_zero(packet.param3)) { + return MAV_RESULT_DENIED; + } return set_message_interval((uint32_t)packet.param1, (int32_t)packet.param2); }