AP_ICEngine: added ICE_OPTIONS

option to kill ignition on RC failsafe. This is needed for some RC
model clubs
This commit is contained in:
Andrew Tridgell 2019-11-30 11:14:17 +11:00
parent 132a1623d3
commit 5098e3f79e
2 changed files with 17 additions and 0 deletions

View File

@ -18,6 +18,7 @@
#include <GCS_MAVLink/GCS.h> #include <GCS_MAVLink/GCS.h>
#include <AP_AHRS/AP_AHRS.h> #include <AP_AHRS/AP_AHRS.h>
#include <AP_Scheduler/AP_Scheduler.h> #include <AP_Scheduler/AP_Scheduler.h>
#include <AP_Notify/AP_Notify.h>
#include "AP_ICEngine.h" #include "AP_ICEngine.h"
extern const AP_HAL::HAL& hal; 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 // @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), 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 AP_GROUPEND
}; };
@ -169,6 +176,11 @@ void AP_ICEngine::update(void)
should_run = true; 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 on current state to work out new state
switch (state) { switch (state) {
case ICE_OFF: case ICE_OFF:

View File

@ -116,6 +116,11 @@ private:
// idle governor // idle governor
float idle_governor_integrator; float idle_governor_integrator;
enum class Options : uint16_t {
DISABLE_IGNITION_RC_FAILSAFE=(1U<<0),
};
AP_Int16 options;
}; };