From 7693a1620727eb9e353d1dd4935de307ae5f4cb4 Mon Sep 17 00:00:00 2001 From: Nick Exton Date: Wed, 9 Oct 2024 10:44:29 +1100 Subject: [PATCH] GCS_MAVLink: Support requesting MESSAGE_INTERVAL via REQUEST_MESSAGE cmd The old method of using MAV_CMD_GET_MESSAGE_INTERVAL is deprecated. --- libraries/GCS_MAVLink/GCS_Common.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 743b8b7e61d300..432be6acf81e6c 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -3195,6 +3195,12 @@ uint8_t GCS::get_channel_from_port_number(uint8_t port_num) MAV_RESULT GCS_MAVLINK::handle_command_request_message(const mavlink_command_int_t &packet) { const uint32_t mavlink_id = (uint32_t)packet.param1; + + if (mavlink_id == MAVLINK_MSG_ID_MESSAGE_INTERVAL) { + const mavlink_command_int_t msg_interval_cmd = { packet.param2, }; + return handle_command_get_message_interval(msg_interval_cmd); + } + const ap_message id = mavlink_id_to_ap_message_id(mavlink_id); if (id == MSG_LAST) { return MAV_RESULT_FAILED;