diff --git a/libraries/AP_Scripting/examples/efi_speed_check.lua b/libraries/AP_Scripting/examples/efi_speed_check.lua new file mode 100644 index 0000000000..c033f6fcbf --- /dev/null +++ b/libraries/AP_Scripting/examples/efi_speed_check.lua @@ -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 \ No newline at end of file