ArduCopter: emit MAV_RESULT_DENIED if start/stop item passed to MAV_CMD_MISSION_START

This commit is contained in:
Peter Barker 2024-08-16 22:45:50 +10:00 committed by Andrew Tridgell
parent b1ae1591fb
commit 6b2f3ff591
1 changed files with 4 additions and 0 deletions

View File

@ -960,6 +960,10 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_CHANGE_SPEED(const mavlink_comm
#if MODE_AUTO_ENABLED == ENABLED
MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_MISSION_START(const mavlink_command_int_t &packet)
{
if (!is_zero(packet.param1) || !is_zero(packet.param2)) {
// first-item/last item not supported
return MAV_RESULT_DENIED;
}
if (copter.set_mode(Mode::Number::AUTO, ModeReason::GCS_COMMAND)) {
copter.set_auto_armed(true);
if (copter.mode_auto.mission.state() != AP_Mission::MISSION_RUNNING) {