From 794a3b75f97c30151c5258337bea05f6e4e4dbf8 Mon Sep 17 00:00:00 2001 From: Bob Long Date: Mon, 23 Sep 2024 16:47:40 +1000 Subject: [PATCH] AP_ICEngine: don't run engine with safety engaged --- libraries/AP_ICEngine/AP_ICEngine.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_ICEngine/AP_ICEngine.cpp b/libraries/AP_ICEngine/AP_ICEngine.cpp index e4ba1a55e1..f81645001a 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.cpp +++ b/libraries/AP_ICEngine/AP_ICEngine.cpp @@ -356,7 +356,7 @@ void AP_ICEngine::update(void) // reset initial height while disarmed initial_height = -pos.z; } - } else if (idle_percent <= 0 && !option_set(Options::THROTTLE_WHILE_DISARMED)) { + } else if (idle_percent <= 0 && !allow_throttle_while_disarmed()) { // force ignition off when disarmed state = ICE_OFF; } @@ -438,7 +438,7 @@ bool AP_ICEngine::throttle_override(float &percentage, const float base_throttle idle_percent > percentage) { percentage = idle_percent; - if (option_set(Options::THROTTLE_WHILE_DISARMED) && !hal.util->get_soft_armed()) { + if (allow_throttle_while_disarmed() && !hal.util->get_soft_armed()) { percentage = MAX(percentage, base_throttle); } return true; @@ -479,7 +479,7 @@ bool AP_ICEngine::throttle_override(float &percentage, const float base_throttle #endif // AP_RPM_ENABLED // if THROTTLE_WHILE_DISARMED is set then we use the base_throttle, allowing the pilot to control throttle while disarmed - if (option_set(Options::THROTTLE_WHILE_DISARMED) && !hal.util->get_soft_armed() && + if (allow_throttle_while_disarmed() && !hal.util->get_soft_armed() && base_throttle > percentage) { percentage = base_throttle; return true;