From 88e12869ea1a7d98ed86a15055c91498ba954dac Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Mon, 19 Jul 2021 16:53:50 -0700 Subject: [PATCH] AP_ICEngine: Add a flag to allow starting the engine while disarmed --- libraries/AP_ICEngine/AP_ICEngine.cpp | 18 ++++++++++++++---- libraries/AP_ICEngine/AP_ICEngine.h | 4 +++- 2 files changed, 17 insertions(+), 5 deletions(-) diff --git a/libraries/AP_ICEngine/AP_ICEngine.cpp b/libraries/AP_ICEngine/AP_ICEngine.cpp index b5b85d38dd4c73..1128a076c72f40 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.cpp +++ b/libraries/AP_ICEngine/AP_ICEngine.cpp @@ -238,6 +238,11 @@ void AP_ICEngine::update(void) should_run = true; } else if (start_chan_last_value <= RC_Channel::AUX_PWM_TRIGGER_LOW) { should_run = false; + + // clear the single start flag now that we will be stopping the engine + if (state != ICE_OFF) { + allow_single_start_while_disarmed = false; + } } else if (state != ICE_OFF) { should_run = true; } @@ -248,8 +253,10 @@ void AP_ICEngine::update(void) } if (option_set(Options::NO_RUNNING_WHILE_DISARMED) && !hal.util->get_soft_armed()) { - // disable the engine if disarmed - should_run = false; + if (!allow_single_start_while_disarmed) { + // no starting while disarmed + should_run = false; + } } #if HAL_PARACHUTE_ENABLED @@ -468,11 +475,15 @@ bool AP_ICEngine::throttle_override(float &percentage, const float base_throttle /* handle DO_ENGINE_CONTROL messages via MAVLink or mission */ -bool AP_ICEngine::engine_control(float start_control, float cold_start, float height_delay) +bool AP_ICEngine::engine_control(float start_control, float cold_start, float height_delay, float allow_disarmed) { if (!enable) { return false; } + + // always update the start while disarmed flag + allow_single_start_while_disarmed = is_equal(allow_disarmed, 1.0f); + if (start_control <= 0) { state = ICE_OFF; return true; @@ -576,7 +587,6 @@ void AP_ICEngine::update_idle_governor(int8_t &min_throttle) #endif // AP_RPM_ENABLED } - // singleton instance. Should only ever be set in the constructor. AP_ICEngine *AP_ICEngine::_singleton; namespace AP { diff --git a/libraries/AP_ICEngine/AP_ICEngine.h b/libraries/AP_ICEngine/AP_ICEngine.h index 1c243dd88fa2c5..9aac72ddc69ec2 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.h +++ b/libraries/AP_ICEngine/AP_ICEngine.h @@ -52,7 +52,7 @@ class AP_ICEngine { ICE_State get_state(void) const { return !enable?ICE_DISABLED:state; } // handle DO_ENGINE_CONTROL messages via MAVLink or mission - bool engine_control(float start_control, float cold_start, float height_delay); + bool engine_control(float start_control, float cold_start, float height_delay, float allow_disarmed); // update min throttle for idle governor void update_idle_governor(int8_t &min_throttle); @@ -138,6 +138,8 @@ class AP_ICEngine { // we are waiting for valid height data bool height_pending:1; + bool allow_single_start_while_disarmed; + // idle governor float idle_governor_integrator;