Skip to content

Commit

Permalink
Scripting: Updated Skypower EFI and generator driver
Browse files Browse the repository at this point in the history
- Documented existing parameters
- Implemented logic to turn off the generator under high engine demand
  • Loading branch information
Georacer committed Dec 18, 2024
1 parent d29f677 commit aed0ca8
Show file tree
Hide file tree
Showing 2 changed files with 167 additions and 27 deletions.
137 changes: 115 additions & 22 deletions libraries/AP_Scripting/drivers/EFI_SkyPower.lua
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ end
local efi_backend = nil

-- Setup EFI Parameters
assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 16), '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
Expand Down Expand Up @@ -208,14 +208,50 @@ local EFI_SP_GEN_CTRL = bind_add_param('GEN_CRTL', 13, 1)
local EFI_SP_RST_TIME = bind_add_param('RST_TIME', 14, 2)

--[[
// @Param: EFI_SP_LOAD_LIM
// @DisplayName: SkyPower EFI generator cutoff engine load
// @Description: SkyPower EFI generator cutoff engine load. If the engine target load is above this limit, the generator will be turned off, to alleviate the engine load. To disable this feature set this value to zero.
// @Range: 0 100
// @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
// @Units: %
--]]
local EFI_SP_LOAD_LIM = bind_add_param('LOAD_LIM', 15, 0)
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
gcs:send_text(0, string.format("EFISP: disabled"))
Expand Down Expand Up @@ -280,7 +316,11 @@ local function engine_control(_driver)
local last_telem_update = get_time_sec()
local last_log_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 generator_must_run = false
local generator_started = false
local engine_start_t = 0.0
local last_throttle = 0.0
Expand Down Expand Up @@ -551,30 +591,83 @@ local function engine_control(_driver)
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
function self.update_generator()
if EFI_SP_GEN_CTRL:get() == 0 then
return
end
local gen_state = rc:get_aux_cached(EFI_SP_GEN_FN:get())
-- Stop the generator if the engine is working at high load.
local load_limit = EFI_SP_LOAD_LIM:get()
if load_limit >0 then
if target_load > load_limit then
gen_state = 0
end
end
if gen_state == 0 and generator_started then
if EFI_SP_GEN_CTRL:get() == 0 then
return
end

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
gcs:send_text(0, string.format("EFISP: stopping generator"))
self.send_generator_stop()
end
if gen_state == 2 and not generator_started then
lastSwitchTime_ms = millis()
end
if generator_must_run and not generator_started then
generator_started = true
gcs:send_text(0, string.format("EFISP: starting generator"))
self.send_generator_start()
end
lastSwitchTime_ms = millis()
end
end


-- update throttle output
function self.update_throttle()
Expand Down
57 changes: 52 additions & 5 deletions libraries/AP_Scripting/drivers/EFI_SkyPower.md
Original file line number Diff line number Diff line change
Expand Up @@ -60,11 +60,58 @@ 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
the engine.

## EFI_SP_LOAD_LIM
This is a threshold on the target engine load. Past this limit, the generator
will be stopped, in order to reduce the engine load and route more power to
the thruster.
To disable this feature set this value to zero.
## 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

Expand Down

0 comments on commit aed0ca8

Please sign in to comment.