mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
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:
parent
1f30ae3076
commit
63e42e194f
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user