Skip to content

Commit

Permalink
GCS_MAVLink: reject SET_MESSAGE_INTERVAL commands with p3 set
Browse files Browse the repository at this point in the history
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
  • Loading branch information
peterbarker committed Sep 7, 2024
1 parent 3dd44dd commit c68f020
Showing 1 changed file with 3 additions and 0 deletions.
3 changes: 3 additions & 0 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}

Expand Down

0 comments on commit c68f020

Please sign in to comment.