From cf6fe205d20307280e9bc6d3979748e809ef7900 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 19 Oct 2023 09:21:34 +1100 Subject: [PATCH] AP_Scripting: make 2-position switch easier for quicktune this allows for low/high instead of low/mid for quicktune with a 2 position switch such as with a herelink transmitter --- .../AP_Scripting/applets/VTOL-quicktune.lua | 25 ++++++++++++++++--- .../AP_Scripting/applets/VTOL-quicktune.md | 16 ++++++++++++ 2 files changed, 37 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Scripting/applets/VTOL-quicktune.lua b/libraries/AP_Scripting/applets/VTOL-quicktune.lua index 9f76241981a88..4ddd6bd782437 100644 --- a/libraries/AP_Scripting/applets/VTOL-quicktune.lua +++ b/libraries/AP_Scripting/applets/VTOL-quicktune.lua @@ -37,7 +37,7 @@ function bind_add_param(name, idx, default_value) end -- setup quicktune specific parameters -assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 13), 'could not add param table') +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 14), 'could not add param table') --[[ // @Param: QUIK_ENABLE @@ -158,6 +158,17 @@ local QUIK_RC_FUNC = bind_add_param('RC_FUNC', 12, 300) --]] local QUIK_MAX_REDUCE = bind_add_param('MAX_REDUCE', 13, 20) +--[[ + // @Param: QUIK_OPTIONS + // @DisplayName: Quicktune options + // @Description: Additional options. When the Two Position Switch option is enabled then a high switch position will start the tune, low will disable the tune. you should also set a QUIK_AUTO_SAVE time so that you will be able to save the tune. + // @Bitmask: 0:UseTwoPositionSwitch + // @User: Standard +--]] +local QUIK_OPTIONS = bind_add_param('OPTIONS', 14, 0) + +local OPTIONS_TWO_POSITION = (1<<0) + local INS_GYRO_FILTER = bind_param("INS_GYRO_FILTER") local RCMAP_ROLL = bind_param("RCMAP_ROLL") @@ -490,7 +501,13 @@ function update() if not sw_pos then return end - if sw_pos == 1 and (not arming:is_armed() or not vehicle:get_likely_flying()) and get_time() > last_warning + 5 then + local sw_pos_tune = 1 + local sw_pos_save = 2 + if (QUIK_OPTIONS:get() & OPTIONS_TWO_POSITION) ~= 0 then + sw_pos_tune = 2 + sw_pos_save = -1 + end + if sw_pos == sw_pos_tune and (not arming:is_armed() or not vehicle:get_likely_flying()) and get_time() > last_warning + 5 then gcs:send_text(MAV_SEVERITY_EMERGENCY, string.format("Tuning: Must be flying to tune")) last_warning = get_time() return @@ -506,7 +523,7 @@ function update() reset_axes_done() return end - if sw_pos == 2 then + if sw_pos == sw_pos_save then -- save all params if need_restore then need_restore = false @@ -514,7 +531,7 @@ function update() gcs:send_text(MAV_SEVERITY_NOTICE, string.format("Tuning: saved")) end end - if sw_pos ~= 1 then + if sw_pos ~= sw_pos_tune then return end diff --git a/libraries/AP_Scripting/applets/VTOL-quicktune.md b/libraries/AP_Scripting/applets/VTOL-quicktune.md index 41b07e7acaa8a..950b552c07f5c 100644 --- a/libraries/AP_Scripting/applets/VTOL-quicktune.md +++ b/libraries/AP_Scripting/applets/VTOL-quicktune.md @@ -166,3 +166,19 @@ values. Parameters will also be reverted if you disarm before saving. If the pilot gives roll, pitch or yaw input while tuning then the tune is paused until 4 seconds after the pilot input stops. + +# Using a Two Position Switch + +Some transitters only have 2 position switches, with no 3 position +switches available. To support quicktune with a 2 position switch +please set the following: + + - set QUIK_OPTIONS to 1 to indicate the use of a 2 position switch + - set QUIK_AUTO_SAVE to 10 to automatically save the tune 10 seconds after tuning is done + +with these two options the tuning will start when the switch gives a +PWM value of over 1800. Ten seconds after tuning is complete the tune +will automatically save. + + +