mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: implement disarm on land based on MIS_OPTIONS
only continue with mission if MIS_OPTIONS bit is set
This commit is contained in:
parent
7c49723f19
commit
e673bd8909
@ -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:
|
||||||
|
Loading…
Reference in New Issue
Block a user