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
This commit is contained in:
Andrew Tridgell 2023-10-19 09:21:34 +11:00
parent c65675a64d
commit cf6fe205d2
2 changed files with 37 additions and 4 deletions

View File

@ -37,7 +37,7 @@ function bind_add_param(name, idx, default_value)
end end
-- setup quicktune specific parameters -- 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 // @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) 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 INS_GYRO_FILTER = bind_param("INS_GYRO_FILTER")
local RCMAP_ROLL = bind_param("RCMAP_ROLL") local RCMAP_ROLL = bind_param("RCMAP_ROLL")
@ -490,7 +501,13 @@ function update()
if not sw_pos then if not sw_pos then
return return
end 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")) gcs:send_text(MAV_SEVERITY_EMERGENCY, string.format("Tuning: Must be flying to tune"))
last_warning = get_time() last_warning = get_time()
return return
@ -506,7 +523,7 @@ function update()
reset_axes_done() reset_axes_done()
return return
end end
if sw_pos == 2 then if sw_pos == sw_pos_save then
-- save all params -- save all params
if need_restore then if need_restore then
need_restore = false need_restore = false
@ -514,7 +531,7 @@ function update()
gcs:send_text(MAV_SEVERITY_NOTICE, string.format("Tuning: saved")) gcs:send_text(MAV_SEVERITY_NOTICE, string.format("Tuning: saved"))
end end
end end
if sw_pos ~= 1 then if sw_pos ~= sw_pos_tune then
return return
end end

View File

@ -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 If the pilot gives roll, pitch or yaw input while tuning then the tune
is paused until 4 seconds after the pilot input stops. 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.