AP_Scripting: added CANDRV to HFE EFI driver and document

This commit is contained in:
Andrew Tridgell 2022-10-22 09:17:45 +11:00 committed by Randy Mackay
parent 037468c1de
commit 2eeff1de32
2 changed files with 83 additions and 10 deletions

View File

@ -3,7 +3,7 @@
--]]
-- Check Script uses a miniumum firmware version
local SCRIPT_AP_VERSION = 4.4
local SCRIPT_AP_VERSION = 4.3
local SCRIPT_NAME = "EFI: HFE CAN"
local VERSION = FWVersion:major() + (FWVersion:minor() * 0.1)
@ -54,30 +54,38 @@ function constrain(v, vmin, vmax)
return v
end
-- Register for the CAN drivers
local driver1 = CAN.get_device(25)
if not driver1 then
gcs:send_text(0, string.format("EFI_HFE: Failed to load driver"))
return
end
local efi_backend = nil
-- Setup EFI Parameters
assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 5), 'could not add EFI_HFE param table')
assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 6), 'could not add EFI_HFE param table')
local EFI_HFE_ENABLE = bind_add_param('ENABLE', 1, 0)
local EFI_HFE_RATE_HZ = bind_add_param('RATE_HZ', 2, 200) -- Script update frequency in Hz
local EFI_HFE_ECU_IDX = bind_add_param('ECU_IDX', 3, 0) -- ECU index on CAN bus, 0 for automatic
local EFI_HFE_FUEL_DTY = bind_add_param('FUEL_DTY', 4, 740) -- fuel density, g/litre
local EFI_HFE_REL_IDX = bind_add_param('REL_IDX', 5, 0) -- relay number for engine enable
local EFI_HFE_CANDRV = bind_add_param('CANDRV', 6, 0) -- CAN driver number
local ICE_PWM_IGN_ON = bind_param("ICE_PWM_IGN_ON")
if EFI_HFE_ENABLE:get() == 0 then
return
end
-- Register for the CAN drivers
local CAN_BUF_LEN = 25
if EFI_HFE_CANDRV:get() == 1 then
driver1 = CAN.get_device(CAN_BUF_LEN)
elseif EFI_HFE_CANDRV:get() == 2 then
driver1 = CAN.get_device2(CAN_BUF_LEN)
end
if not driver1 then
gcs:send_text(0, string.format("EFI_HFE: Failed to load driver"))
return
end
local now_s = get_time_sec()
--[[

View File

@ -0,0 +1,65 @@
# EFI HFE Driver
This driver implements support for the HFE International range of EFI
CAN engine control units. It supports monitoring and control of HFE
engines on fixed wing aircraft. This driver assumes you are using the
ICE subsystem in fixed wing aircraft for engine control.
# Parameters
The script used the following parameters:
## EFI_HFE_ENABLE
this must be set to 1 to enable the driver
## EFI_HFE_CANDRV
This sets the CAN scripting driver number to attach to. This is
normally set to 1 to use a CAN driver with CAN_Dx_PROTOCOL=10. To use
the 2nd scripting CAN driver set this to 2 and set CAN_Dx_PROTOCOL=12.
## EFI_HFE_ECU_IDX
This sets the ECU number on the CAN bus. A value of zero means that
the ECU number is auto-detected based on the first ECU seen on the
bus.
## EFI_HFE_RATE_HZ
This sets the update rate of the driver. A value of 200 is reasonable
## EFI_HFE_FUEL_DTY
This sets the fuel density in grams per litre, for fuel consumption
calculations
## EFI_HFE_REL_IDX
This sets a relay number to use for the ECU enable function. if the
ECU requires a high voltage GPIO to enable then you should set a
RELAY_PIN that the ECU enable is attached to and set the relay number
here.
# Operation
This driver should be loaded by placing the lua script in the
APM/SCRIPTS directory on the microSD card, which can be done either
directly or via MAVFTP. The following key parameters should be set:
- SCR_ENABLE should be set to 1
- EFI_TYPE should be set to 7
- ICE_ENABLE should be set to 1
then the flight controller should rebooted and parameters should be
refreshed.
Once loaded the EFI_HFE parameters will appear and should be set
according to the parameter list above.
The ICE start channel will be monitored for starter control.
The GCS will receive EFI_STATUS MAVLink messages which includes RPM,
cylinder head temperature, injection timing, engine load, fuel
consumption rate, throttle position atmospheric pressure and ECU
voltage.