From c47205e26d16908935aff7dee4760438cc9d39ca Mon Sep 17 00:00:00 2001 From: Bob Long Date: Thu, 26 Sep 2024 09:38:27 +1000 Subject: [PATCH 1/3] Revert "AP_ICEngine : enable starter when soft_armed" This reverts commits ce981b48580680493b293497db4084dbcaa61cb6 and 791860a1151788a1289d8b786e2623ccae03cbfa --- libraries/AP_ICEngine/AP_ICEngine.cpp | 7 +------ 1 file changed, 1 insertion(+), 6 deletions(-) diff --git a/libraries/AP_ICEngine/AP_ICEngine.cpp b/libraries/AP_ICEngine/AP_ICEngine.cpp index 4f753713f8..e4ba1a55e1 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.cpp +++ b/libraries/AP_ICEngine/AP_ICEngine.cpp @@ -402,12 +402,7 @@ void AP_ICEngine::update(void) case ICE_STARTING: set_ignition(true); - - if (hal.util->get_soft_armed() || allow_throttle_while_disarmed()) { - set_starter(true); - } else { - set_starter(false); - } + set_starter(true); if (starter_start_time_ms == 0) { starter_start_time_ms = now; From 794a3b75f97c30151c5258337bea05f6e4e4dbf8 Mon Sep 17 00:00:00 2001 From: Bob Long Date: Mon, 23 Sep 2024 16:47:40 +1000 Subject: [PATCH 2/3] 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; From f9a6dc9bab67d299c645a00137e111063bd99c73 Mon Sep 17 00:00:00 2001 From: Bob Long Date: Mon, 23 Sep 2024 17:07:20 +1000 Subject: [PATCH 3/3] AP_ICEngine: clarify ICE_OPTIONS:2 description --- libraries/AP_ICEngine/AP_ICEngine.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_ICEngine/AP_ICEngine.cpp b/libraries/AP_ICEngine/AP_ICEngine.cpp index f81645001a..f9148d933b 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.cpp +++ b/libraries/AP_ICEngine/AP_ICEngine.cpp @@ -145,7 +145,7 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = { // @Param: OPTIONS // @DisplayName: ICE options // @Description: Options for ICE control. The Disable ignition in RC failsafe option will cause the ignition to be set off on any R/C failsafe. If Throttle while disarmed is set then throttle control will be allowed while disarmed for planes when in MANUAL mode. If disable while disarmed is set the engine will not start while the vehicle is disarmed unless overriden by the MAVLink DO_ENGINE_CONTROL command. - // @Bitmask: 0:Disable ignition in RC failsafe,1:Disable redline governor,2:Throttle while disarmed,3:Disable while disarmed + // @Bitmask: 0:Disable ignition in RC failsafe,1:Disable redline governor,2:Throttle control in MANUAL while disarmed with safety off,3:Disable while disarmed AP_GROUPINFO("OPTIONS", 15, AP_ICEngine, options, 0), // @Param: STARTCHN_MIN