Skip to content

Commit

Permalink
scripting: Added generator cutoff for EFI Skypower
Browse files Browse the repository at this point in the history
  • Loading branch information
Georacer committed Dec 16, 2024
1 parent aec7cc2 commit d29f677
Show file tree
Hide file tree
Showing 2 changed files with 24 additions and 1 deletion.
19 changes: 18 additions & 1 deletion 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, 15), 'could not add EFI_SP param table')
assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 16), 'could not add EFI_SP param table')

--[[
// @Param: EFI_SP_ENABLE
Expand Down Expand Up @@ -207,6 +207,16 @@ 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
// @User: Standard
// @Units: %
--]]
local EFI_SP_LOAD_LIM = bind_add_param('LOAD_LIM', 15, 0)

if EFI_SP_ENABLE:get() == 0 then
gcs:send_text(0, string.format("EFISP: disabled"))
return
Expand Down Expand Up @@ -547,6 +557,13 @@ local function engine_control(_driver)
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
generator_started = false
gcs:send_text(0, string.format("EFISP: stopping generator"))
Expand Down
6 changes: 6 additions & 0 deletions libraries/AP_Scripting/drivers/EFI_SkyPower.md
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,12 @@ 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.

# Operation

This driver should be loaded by placing the lua script in the
Expand Down

0 comments on commit d29f677

Please sign in to comment.