From 809511757f9c10da397eeebc44a28a3cbc2c4266 Mon Sep 17 00:00:00 2001 From: Marco Robustini Date: Sun, 1 Dec 2024 10:09:22 +0100 Subject: [PATCH 01/11] MissionRotation LUA - Load one of up to 10 mission files based on AUX switch state This LUA script is an evolution on the MissionSelector.LUA. Allows you to select up to 10 missions, either while arming or in the unarmed state. Requires that an RC_xFUNCTION be set to 24 (Mission Reset). The scripts should be installed in the SCRIPTS folder on the MicroSD, and the mission files in the root. The mission file called mission0.txt (the default mission) must exist and is loaded at boot, if the script does not find it it stops working. To load to the next mission file just bring AUX switch from low to high, each switch loads the next mission file in numerical order. If the next mission file numerically does not exist load the next one, at the end of the rotation it returns to load mission0.txt. Provides for sending messages under any condition, load or error. --- .../AP_Scripting/applets/MissionRotation.lua | 94 +++++++++++++++++++ .../AP_Scripting/applets/MissionRotation.md | 17 ++++ 2 files changed, 111 insertions(+) create mode 100644 libraries/AP_Scripting/applets/MissionRotation.lua create mode 100644 libraries/AP_Scripting/applets/MissionRotation.md diff --git a/libraries/AP_Scripting/applets/MissionRotation.lua b/libraries/AP_Scripting/applets/MissionRotation.lua new file mode 100644 index 0000000000000..bba77528a99f4 --- /dev/null +++ b/libraries/AP_Scripting/applets/MissionRotation.lua @@ -0,0 +1,94 @@ +-- 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 + +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.") + 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 function read_mission(file_name) + local file = io.open(file_name, "r") + if not file then + return false + end + + local header = file:read('l') + assert(string.find(header, 'QGC WPL 110') == 1, file_name .. ': incorrect format') + + assert(mission:clear(), 'Could not clear current mission') + + local item = mavlink_mission_item_int_t() + local index = 0 + + while true do + local data = {} + for i = 1, 12 do + data[i] = file:read('n') + if data[i] == nil then + if i == 1 then + gcs:send_text(6, "Loaded mission: " .. file_name) + file:close() + return true + else + mission:clear() + error('Failed to read file: premature end of data') + end + end + end + + item:seq(data[1]) + item:frame(data[3]) + item:command(data[4]) + item:param1(data[5]) + item:param2(data[6]) + item:param3(data[7]) + item:param4(data[8]) + item:x(data[9] * 10^7) + item:y(data[10] * 10^7) + item:z(data[11]) + + if not mission:set_item(index, item) then + mission:clear() + error(string.format('Failed to set mission item %i', index)) + end + index = index + 1 + end +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.") + 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) + 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() + end + + last_sw_pos = sw_pos + + return update, 1000 +end + +gcs:send_text(5, "MissionRotation.lua loaded") +return update, 1000 diff --git a/libraries/AP_Scripting/applets/MissionRotation.md b/libraries/AP_Scripting/applets/MissionRotation.md new file mode 100644 index 0000000000000..d225ef7510677 --- /dev/null +++ b/libraries/AP_Scripting/applets/MissionRotation.md @@ -0,0 +1,17 @@ +# MissionRotation LUA script + +This LUA script is an evolution on the MissionSelector.LUA. + +Allows you to select up to 10 missions, either while arming or in the unarmed state. + +Requires that an RC_xFUNCTION be set to 24 (Mission Reset). + +The scripts should be installed in the SCRIPTS folder on the MicroSD, and the mission files in the root. + +The mission file called mission0.txt (the default mission) must exist and is loaded at boot, if the script does not find it it stops working. + +To load to the next mission file just bring AUX switch from low to high, each switch loads the next mission file in numerical order. + +If the next mission file numerically does not exist load the next one, at the end of the rotation it returns to load mission0.txt. + +Provides for sending messages under any condition, load or error. \ No newline at end of file From fccb74d02eff07bcab326796316281c96ab0b800 Mon Sep 17 00:00:00 2001 From: Marco Robustini Date: Sun, 1 Dec 2024 10:19:51 +0100 Subject: [PATCH 02/11] Update MissionRotation.md Fix typo --- libraries/AP_Scripting/applets/MissionRotation.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Scripting/applets/MissionRotation.md b/libraries/AP_Scripting/applets/MissionRotation.md index d225ef7510677..2e9151462aa0b 100644 --- a/libraries/AP_Scripting/applets/MissionRotation.md +++ b/libraries/AP_Scripting/applets/MissionRotation.md @@ -4,7 +4,7 @@ This LUA script is an evolution on the MissionSelector.LUA. Allows you to select up to 10 missions, either while arming or in the unarmed state. -Requires that an RC_xFUNCTION be set to 24 (Mission Reset). +Requires that an RCx_OPTION be set to 24 (Mission Reset). The scripts should be installed in the SCRIPTS folder on the MicroSD, and the mission files in the root. @@ -14,4 +14,4 @@ To load to the next mission file just bring AUX switch from low to high, each sw If the next mission file numerically does not exist load the next one, at the end of the rotation it returns to load mission0.txt. -Provides for sending messages under any condition, load or error. \ No newline at end of file +Provides for sending messages under any condition, load or error. From be00dad4f0475ba48a6fa48d24af12b036443b19 Mon Sep 17 00:00:00 2001 From: Marco Robustini Date: Mon, 2 Dec 2024 06:28:46 +0100 Subject: [PATCH 03/11] 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 bba77528a99f4..ee79a1e264f0c 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 From 5a8817b1bc09688be4c6cd74d724481dd83e2437 Mon Sep 17 00:00:00 2001 From: Marco Robustini Date: Mon, 2 Dec 2024 06:29:44 +0100 Subject: [PATCH 04/11] Update MissionRotation.lua Cosmetic --- libraries/AP_Scripting/applets/MissionRotation.lua | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Scripting/applets/MissionRotation.lua b/libraries/AP_Scripting/applets/MissionRotation.lua index ee79a1e264f0c..3178008613b6e 100644 --- a/libraries/AP_Scripting/applets/MissionRotation.lua +++ b/libraries/AP_Scripting/applets/MissionRotation.lua @@ -1,6 +1,6 @@ -- Script to load one of up to 10 mission files based on AUX switch state -- 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. +-- 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 From 75dc1e11f5a98dff734a344301a7188cb992a016 Mon Sep 17 00:00:00 2001 From: Marco Robustini Date: Mon, 2 Dec 2024 06:32:03 +0100 Subject: [PATCH 05/11] Update MissionRotation.md Updated operating logic --- libraries/AP_Scripting/applets/MissionRotation.md | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Scripting/applets/MissionRotation.md b/libraries/AP_Scripting/applets/MissionRotation.md index 2e9151462aa0b..e2478cf8ca97d 100644 --- a/libraries/AP_Scripting/applets/MissionRotation.md +++ b/libraries/AP_Scripting/applets/MissionRotation.md @@ -10,8 +10,10 @@ The scripts should be installed in the SCRIPTS folder on the MicroSD, and the mi The mission file called mission0.txt (the default mission) must exist and is loaded at boot, if the script does not find it it stops working. -To load to the next mission file just bring AUX switch from low to high, each switch loads the next mission file in numerical order. +To load to the next mission file just bring AUX switch from low to high for no more than three seconds, each switch high-low loads the next mission file in numerical order. If the next mission file numerically does not exist load the next one, at the end of the rotation it returns to load mission0.txt. +If AUX is held at high state for more than three seconds the script will restart by loading mission0.txt. + Provides for sending messages under any condition, load or error. From 468c730414e602989b0e37c39cce9a0de0701553 Mon Sep 17 00:00:00 2001 From: Marco Robustini Date: Mon, 2 Dec 2024 06:49:49 +0100 Subject: [PATCH 06/11] Update MissionRotation.lua - removal of last_sw_pos - removed all comments except the initial ones --- .../AP_Scripting/applets/MissionRotation.lua | 24 ++++++++----------- 1 file changed, 10 insertions(+), 14 deletions(-) diff --git a/libraries/AP_Scripting/applets/MissionRotation.lua b/libraries/AP_Scripting/applets/MissionRotation.lua index 3178008613b6e..669a01768906f 100644 --- a/libraries/AP_Scripting/applets/MissionRotation.lua +++ b/libraries/AP_Scripting/applets/MissionRotation.lua @@ -3,16 +3,15 @@ -- 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 +local rc_switch = rc:find_channel_for_option(24) if not rc_switch then 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 current_mission_index = 0 +local max_missions = 9 +local high_timer = 0 local function read_mission(file_name) local file = io.open(file_name, "r") @@ -22,7 +21,6 @@ local function read_mission(file_name) local header = file:read('l') assert(string.find(header, 'QGC WPL 110') == 1, file_name .. ': incorrect format') - assert(mission:clear(), 'Could not clear current mission') local item = mavlink_mission_item_int_t() @@ -63,7 +61,6 @@ local function read_mission(file_name) end end --- Ensure mission0.txt exists and load it; stop if not found if not read_mission("mission0.txt") then gcs:send_text(MAV_SEVERITY.CRITICAL, "Critical error: mission0.txt not found, script stopped.") return @@ -80,23 +77,22 @@ end function update() local sw_pos = rc_switch:get_aux_switch_pos() - if sw_pos == 2 then -- AUX high position + if sw_pos == 2 then high_timer = high_timer + 1 - if high_timer >= 3 then -- 3 seconds elapsed + if high_timer >= 3 then 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 + high_timer = 0 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 + load_next_mission() end - high_timer = 0 -- Reset timer when AUX is not high + high_timer = 0 end - last_sw_pos = sw_pos - return update, 1000 -- Run every second + return update, 1000 end gcs:send_text(MAV_SEVERITY.NOTICE, "MissionSelector loaded") From a5e5eef5848bfe613b5e39453ed62651e4c34106 Mon Sep 17 00:00:00 2001 From: Marco Robustini Date: Mon, 2 Dec 2024 07:04:14 +0100 Subject: [PATCH 07/11] Update MissionRotation.lua Inhibited the ability to change mission if flight mode is AUTO, with associated warning message --- libraries/AP_Scripting/applets/MissionRotation.lua | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Scripting/applets/MissionRotation.lua b/libraries/AP_Scripting/applets/MissionRotation.lua index 669a01768906f..8901cf0f704e0 100644 --- a/libraries/AP_Scripting/applets/MissionRotation.lua +++ b/libraries/AP_Scripting/applets/MissionRotation.lua @@ -5,7 +5,7 @@ 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) if not rc_switch then - gcs:send_text(MAV_SEVERITY.ERROR, "Mission Reset switch not assigned.") + gcs:send_text(MAV_SEVERITY.ERROR, "Mission Reset switch not assigned") return end @@ -14,6 +14,11 @@ local max_missions = 9 local high_timer = 0 local function read_mission(file_name) + if vehicle:get_mode() == 10 then -- 10 = AUTO mode + gcs:send_text(MAV_SEVERITY.ERROR, "Cannot load mission in AUTO mode") + return false + end + local file = io.open(file_name, "r") if not file then return false @@ -62,7 +67,7 @@ local function read_mission(file_name) end if not read_mission("mission0.txt") then - gcs:send_text(MAV_SEVERITY.CRITICAL, "Critical error: mission0.txt not found, script stopped.") + gcs:send_text(MAV_SEVERITY.CRITICAL, "Critical error: mission0.txt not found, script stopped") return end @@ -95,5 +100,5 @@ function update() return update, 1000 end -gcs:send_text(MAV_SEVERITY.NOTICE, "MissionSelector loaded") +gcs:send_text(MAV_SEVERITY.NOTICE, "Mission Rotation loaded") return update, 1000 From 526f336eccf476a13264e6231eb00e592a8644e7 Mon Sep 17 00:00:00 2001 From: Marco Robustini Date: Mon, 2 Dec 2024 08:36:02 +0100 Subject: [PATCH 08/11] Update MissionRotation.lua MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit If a mission switch is attempted in AUTO flight mode, a warning “Could not clear current mission” will be shown and no operation will be performed. --- .../AP_Scripting/applets/MissionRotation.lua | 25 ++++++++++++++----- 1 file changed, 19 insertions(+), 6 deletions(-) diff --git a/libraries/AP_Scripting/applets/MissionRotation.lua b/libraries/AP_Scripting/applets/MissionRotation.lua index 8901cf0f704e0..83ed03bf2930d 100644 --- a/libraries/AP_Scripting/applets/MissionRotation.lua +++ b/libraries/AP_Scripting/applets/MissionRotation.lua @@ -14,8 +14,7 @@ local max_missions = 9 local high_timer = 0 local function read_mission(file_name) - if vehicle:get_mode() == 10 then -- 10 = AUTO mode - gcs:send_text(MAV_SEVERITY.ERROR, "Cannot load mission in AUTO mode") + if vehicle:get_mode() == 3 then return false end @@ -26,7 +25,14 @@ local function read_mission(file_name) local header = file:read('l') assert(string.find(header, 'QGC WPL 110') == 1, file_name .. ': incorrect format') - assert(mission:clear(), 'Could not clear current mission') + + if vehicle:get_mode() ~= 3 then + if not mission:clear() then + gcs:send_text(MAV_SEVERITY.ERROR, "Could not clear current mission") + file:close() + return false + end + end local item = mavlink_mission_item_int_t() local index = 0 @@ -72,6 +78,10 @@ if not read_mission("mission0.txt") then end local function load_next_mission() + if vehicle:get_mode() == 3 then + return + end + 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 @@ -85,9 +95,12 @@ function update() if sw_pos == 2 then high_timer = high_timer + 1 if high_timer >= 3 then - current_mission_index = 0 - read_mission("mission0.txt") - gcs:send_text(MAV_SEVERITY.WARNING, "Reset to mission0.txt") + if vehicle:get_mode() ~= 3 then + current_mission_index = 0 + if read_mission("mission0.txt") then + gcs:send_text(MAV_SEVERITY.WARNING, "Reset to mission0.txt") + end + end high_timer = 0 end else From 4c108b1e51941c3138c6050f019d26b64f52171e Mon Sep 17 00:00:00 2001 From: Marco Robustini Date: Mon, 2 Dec 2024 08:36:27 +0100 Subject: [PATCH 09/11] Update MissionRotation.md --- libraries/AP_Scripting/applets/MissionRotation.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Scripting/applets/MissionRotation.md b/libraries/AP_Scripting/applets/MissionRotation.md index e2478cf8ca97d..484eb11201312 100644 --- a/libraries/AP_Scripting/applets/MissionRotation.md +++ b/libraries/AP_Scripting/applets/MissionRotation.md @@ -16,4 +16,6 @@ If the next mission file numerically does not exist load the next one, at the en If AUX is held at high state for more than three seconds the script will restart by loading mission0.txt. +If a mission switch is attempted in AUTO flight mode, a warning “Could not clear current mission” will be shown and no operation will be performed. + Provides for sending messages under any condition, load or error. From 8186d844b0c6c1b19bbb9378e45f0dc33a4b0144 Mon Sep 17 00:00:00 2001 From: Marco Robustini Date: Mon, 2 Dec 2024 17:42:03 +0100 Subject: [PATCH 10/11] Update MissionRotation.lua Fixed issue that sent duplicate mission change messages. --- .../AP_Scripting/applets/MissionRotation.lua | 19 ++++++++++--------- 1 file changed, 10 insertions(+), 9 deletions(-) diff --git a/libraries/AP_Scripting/applets/MissionRotation.lua b/libraries/AP_Scripting/applets/MissionRotation.lua index 83ed03bf2930d..a127434ec99ef 100644 --- a/libraries/AP_Scripting/applets/MissionRotation.lua +++ b/libraries/AP_Scripting/applets/MissionRotation.lua @@ -4,14 +4,16 @@ 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) + if not rc_switch then gcs:send_text(MAV_SEVERITY.ERROR, "Mission Reset switch not assigned") return end local current_mission_index = 0 -local max_missions = 9 +local max_missions = 6 -- Aggiornato a 6 poiché hai fino a mission6.txt local high_timer = 0 +local latest_mission_loaded = -1 -- Track the last loaded mission local function read_mission(file_name) if vehicle:get_mode() == 3 then @@ -43,7 +45,6 @@ local function read_mission(file_name) data[i] = file:read('n') if data[i] == nil then if i == 1 then - gcs:send_text(MAV_SEVERITY.WARNING, "Loaded mission: " .. file_name) file:close() return true else @@ -78,14 +79,14 @@ if not read_mission("mission0.txt") then end local function load_next_mission() - if vehicle:get_mode() == 3 then - return - end - 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) + if latest_mission_loaded ~= current_mission_index then + gcs:send_text(MAV_SEVERITY.WARNING, "Loaded mission: " .. file_name) + latest_mission_loaded = current_mission_index + end end end @@ -105,11 +106,11 @@ function update() end else if high_timer > 0 and high_timer < 3 then - load_next_mission() + load_next_mission() -- Load next mission if switched back before 3 seconds end high_timer = 0 end - + return update, 1000 end From a96fa596eac9f6be6d81a95bc1a2a6e7aabc7b04 Mon Sep 17 00:00:00 2001 From: Marco Robustini Date: Mon, 2 Dec 2024 18:05:39 +0100 Subject: [PATCH 11/11] Update MissionRotation.lua Second attempt: fixed duplicate message sending problem in mission loading. --- .../AP_Scripting/applets/MissionRotation.lua | 17 ++++++++--------- 1 file changed, 8 insertions(+), 9 deletions(-) diff --git a/libraries/AP_Scripting/applets/MissionRotation.lua b/libraries/AP_Scripting/applets/MissionRotation.lua index a127434ec99ef..7e890b3fdde80 100644 --- a/libraries/AP_Scripting/applets/MissionRotation.lua +++ b/libraries/AP_Scripting/applets/MissionRotation.lua @@ -11,9 +11,8 @@ if not rc_switch then end local current_mission_index = 0 -local max_missions = 6 -- Aggiornato a 6 poiché hai fino a mission6.txt +local max_missions = 9 local high_timer = 0 -local latest_mission_loaded = -1 -- Track the last loaded mission local function read_mission(file_name) if vehicle:get_mode() == 3 then @@ -79,14 +78,14 @@ if not read_mission("mission0.txt") then end local function load_next_mission() + if vehicle:get_mode() == 3 then + return + end + 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 - if latest_mission_loaded ~= current_mission_index then - gcs:send_text(MAV_SEVERITY.WARNING, "Loaded mission: " .. file_name) - latest_mission_loaded = current_mission_index - end + gcs:send_text(MAV_SEVERITY.WARNING, "Loaded mission: " .. file_name) end end @@ -106,11 +105,11 @@ function update() end else if high_timer > 0 and high_timer < 3 then - load_next_mission() -- Load next mission if switched back before 3 seconds + load_next_mission() end high_timer = 0 end - + return update, 1000 end