Browse Source

Copter: accept MISSION_START commands when vehicle is disarmed

zr-v5.1
Randy Mackay 4 years ago
parent
commit
2d9c6867f4
  1. 3
      ArduCopter/GCS_Mavlink.cpp

3
ArduCopter/GCS_Mavlink.cpp

@ -796,8 +796,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_ @@ -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…
Cancel
Save