diff --git a/libraries/AP_ICEngine/AP_ICEngine.cpp b/libraries/AP_ICEngine/AP_ICEngine.cpp index 92d49f1a67..9be25d26a5 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.cpp +++ b/libraries/AP_ICEngine/AP_ICEngine.cpp @@ -18,6 +18,7 @@ #include #include #include +#include #include "AP_ICEngine.h" extern const AP_HAL::HAL& hal; @@ -126,6 +127,12 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = { // @Description: This configures the slewrate used to adjust the idle setpoint in percentage points per second AP_GROUPINFO("IDLE_SLEW", 14, AP_ICEngine, idle_slew, 1), + // @Param: OPTIONS + // @DisplayName: ICE options + // @Description: Options for ICE control + // @Bitmask: 0:DisableIgnitionRCFailsafe + AP_GROUPINFO("OPTIONS", 15, AP_ICEngine, options, 0), + AP_GROUPEND }; @@ -169,6 +176,11 @@ void AP_ICEngine::update(void) should_run = true; } + if ((options & uint16_t(Options::DISABLE_IGNITION_RC_FAILSAFE)) && AP_Notify::flags.failsafe_radio) { + // user has requested ignition kill on RC failsafe + should_run = false; + } + // switch on current state to work out new state switch (state) { case ICE_OFF: diff --git a/libraries/AP_ICEngine/AP_ICEngine.h b/libraries/AP_ICEngine/AP_ICEngine.h index 1f7b14f7fa..de9061edd1 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.h +++ b/libraries/AP_ICEngine/AP_ICEngine.h @@ -116,6 +116,11 @@ private: // idle governor float idle_governor_integrator; + + enum class Options : uint16_t { + DISABLE_IGNITION_RC_FAILSAFE=(1U<<0), + }; + AP_Int16 options; };