From c3d96b4494285848b70ede89fc35a1098adde60b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 14 Aug 2023 11:01:16 +1000 Subject: [PATCH] AP_Scripting: added EFI driver for DLA EFI serial protocol a simple serial protocol, no CRC, gap framed --- libraries/AP_Scripting/drivers/EFI_DLA.lua | 188 +++++++++++++++++++++ libraries/AP_Scripting/drivers/EFI_DLA.md | 50 ++++++ 2 files changed, 238 insertions(+) create mode 100644 libraries/AP_Scripting/drivers/EFI_DLA.lua create mode 100644 libraries/AP_Scripting/drivers/EFI_DLA.md diff --git a/libraries/AP_Scripting/drivers/EFI_DLA.lua b/libraries/AP_Scripting/drivers/EFI_DLA.lua new file mode 100644 index 0000000000000..9c764ac4a38b2 --- /dev/null +++ b/libraries/AP_Scripting/drivers/EFI_DLA.lua @@ -0,0 +1,188 @@ +--[[ + DLA serial EFI protocol + + Note that this protocol is gap framed, no CRC + + https://www.austars-model.com/dla-232cc-uavuas-engine-optional-one-key-startauto-startergenerator_g17937.html +--]] + +local PARAM_TABLE_KEY = 41 +local PARAM_TABLE_PREFIX = "EFI_DLA_" + +local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} + +-- bind a parameter to a variable given +local function bind_param(name) + local p = Parameter() + assert(p:init(name), string.format('could not find %s parameter', name)) + return p +end + +-- add a parameter and bind it to a variable +local function bind_add_param(name, idx, default_value) + assert(param:add_param(PARAM_TABLE_KEY, idx, name, default_value), string.format('could not add param %s', name)) + return bind_param(PARAM_TABLE_PREFIX .. name) +end + +-- setup script specific parameters +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 8), 'could not add param table') + +--[[ + // @Param: EFI_DLA_ENABLE + // @DisplayName: EFI DLA enable + // @Description: Enable EFI DLA driver + // @Values: 0:Disabled,1:Enabled + // @User: Standard +--]] +EFI_DLA_ENABLE = bind_add_param("ENABLE", 1, 0) + +--[[ + // @Param: EFI_DLA_LPS + // @DisplayName: EFI DLA fuel scale + // @Description: EFI DLA litres of fuel per second of injection time + // @Range: 0.00001 1 + // @Units: litres + // @User: Standard +--]] +EFI_DLA_LPS = bind_add_param("LPS", 2, 0.001) + +if EFI_DLA_ENABLE:get() ~= 1 then + return +end + +local uart = serial:find_serial(0) -- first scripting serial +if not uart then + gcs:send_text(MAV_SEVERITY.ERROR, "EFI_DLA: unable to find scripting serial") + return +end +uart:begin(115200) + +local efi_backend = efi:get_backend(0) +if not efi_backend then + gcs:send_text(MAV_SEVERITY.ERROR, "EFI_DLA: unable to find EFI backend") + return +end + +--[[ + discard n bytes +--]] +local function discard_bytes(n) + for _ = 1, n do + uart:read() + end +end + +local function read_bytes(n) + local ret = "" + for _ = 1, n do + ret = ret .. string.char(uart:read()) + end + return ret +end + +local state = {} +state.last_read_us = uint32_t(0) +state.total_fuel_cm3 = 0.0 + +--[[ + check for input and parse data +--]] +local function check_input() + local n_bytes = uart:available():toint() + --gcs:send_text(MAV_SEVERITY.INFO, string.format("n_bytes=%u %.2f", n_bytes, millis():tofloat()*0.001)) + if n_bytes < 82 then + return + end + if n_bytes > 82 then + discard_bytes(n_bytes) + return + end + + state.seconds, state.pw1, state.pw2 = string.unpack("