From c5e62eb6e4ddcef180b3ff660cc31d676ec312e3 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 18 Feb 2021 21:28:33 +1100 Subject: [PATCH] GCS_MAVLink: schedule current waypoint rather than immediate send This message may not fit in our outgoing buffer --- libraries/GCS_MAVLink/GCS_Common.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index a89a5ed13d..ffe5611b07 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -517,7 +517,7 @@ void GCS_MAVLINK::handle_mission_set_current(AP_Mission &mission, const mavlink_ // set current command if (mission.set_current_cmd(packet.seq)) { - mavlink_msg_mission_current_send(chan, packet.seq); + send_message(MSG_CURRENT_WAYPOINT); } }