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
This commit is contained in:
Peter Barker 2024-09-05 19:14:54 +10:00 committed by Andrew Tridgell
parent 3c9965f5e5
commit 78f0175e20
1 changed files with 3 additions and 0 deletions

View File

@ -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);
}