GCS_MAVLink: send correct mission_ack result type

has no effect since the two typedef enums equated to same value
This commit is contained in:
Tom Pittenger 2018-04-16 16:52:38 -07:00 committed by Randy Mackay
parent 1f30ae3076
commit 63e42e194f
1 changed files with 1 additions and 1 deletions

View File

@ -533,7 +533,7 @@ void GCS_MAVLINK::handle_mission_clear_all(AP_Mission &mission, mavlink_message_
// clear all waypoints
if (mission.clear()) {
// send ack
mavlink_msg_mission_ack_send(chan, msg->sysid, msg->compid, MAV_RESULT_ACCEPTED,
mavlink_msg_mission_ack_send(chan, msg->sysid, msg->compid, MAV_MISSION_ACCEPTED,
MAV_MISSION_TYPE_MISSION);
}else{
// send nack