From be00dad4f0475ba48a6fa48d24af12b036443b19 Mon Sep 17 00:00:00 2001 From: Marco Robustini Date: Mon, 2 Dec 2024 06:28:46 +0100 Subject: [PATCH] Update MissionRotation.lua Changed the operating logic: - always loads mission0.txt at startup, cycles missions to AUX high if held for less than 3 seconds - resets mission0.txt if AUX is high for more than 3 seconds --- .../AP_Scripting/applets/MissionRotation.lua | 43 +++++++++++-------- 1 file changed, 26 insertions(+), 17 deletions(-) diff --git a/libraries/AP_Scripting/applets/MissionRotation.lua b/libraries/AP_Scripting/applets/MissionRotation.lua index bba77528a99f43..ee79a1e264f0c4 100644 --- a/libraries/AP_Scripting/applets/MissionRotation.lua +++ b/libraries/AP_Scripting/applets/MissionRotation.lua @@ -1,15 +1,18 @@ -- Script to load one of up to 10 mission files based on AUX switch state --- Always loads mission0.txt at boot, then cycles through files on AUX high transitions +-- Always loads mission0.txt at boot, cycles missions on AUX high if held less than 3 seconds +-- Reset the mission0.txt if AUX is high for more than 3 seconds. +local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} local rc_switch = rc:find_channel_for_option(24) -- AUX FUNC switch for mission loading if not rc_switch then - gcs:send_text(6, "Mission Reset switch not assigned.") + gcs:send_text(MAV_SEVERITY.ERROR, "Mission Reset switch not assigned.") return end local last_sw_pos = -1 -- Track the last switch position local current_mission_index = 0 -- Start with mission0.txt local max_missions = 9 -- Maximum mission index (mission0.txt to mission9.txt) +local high_timer = 0 -- Timer to track how long AUX stays high local function read_mission(file_name) local file = io.open(file_name, "r") @@ -31,7 +34,7 @@ local function read_mission(file_name) data[i] = file:read('n') if data[i] == nil then if i == 1 then - gcs:send_text(6, "Loaded mission: " .. file_name) + gcs:send_text(MAV_SEVERITY.WARNING, "Loaded mission: " .. file_name) file:close() return true else @@ -62,33 +65,39 @@ end -- Ensure mission0.txt exists and load it; stop if not found if not read_mission("mission0.txt") then - gcs:send_text(6, "Critical error: mission0.txt not found. Script stopped.") + gcs:send_text(MAV_SEVERITY.CRITICAL, "Critical error: mission0.txt not found, script stopped.") return end local function load_next_mission() - while true do - local file_name = string.format("mission%d.txt", current_mission_index) - if read_mission(file_name) then - break - end - current_mission_index = (current_mission_index + 1) % (max_missions + 1) + current_mission_index = (current_mission_index + 1) % (max_missions + 1) + local file_name = string.format("mission%d.txt", current_mission_index) + if read_mission(file_name) then + gcs:send_text(MAV_SEVERITY.WARNING, "Loaded mission: " .. file_name) end end function update() local sw_pos = rc_switch:get_aux_switch_pos() - -- Check if AUX switch transitioned from low to high - if sw_pos == 2 and last_sw_pos ~= 2 then - current_mission_index = (current_mission_index + 1) % (max_missions + 1) - load_next_mission() + if sw_pos == 2 then -- AUX high position + high_timer = high_timer + 1 + if high_timer >= 3 then -- 3 seconds elapsed + current_mission_index = 0 + read_mission("mission0.txt") + gcs:send_text(MAV_SEVERITY.WARNING, "Reset to mission0.txt") + high_timer = 0 -- Reset the timer after reset + end + else + if high_timer > 0 and high_timer < 3 then + load_next_mission() -- Load next mission only if held high for less than 3 seconds + end + high_timer = 0 -- Reset timer when AUX is not high end last_sw_pos = sw_pos - - return update, 1000 + return update, 1000 -- Run every second end -gcs:send_text(5, "MissionRotation.lua loaded") +gcs:send_text(MAV_SEVERITY.NOTICE, "MissionSelector loaded") return update, 1000