AP_Scripting: VTOL-quiktune add param for RC script function
This commit is contained in:
parent
430e52a91b
commit
82ece34981
@ -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, 11), 'could not add param table')
|
||||
assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 12), 'could not add param table')
|
||||
|
||||
local QUIK_ENABLE = bind_add_param('ENABLE', 1, 0)
|
||||
local QUIK_AXES = bind_add_param('AXES', 2, 7)
|
||||
@ -50,6 +50,7 @@ local QUIK_RP_PI_RATIO = bind_add_param('RP_PI_RATIO', 8, 1.0)
|
||||
local QUIK_Y_PI_RATIO = bind_add_param('Y_PI_RATIO', 9, 10)
|
||||
local QUIK_AUTO_FILTER = bind_add_param('AUTO_FILTER', 10, 1)
|
||||
local QUIK_AUTO_SAVE = bind_add_param('AUTO_SAVE', 11, 0)
|
||||
local QUIK_RC_FUNC = bind_add_param('RC_FUNC', 12, 300)
|
||||
|
||||
local INS_GYRO_FILTER = bind_param("INS_GYRO_FILTER")
|
||||
|
||||
@ -354,7 +355,7 @@ end
|
||||
local last_warning = get_time()
|
||||
function update()
|
||||
if quick_switch == nil then
|
||||
quick_switch = rc:find_channel_for_option(300)
|
||||
quick_switch = rc:find_channel_for_option(math.floor(QUIK_RC_FUNC:get()))
|
||||
end
|
||||
if quick_switch == nil or QUIK_ENABLE:get() < 1 then
|
||||
return
|
||||
|
@ -17,6 +17,11 @@ are:
|
||||
|
||||
this must be set to 1 to enable the script
|
||||
|
||||
## QUIK_RC_FUNC
|
||||
|
||||
The RCz_OPTIONS scripting function binding to be used for this script.
|
||||
Default RCz_OPTIONS binding is 300 (scripting1).
|
||||
|
||||
## QUIK_AXES
|
||||
|
||||
This is the set of axes that the tune will run on. The default is 7,
|
||||
@ -108,15 +113,18 @@ refresh parameters. Then set QUIK_ENABLE to 1.
|
||||
You will then need to setup a 3 position switch on an available RC
|
||||
input channel for controlling the tune (or 2 position if you set
|
||||
QUIK_AUTO_SAVE). If for example channel 6 is available with a 3
|
||||
position switch then you should set RC6_OPTION=300 to association the
|
||||
position switch then you should set RC6_OPTION=300 (scripting1) to associate the
|
||||
tuning control with that switch.
|
||||
|
||||
If needed, the QUIK_RC_FUNC option can be used to associate the tuning switch
|
||||
with a different scripting binding such as RCz_OPTION = 302 (scripting3).
|
||||
|
||||
You should then takeoff and put the vehicle into QLOITER mode (for
|
||||
quadplanes) or LOITER mode (for multicopters) and have it in a steady
|
||||
hover in low wind.
|
||||
|
||||
Then move the control switch you setup with option 300 to the middle
|
||||
position. This will start the tuning process. You will see text
|
||||
Then move the control switch you setup with option 300 (or via QUIK_RC_FUNC)
|
||||
to the middle position. This will start the tuning process. You will see text
|
||||
messages on the ground station showing the progress of the tune. As
|
||||
the aircraft reaches the oscillation limit of each parameter it will
|
||||
start a small oscillation, then it will reduce that gain by the
|
||||
|
Loading…
Reference in New Issue
Block a user