From af3992d7950ca56994d21267825c5a65160c8d84 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 26 Sep 2023 15:56:43 +1000 Subject: [PATCH] Plane: handle DO_GO_AROUND as both COMMAND_LONG and COMMAND_INT --- ArduPlane/GCS_Mavlink.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 5000122129..15593a66fd 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1002,6 +1002,9 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in return handle_command_DO_VTOL_TRANSITION(packet); #endif + case MAV_CMD_DO_GO_AROUND: + return plane.trigger_land_abort(packet.param1) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED; + default: return GCS_MAVLINK::handle_command_int_packet(packet, msg); } @@ -1061,9 +1064,6 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l } return MAV_RESULT_FAILED; - case MAV_CMD_DO_GO_AROUND: - return plane.trigger_land_abort(packet.param1) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED; - default: return GCS_MAVLINK::handle_command_long_packet(packet, msg); }