Skip to content

Commit

Permalink
AP_Scripting: update SkyPower driver to support new model
Browse files Browse the repository at this point in the history
support SP-275 dual-cylinder ECU
  • Loading branch information
tridge committed Dec 10, 2023
1 parent d1ad9cc commit 6681eec
Showing 1 changed file with 104 additions and 31 deletions.
135 changes: 104 additions & 31 deletions libraries/AP_Scripting/drivers/EFI_SkyPower.lua
Original file line number Diff line number Diff line change
Expand Up @@ -174,6 +174,27 @@ local EFI_SP_LOG_RT = bind_add_param('LOG_RT', 10, 10) -- rate for logg
--]]
local EFI_SP_ST_DISARM = bind_add_param('ST_DISARM', 11, 0) -- allow start when disarmed

--[[
// @Param: EFI_SP_MODEL
// @DisplayName: SkyPower EFI ECU model
// @Description: SkyPower EFI ECU model
// @Values: 0:Default,1:SP_275
// @User: Standard
--]]
local EFI_SP_MODEL = bind_add_param('MODEL', 12, 0)

--[[
// @Param: EFI_SP_GEN_CTRL
// @DisplayName: SkyPower EFI enable generator control
// @Description: SkyPower EFI enable generator control
// @Values: 0:Disabled,1:Enabled
// @User: Standard
--]]
local EFI_SP_GEN_CTRL = bind_add_param('GEN_CRTL', 13, 1)

local MODEL_DEFAULT = 0
local MODEL_SP_275 = 1

if EFI_SP_ENABLE:get() == 0 then
gcs:send_text(0, string.format("EFISP: disabled"))
return
Expand Down Expand Up @@ -246,6 +267,9 @@ local function engine_control(_driver, _idx)
local generator_started = false
local engine_start_t = 0.0
local last_throttle = 0.0
local sensor_error_flags = 0
local thermal_limit_flags = 0
local starter_rpm = 0

-- frames for sending commands
local FRM_500 = uint32_t(0x500)
Expand All @@ -264,6 +288,10 @@ local function engine_control(_driver, _idx)
temps.cht = 0.0 -- Cylinder Head Temperature
temps.imt = 0.0 -- intake manifold temperature
temps.oilt = 0.0 -- oil temperature
temps.cht2 = 0.0
temps.egt2 = 0.0
temps.imt2 = 0.0
temps.oil2 = 0.0

-- read telemetry packets
function self.update_telemetry()
Expand All @@ -276,8 +304,8 @@ local function engine_control(_driver, _idx)
break
end

-- All Frame IDs for this EFI Engine are extended
if frame:isExtended() then
-- All Frame IDs for this EFI Engine are not extended
if not frame:isExtended() then
self.handle_EFI_packet(frame, _idx)
end
end
Expand All @@ -291,34 +319,71 @@ local function engine_control(_driver, _idx)
-- handle an EFI packet
function self.handle_EFI_packet(frame, idx)
local id = frame:id_signed()
if id == 0x100 then
rpm = get_uint16(frame, 0)
ignition_angle = get_uint16(frame, 2) * 0.1
throttle_angle = get_uint16(frame, 4) * 0.1
last_rpm_t = get_time_sec()
elseif id == 0x101 then
current_load = get_uint16(frame, 0) * 0.1
target_load = get_uint16(frame, 2) * 0.1
inj_time = get_uint16(frame, 4)
inj_ang = get_uint16(frame, 6) * 0.1
elseif id == 0x102 then
-- unused fields
elseif id == 0x104 then
supply_voltage = get_uint16(frame, 0) * 0.1
ecu_temp = get_uint16(frame, 2) * 0.1
air_pressure = get_uint16(frame, 4)
fuel_consumption_lph = get_uint16(frame,6)*0.001
if last_fuel_s > 0 then
local dt = now_s - last_fuel_s
local fuel_lps = fuel_consumption_lph / 3600.0
fuel_total_l = fuel_total_l + fuel_lps * dt
if EFI_SP_MODEL:get() == MODEL_SP_275 then
-- updated telemetry for SP-275 ECU
if id == 0x100 then
rpm = get_uint16(frame, 0)
ignition_angle = get_uint16(frame, 2) * 0.1
throttle_angle = get_uint16(frame, 4) * 0.1
last_rpm_t = get_time_sec()
elseif id == 0x101 then
air_pressure = get_uint16(frame, 4)
elseif id == 0x102 then
inj_time = get_uint16(frame, 4)
inj_ang = get_uint16(frame, 2) * 0.1
elseif id == 0x104 then
supply_voltage = get_uint16(frame, 0) * 0.1
elseif id == 0x105 then
temps.cht = get_uint16(frame, 0) * 0.1
temps.imt = get_uint16(frame, 2) * 0.1
temps.egt = get_uint16(frame, 4) * 0.1
temps.oilt = get_uint16(frame, 6) * 0.1
elseif id == 0x107 then
sensor_error_flags = get_uint16(frame, 0)
thermal_limit_flags = get_uint16(frame, 2)
elseif id == 0x107 then
target_load = get_uint16(frame, 6) * 0.1
elseif id == 0x10C then
temps.cht2 = get_uint16(frame, 4) * 0.1
temps.egt2 = get_uint16(frame, 6) * 0.1
elseif id == 0x10D then
current_load = get_uint16(frame, 2) * 0.1
elseif id == 0x113 then
gen.amps = get_uint16(frame, 2)
elseif id == 0x2E0 then
starter_rpm = get_uint16(frame, 4)
end
else
-- original SkyPower driver
if id == 0x100 then
rpm = get_uint16(frame, 0)
ignition_angle = get_uint16(frame, 2) * 0.1
throttle_angle = get_uint16(frame, 4) * 0.1
last_rpm_t = get_time_sec()
elseif id == 0x101 then
current_load = get_uint16(frame, 0) * 0.1
target_load = get_uint16(frame, 2) * 0.1
inj_time = get_uint16(frame, 4)
inj_ang = get_uint16(frame, 6) * 0.1
elseif id == 0x102 then
-- unused fields
elseif id == 0x104 then
supply_voltage = get_uint16(frame, 0) * 0.1
ecu_temp = get_uint16(frame, 2) * 0.1
air_pressure = get_uint16(frame, 4)
fuel_consumption_lph = get_uint16(frame,6)*0.001
if last_fuel_s > 0 then
local dt = now_s - last_fuel_s
local fuel_lps = fuel_consumption_lph / 3600.0
fuel_total_l = fuel_total_l + fuel_lps * dt
end
last_fuel_s = now_s
elseif id == 0x105 then
temps.cht = get_uint16(frame, 0) * 0.1
temps.imt = get_uint16(frame, 2) * 0.1
temps.egt = get_uint16(frame, 4) * 0.1
temps.oilt = get_uint16(frame, 6) * 0.1
end
last_fuel_s = now_s
elseif id == 0x105 then
temps.cht = get_uint16(frame, 0) * 0.1
temps.imt = get_uint16(frame, 2) * 0.1
temps.egt = get_uint16(frame, 4) * 0.1
temps.oilt = get_uint16(frame, 6) * 0.1
end
end

Expand Down Expand Up @@ -455,6 +520,9 @@ local function engine_control(_driver, _idx)

-- 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())
if gen_state == 0 and generator_started then
generator_started = false
Expand Down Expand Up @@ -504,6 +572,9 @@ local function engine_control(_driver, _idx)
gcs:send_named_float('EFI_OILTMP', temps.oilt)
gcs:send_named_float('EFI_TRLOAD', target_load)
gcs:send_named_float('EFI_VOLTS', supply_voltage)
gcs:send_named_float('EFI_GEN_AMPS', gen.amps)
gcs:send_named_float('EFI_CHT2', temps.cht2)
gcs:send_named_float('EFI_STARTRPM', starter_rpm)
end

-- update custom logging
Expand All @@ -517,9 +588,11 @@ local function engine_control(_driver, _idx)
return
end
last_log_t = now
logger.write('EFSP','Thr,CLoad,TLoad,OilT,RPM,gRPM,gAmp,gCur', 'ffffffff',
logger.write('EFSP','Thr,CLoad,TLoad,OilT,RPM,gRPM,gAmp,gCur,SErr,TLim,STRPM', 'ffffffffHHH',
last_throttle, current_load, target_load, temps.oilt, rpm,
gen.rpm, gen.amps, gen.batt_current)
gen.rpm, gen.amps, gen.batt_current,
sensor_error_flags, thermal_limit_flags,
starter_rpm)
end

-- return the instance
Expand Down

0 comments on commit 6681eec

Please sign in to comment.