AP_ICEngine: added option to force low throttle on engine off

this fixes an issue with EFI engines that use low throttle demand to
stop the engine, instead of using an ignition channel. This option
needs to be set on these aircraft to prevent the idle governor or the
fwd throttle integrator in quadplanes from keeping the engine on when
the pilot asks for it to be off.
This commit is contained in:
Andrew Tridgell 2022-07-10 16:07:52 +10:00 committed by Randy Mackay
parent 85acba21e2
commit ef473a4372
2 changed files with 10 additions and 2 deletions

View File

@ -211,7 +211,7 @@ void AP_ICEngine::update(void)
should_run = true;
}
if ((options & uint16_t(Options::DISABLE_IGNITION_RC_FAILSAFE)) && AP_Notify::flags.failsafe_radio) {
if (option_set(Options::DISABLE_IGNITION_RC_FAILSAFE) && AP_Notify::flags.failsafe_radio) {
// user has requested ignition kill on RC failsafe
should_run = false;
}
@ -340,9 +340,13 @@ bool AP_ICEngine::throttle_override(uint8_t &percentage)
}
if (state == ICE_STARTING || state == ICE_START_DELAY) {
percentage = (uint8_t)start_percent.get();
percentage = start_percent.get();
return true;
} else if (state != ICE_RUNNING && hal.util->get_soft_armed()) {
percentage = 0;
return true;
}
return false;
}

View File

@ -125,6 +125,10 @@ private:
};
AP_Int16 options;
bool option_set(Options option) const {
return (options & uint16_t(option)) != 0;
}
// start_chan debounce
uint16_t start_chan_last_value = 1500;
uint32_t start_chan_last_ms;