AP_ICEngine: Add an option to disable starting while disarmed

This commit is contained in:
Michael du Breuil 2023-09-20 10:08:24 -07:00 committed by Tom Pittenger
parent 4381c17cb2
commit e8deb491de
2 changed files with 12 additions and 6 deletions

View File

@ -142,8 +142,8 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = {
// @Param: OPTIONS
// @DisplayName: ICE options
// @Description: Options for ICE control. The DisableIgnitionRCFailsafe option will cause the ignition to be set off on any R/C failsafe. If ThrottleWhileDisarmed is set then throttle control will be allowed while disarmed for planes when in MANUAL mode.
// @Bitmask: 0:DisableIgnitionRCFailsafe,1:DisableRedineGovernor,2:ThrottleWhileDisarmed
// @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.
// @Bitmask: 0:Disable ignition in RC failsafe,1:Disable redine governor,2:ThrottleWhileDisarmed,3:Disable while disarmed
AP_GROUPINFO("OPTIONS", 15, AP_ICEngine, options, 0),
// @Param: STARTCHN_MIN
@ -247,6 +247,11 @@ void AP_ICEngine::update(void)
should_run = false;
}
if (option_set(Options::NO_RUNNING_WHILE_DISARMED) && !hal.util->get_soft_armed()) {
// disable the engine if disarmed
should_run = false;
}
#if HAL_PARACHUTE_ENABLED
// Stop on parachute deployment
AP_Parachute *parachute = AP::parachute();
@ -558,7 +563,7 @@ void AP_ICEngine::update_idle_governor(int8_t &min_throttle)
// Calculate the change per loop to achieve the desired slew rate of 1 percent per second
static const float idle_setpoint_step = idle_slew * AP::scheduler().get_loop_period_s();
// Update Integrator
// Update Integrator
if (underspeed) {
idle_governor_integrator += idle_setpoint_step;
} else {

View File

@ -142,9 +142,10 @@ private:
float idle_governor_integrator;
enum class Options : uint16_t {
DISABLE_IGNITION_RC_FAILSAFE=(1U<<0),
DISABLE_REDLINE_GOVERNOR = (1U << 1),
THROTTLE_WHILE_DISARMED = (1U << 2),
DISABLE_IGNITION_RC_FAILSAFE = (1U << 0),
DISABLE_REDLINE_GOVERNOR = (1U << 1),
THROTTLE_WHILE_DISARMED = (1U << 2),
NO_RUNNING_WHILE_DISARMED = (1U << 3),
};
AP_Int16 options;