From fe93a08b0376ed90641d6d1312f1a99b511438e1 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Sat, 31 Jan 2026 14:07:54 +1030 Subject: [PATCH] Copter: Heli: Handle GROUND_IDLE in Stab and Acro --- ArduCopter/mode_acro_heli.cpp | 2 ++ ArduCopter/mode_stabilize_heli.cpp | 2 ++ 2 files changed, 4 insertions(+) diff --git a/ArduCopter/mode_acro_heli.cpp b/ArduCopter/mode_acro_heli.cpp index b0637d6e5d..ffa7a6a135 100644 --- a/ArduCopter/mode_acro_heli.cpp +++ b/ArduCopter/mode_acro_heli.cpp @@ -37,6 +37,8 @@ void ModeAcro_Heli::run() if (!motors->armed()) { // Motors should be Stopped motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN); + } else if (!motors->get_interlock()) { + motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE); } else { // heli will not let the spool state progress to THROTTLE_UNLIMITED until motor interlock is enabled motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); diff --git a/ArduCopter/mode_stabilize_heli.cpp b/ArduCopter/mode_stabilize_heli.cpp index 5813ceb68a..deb5bbfac7 100644 --- a/ArduCopter/mode_stabilize_heli.cpp +++ b/ArduCopter/mode_stabilize_heli.cpp @@ -44,6 +44,8 @@ void ModeStabilize_Heli::run() if (!motors->armed()) { // Motors should be Stopped motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN); + } else if (!motors->get_interlock()) { + motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE); } else { // heli will not let the spool state progress to THROTTLE_UNLIMITED until motor interlock is enabled motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);