mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: Add EFI state get example
This commit is contained in:
parent
59cb583d63
commit
ebef532258
|
@ -0,0 +1,21 @@
|
|||
--[[
|
||||
Example for getting state of EFI and checking if the RPM is within tolerance
|
||||
--]]
|
||||
|
||||
function do_check()
|
||||
local efi_state = efi:get_state()
|
||||
local engine_speed = efi_state:engine_speed_rpm()
|
||||
if not engine_speed then
|
||||
return
|
||||
end
|
||||
if engine_speed > 7000 then
|
||||
gcs:send_text(2, "ECU RPM is too high!")
|
||||
end
|
||||
end
|
||||
|
||||
function update()
|
||||
do_check()
|
||||
return update, 100
|
||||
end
|
||||
gcs:send_text(6, "Started EFI speed check");
|
||||
return update, 0
|
Loading…
Reference in New Issue