From cd7b1e9fcc47c49849deef1a8f1dcf8e08498389 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 13 May 2024 20:41:01 +1000 Subject: [PATCH] AP_Scripting: added example script that causes a hard fault this exercises rapid fault handling --- .../AP_Scripting/examples/fault_handling.lua | 50 +++++++++++++++++++ 1 file changed, 50 insertions(+) create mode 100644 libraries/AP_Scripting/examples/fault_handling.lua diff --git a/libraries/AP_Scripting/examples/fault_handling.lua b/libraries/AP_Scripting/examples/fault_handling.lua new file mode 100644 index 00000000000000..ff1d792adca259 --- /dev/null +++ b/libraries/AP_Scripting/examples/fault_handling.lua @@ -0,0 +1,50 @@ +--[[ + example script to test fault handling with pcall +--]] + +local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} + +gcs:send_text(MAV_SEVERITY.INFO, "Loading fault test") + +local test_count = 0 + +--[[ + evaluate some lua code and return as a string +--]] +local function evaluate(code) + local eval_code = "function eval_func()\n" .. code .. "\nend\n" + local f, errloc, err = load(eval_code, "eval_func", "t", _ENV) + if not f then + gcs:send_text(MAV_SEVERITY.info, string.format("load failed: err=%s errloc=%s", err, errloc)) + return nil + end + local success, err2 = pcall(f) + if not success then + gcs:send_text(MAV_SEVERITY.DEBUG,string.format("pcall failed: err=%s", err2)) + return nil + end + local ok, s2 = pcall(eval_func) + eval_func = nil + if ok then + return s2 + end + return nil +end + +local function run_test() + evaluate("local loc = nil; loc:get_lat()") +end + +local function update() + test_count = test_count + 1 + if test_count % 100 == 0 then + gcs:send_text(MAV_SEVERITY.INFO,string.format("Test %u", test_count)) + end + run_test() + return update,1 +end + +gcs:send_text(MAV_SEVERITY.INFO, "Starting fault test in 2 seconds") + +-- wait a while for GCS to connect +return update,2000