Copter: get_alt_hold_state_D_ms: Add GROUND_IDLE for using_interlock

This commit is contained in:
Leonard Hall
2026-02-01 14:10:52 +10:30
committed by Randy Mackay
parent 55296cc385
commit a6ead9f097

View File

@@ -952,7 +952,8 @@ Mode::AltHoldModeState Mode::get_alt_hold_state_D_ms(float target_climb_rate_ms)
if (target_climb_rate_ms < 0.0f && !copter.ap.using_interlock) {
// the aircraft should move to a ground idle state
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
} else if (copter.ap.using_interlock && !motors->get_interlock()) {
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
} else {
// the aircraft should prepare for imminent take off
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);