AP_Scripting: convert HFE driver to get_backend
This commit is contained in:
parent
3b5561aa88
commit
186e579036
@ -58,7 +58,13 @@ end
|
|||||||
local driver1 = CAN.get_device(25)
|
local driver1 = CAN.get_device(25)
|
||||||
|
|
||||||
if not driver1 then
|
if not driver1 then
|
||||||
gcs:send_text(0, string.format("EFI CAN Telemetry: Failed to load driver"))
|
gcs:send_text(0, string.format("EFI_HFE: Failed to load driver"))
|
||||||
|
return
|
||||||
|
end
|
||||||
|
|
||||||
|
local efi_backend = efi:get_backend(0)
|
||||||
|
if not efi_backend then
|
||||||
|
gcs:send_text(0, string.format("EFI_HFE: Failed to find EFI scripting backend"))
|
||||||
return
|
return
|
||||||
end
|
end
|
||||||
|
|
||||||
@ -220,7 +226,7 @@ local function engine_control(_driver)
|
|||||||
efi_state:last_updated_ms(millis())
|
efi_state:last_updated_ms(millis())
|
||||||
|
|
||||||
-- Set the EFI_State into the EFI scripting driver
|
-- Set the EFI_State into the EFI scripting driver
|
||||||
efi:handle_scripting(efi_state)
|
efi_backend:handle_scripting(efi_state)
|
||||||
end
|
end
|
||||||
|
|
||||||
-- send throttle
|
-- send throttle
|
||||||
|
Loading…
Reference in New Issue
Block a user