Scripting: Updated Skypower EFI and generator driver

- Documented existing parameters
- Implemented logic to turn off the generator under high engine demand
This commit is contained in:
George Zogopoulos 2024-12-16 18:10:46 +01:00
parent aec7cc24d1
commit 6b38eeff29
2 changed files with 172 additions and 9 deletions

View File

@ -74,7 +74,7 @@ end
local efi_backend = nil local efi_backend = nil
-- Setup EFI Parameters -- Setup EFI Parameters
assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 15), 'could not add EFI_SP param table') assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 19), 'could not add EFI_SP param table')
--[[ --[[
// @Param: EFI_SP_ENABLE // @Param: EFI_SP_ENABLE
@ -207,6 +207,52 @@ local EFI_SP_GEN_CTRL = bind_add_param('GEN_CRTL', 13, 1)
--]] --]]
local EFI_SP_RST_TIME = bind_add_param('RST_TIME', 14, 2) local EFI_SP_RST_TIME = bind_add_param('RST_TIME', 14, 2)
--[[
// @Param: EFI_SP_GEN_AUTO
// @DisplayName: Enable automatic EFI Generator on/off logic
// @Description: Enable automatic EFI Generator on/off logic.
// @Values: 0:Disabled,1:Enabled
// @User: Standard
--]]
local EFI_SP_GEN_AUTO = bind_add_param('GEN_AUTO', 15, 0)
--[[
// @Param: EFI_SP_GEN_MIN
// @DisplayName: EFI Generator Min Load
// @Description: EFI Generator will switch ON if engine load is less than this parameter for EFI_SP_GEN_TIMER seconds. Applies when EFI_SP_GEN_AUTO=1.
// @Range: 20 50
// @User: Standard
--]]
local EFI_SP_GEN_MIN = bind_add_param('GEN_MIN', 16, 35)
--[[
// @Param: EFI_SP_GEN_MAX
// @DisplayName: EFI Generator Max Load
// @Description: EFI Generator will switch OFF if engine load is more than this parameter for EFI_SP_GEN_TIMER seconds. Applies when EFI_SP_GEN_AUTO=1.
// @Range: 40 80
// @User: Standard
--]]
local EFI_SP_GEN_MAX = bind_add_param('GEN_MAX', 17, 65)
--[[
// @Param: EFI_SP_GEN_TIMER
// @DisplayName: EFI Generator Switch Timer
// @Description: EFI Generator load has to be greater than EFI_SP_GEN_MAX or less than EFI_SP_GEN_MAX for this many seconds for a switch to happen. Applies when EFI_SP_GEN_AUTO=1.
// @Range: 0 10
// @User: Standard
--]]
local EFI_SP_GEN_TIMER = bind_add_param('GEN_TIMER', 18, 2)
--[[
// @Param: EFI_SP_GEN_TOUT
// @DisplayName: EFI Generator Switch Timeout
// @Description: EFI Generator will not be switched on/off if it was previously switched within this many seconds. Applies when EFI_SP_GEN_AUTO=1.
// @Range: 0 10
// @User: Standard
--]]
local EFI_SP_GEN_TOUT = bind_add_param('GEN_TOUT', 19, 5)
if EFI_SP_ENABLE:get() == 0 then if EFI_SP_ENABLE:get() == 0 then
gcs:send_text(0, string.format("EFISP: disabled")) gcs:send_text(0, string.format("EFISP: disabled"))
return return
@ -270,7 +316,11 @@ local function engine_control(_driver)
local last_telem_update = get_time_sec() local last_telem_update = get_time_sec()
local last_log_t = get_time_sec() local last_log_t = get_time_sec()
local last_stop_message_t = get_time_sec() local last_stop_message_t = get_time_sec()
local lastSwitchTime_ms = uint32_t(0) -- Time (in ms) when the generator was last switched on or off.
local aboveThresholdTime_ms = 0 -- Time (in ms) engine load has remained above the threshold
local belowThresholdTime_ms = 0 -- Time (in ms) engine load has remained below the threshold
local engine_started = false local engine_started = false
local generator_must_run = false
local generator_started = false local generator_started = false
local engine_start_t = 0.0 local engine_start_t = 0.0
local last_throttle = 0.0 local last_throttle = 0.0
@ -541,23 +591,83 @@ local function engine_control(_driver)
end end
end end
-- Function to check the EFI engine load
function self.checkEngineLoad()
local update_rate_ms = 1000 / EFI_SP_UPDATE_HZ:get()
local loadPercent = efi_state:engine_load_percent()
if loadPercent >= EFI_SP_GEN_MAX:get() then
aboveThresholdTime_ms = aboveThresholdTime_ms + update_rate_ms
belowThresholdTime_ms = 0
elseif loadPercent <= EFI_SP_GEN_MIN:get() then
belowThresholdTime_ms = belowThresholdTime_ms + update_rate_ms
aboveThresholdTime_ms = 0
else
aboveThresholdTime_ms = 0
belowThresholdTime_ms = 0
end
if self.enoughSwitchTimePassed() then
if aboveThresholdTime_ms >= EFI_SP_GEN_TIMER:get()*1000 then
generator_must_run = false -- Switch off the generator
elseif belowThresholdTime_ms >= EFI_SP_GEN_TIMER:get()*1000 then
generator_must_run = true -- Switch on the generator
end
end
end
-- Function to check if enough time has passed since the last switch
function self.enoughSwitchTimePassed()
local elapsedTime = millis() - lastSwitchTime_ms
return elapsedTime >= EFI_SP_GEN_TOUT:get()*1000
end
-- Apply autoswitch logic to the target generator state.
function self.generator_autoswitch()
if not efi_state:engine_load_percent() then
return
end
if efi_state:engine_load_percent() == 0 or millis() - efi_state:last_updated_ms() > 200 then
-- Probably no data
return
end
self.checkEngineLoad()
end
-- update generator control -- update generator control
function self.update_generator() function self.update_generator()
if EFI_SP_GEN_CTRL:get() == 0 then if EFI_SP_GEN_CTRL:get() == 0 then
return return
end end
local gen_state = rc:get_aux_cached(EFI_SP_GEN_FN:get())
if gen_state == 0 and generator_started then local gen_state = rc:get_aux_cached(EFI_SP_GEN_FN:get())
if gen_state == 0 then
generator_must_run = false
elseif gen_state == 2 then
generator_must_run = true
end
-- Apply automatic generator switching logic.
if EFI_SP_GEN_AUTO:get() == 1 then
self.generator_autoswitch()
end
if not generator_must_run and generator_started then
generator_started = false generator_started = false
gcs:send_text(0, string.format("EFISP: stopping generator")) gcs:send_text(0, string.format("EFISP: stopping generator"))
self.send_generator_stop() self.send_generator_stop()
end lastSwitchTime_ms = millis()
if gen_state == 2 and not generator_started then end
if generator_must_run and not generator_started then
generator_started = true generator_started = true
gcs:send_text(0, string.format("EFISP: starting generator")) gcs:send_text(0, string.format("EFISP: starting generator"))
self.send_generator_start() self.send_generator_start()
end lastSwitchTime_ms = millis()
end
end end
-- update throttle output -- update throttle output
function self.update_throttle() function self.update_throttle()

View File

@ -60,6 +60,59 @@ driver will monitor engine RPM when the engine is started and if it
drops below this value then an engine start will be sent to restart drops below this value then an engine start will be sent to restart
the engine. the engine.
## EFI_SP_TLM_RT
Telemetry rate. This is the rate at which extra telemetry values
are sent to the GCS.
## EFI_SP_LOG_RT
Log rate. This is the rate at which extra logging of the SkyPower EFI is
performed.
## EFI_SP_ST_DISARM
This controls if starting the engine while disarmed is allowed. 0:Disabled,1:Enabled.
## EFI_SP_MODEL
SkyPower EFI ECU model. 0:SRE_180, 1:SP_275.
## EFI_SP_GEN_CTRL
Enable generator control. 0:Disabled,1:Enabled
## EFI_SP_RST_TIME
SkyPower EFI restart time. If engine should be running and it has stopped for
this amount of time then auto-restart. To disable this feature set this value to zero.
## EFI_SP_GEN_AUTO
Enable automatic EFI Generator on/off logic. This will automatically switch
the generator on or off, depending on the engine load.
## EFI_SP_GEN_MIN
EFI Generator will switch ON if engine load is less than this parameter for
`EFI_SP_GEN_TIMER` seconds. Applies when `EFI_SP_GEN_AUTO`=1.
## EFI_SP_GEN_MAX
EFI Generator will switch OFF if engine load is more than this parameter for
`EFI_SP_GEN_TIMER` seconds. Applies when `EFI_SP_GEN_AUTO`=1.
## EFI_SP_GEN_TIMER
EFI Generator load has to be greater than `EFI_SP_GEN_MAX` or less than
`EFI_SP_GEN_MAX` for this many seconds for a switch to happen. Applies when
`EFI_SP_GEN_AUTO`=1.
## EFI_SP_GEN_TOUT
EFI Generator will not be switched on/off if it was previously switched within
this many seconds. Applies when `EFI_SP_GEN_AUTO`=1.
# Operation # Operation
This driver should be loaded by placing the lua script in the This driver should be loaded by placing the lua script in the