Skip to content

Commit

Permalink
GCS_MAVLink: Support requesting MESSAGE_INTERVAL via REQUEST_MESSAGE cmd
Browse files Browse the repository at this point in the history
The old method of using MAV_CMD_GET_MESSAGE_INTERVAL is deprecated.
  • Loading branch information
nexton-winjeel committed Oct 8, 2024
1 parent 5f67904 commit 7693a16
Showing 1 changed file with 6 additions and 0 deletions.
6 changes: 6 additions & 0 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down

0 comments on commit 7693a16

Please sign in to comment.