mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Copter: accept MISSION_START commands when vehicle is disarmed
This commit is contained in:
parent
32fb3cb929
commit
2d9c6867f4
@ -796,8 +796,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
|
||||
|
||||
#if MODE_AUTO_ENABLED == ENABLED
|
||||
case MAV_CMD_MISSION_START:
|
||||
if (copter.motors->armed() &&
|
||||
copter.set_mode(Mode::Number::AUTO, ModeReason::GCS_COMMAND)) {
|
||||
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) {
|
||||
copter.mode_auto.mission.start_or_resume();
|
||||
|
Loading…
Reference in New Issue
Block a user