GCS_MAVLink: schedule current waypoint rather than immediate send

This message may not fit in our outgoing buffer
This commit is contained in:
Peter Barker 2021-02-18 21:28:33 +11:00 committed by Andrew Tridgell
parent 0e76006dc5
commit c5e62eb6e4

View File

@ -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);
}
}