diff --git a/libraries/GCS_MAVLink/MissionItemProtocol.cpp b/libraries/GCS_MAVLink/MissionItemProtocol.cpp index 5667578ad064e..69a5eab7dd78c 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol.cpp +++ b/libraries/GCS_MAVLink/MissionItemProtocol.cpp @@ -315,7 +315,7 @@ void MissionItemProtocol::handle_mission_item(const mavlink_message_t &msg, cons return; } // if we have enough space, then send the next WP request immediately - if (HAVE_PAYLOAD_SPACE(link->get_chan(), MISSION_REQUEST)) { + if (HAVE_PAYLOAD_SPACE(link->get_chan(), MISSION_REQUEST_INT)) { queued_request_send(); } else { link->send_message(next_item_ap_message_id()); @@ -368,8 +368,8 @@ void MissionItemProtocol::queued_request_send() INTERNAL_ERROR(AP_InternalError::error_t::gcs_bad_missionprotocol_link); return; } - CHECK_PAYLOAD_SIZE2_VOID(link->get_chan(), MISSION_REQUEST); - mavlink_msg_mission_request_send( + CHECK_PAYLOAD_SIZE2_VOID(link->get_chan(), MISSION_REQUEST_INT); + mavlink_msg_mission_request_int_send( link->get_chan(), dest_sysid, dest_compid,