Copter: implement disarm on land based on MIS_OPTIONS

only continue with mission if MIS_OPTIONS bit is set
This commit is contained in:
Andrew Tridgell 2020-03-04 14:29:14 +11:00 committed by Randy Mackay
parent 7c49723f19
commit e673bd8909

View File

@ -1521,6 +1521,16 @@ bool ModeAuto::verify_land()
case State::Descending: case State::Descending:
// rely on THROTTLE_LAND mode to correctly update landing status // rely on THROTTLE_LAND mode to correctly update landing status
retval = copter.ap.land_complete && (motors->get_spool_state() == AP_Motors::SpoolState::GROUND_IDLE); retval = copter.ap.land_complete && (motors->get_spool_state() == AP_Motors::SpoolState::GROUND_IDLE);
if (retval && !mission.continue_after_land() && copter.motors->armed()) {
/*
we want to stop mission processing on land
completion. Disarm now, then return false. This
leaves mission state machine in the current NAV_LAND
mission item. After disarming the mission will reset
*/
copter.arming.disarm(AP_Arming::Method::LANDED);
retval = false;
}
break; break;
default: default: