Plane: handle DO_GO_AROUND as both COMMAND_LONG and COMMAND_INT

This commit is contained in:
Peter Barker 2023-09-26 15:56:43 +10:00 committed by Andrew Tridgell
parent 8cfdf10cf1
commit af3992d795
1 changed files with 3 additions and 3 deletions

View File

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