mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_Scripting: added revert_param.lua applet
This script implements a easy parameter reversion system to help with manual in-flight tuning. It allows you to do a wide range of manual tuning while flying and if you get in trouble (eg. an oscillation) then you can use a switch to instantly revert all the parameter changes to the values from startup.
This commit is contained in:
parent
086d0907dd
commit
ded8d2a4b4
157
libraries/AP_Scripting/applets/revert_param.lua
Normal file
157
libraries/AP_Scripting/applets/revert_param.lua
Normal file
@ -0,0 +1,157 @@
|
||||
--[[
|
||||
parameter reversion utility. This helps with manual tuning
|
||||
in-flight by giving a way to instantly revert parameters to the startup parameters
|
||||
--]]
|
||||
local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7}
|
||||
|
||||
local PARAM_TABLE_KEY = 31
|
||||
local PARAM_TABLE_PREFIX = "PREV_"
|
||||
|
||||
local UPDATE_RATE_HZ = 4
|
||||
|
||||
-- bind a parameter to a variable, old syntax to support older firmware
|
||||
function bind_param(name)
|
||||
local p = Parameter()
|
||||
if not p:init(name) then
|
||||
return nil
|
||||
end
|
||||
return p
|
||||
end
|
||||
|
||||
-- add a parameter and bind it to a variable
|
||||
function bind_add_param(name, idx, default_value)
|
||||
assert(param:add_param(PARAM_TABLE_KEY, idx, name, default_value), string.format('could not add param %s', name))
|
||||
local p = bind_param(PARAM_TABLE_PREFIX .. name)
|
||||
assert(p, string.format("count not find parameter %s", name))
|
||||
return p
|
||||
end
|
||||
|
||||
-- setup script specific parameters
|
||||
assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 5), 'could not add param table')
|
||||
|
||||
--[[
|
||||
// @Param: PREV_ENABLE
|
||||
// @DisplayName: parameter reversion enable
|
||||
// @Description: Enable parameter reversion system
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
// @User: Standard
|
||||
--]]
|
||||
local PREV_ENABLE = bind_add_param('ENABLE', 1, 0)
|
||||
|
||||
--[[
|
||||
// @Param: PREV_RC_FUNC
|
||||
// @DisplayName: param reversion RC function
|
||||
// @Description: RCn_OPTION number to used to trigger parameter reversion
|
||||
// @User: Standard
|
||||
--]]
|
||||
local PREV_RC_FUNC = bind_add_param('RC_FUNC', 2, 300)
|
||||
|
||||
-- params dictionary indexed by name
|
||||
local params = {}
|
||||
local param_saved = {}
|
||||
local param_count = 0
|
||||
|
||||
local ATC_prefixes = { "ATC", "Q_A" }
|
||||
local PSC_prefixes = { "PSC", "Q_P" }
|
||||
local PID_prefixes = { "_RAT_RLL_", "_RAT_PIT_", "_RAT_YAW_" }
|
||||
local PID_suffixes = { "FF", "P", "I", "D", "IMAX", "FLTD", "FLTE", "FLTT", "SMAX" }
|
||||
local angle_axes = { "RLL", "PIT", "YAW" }
|
||||
local PSC_types = { "ACCZ", "VELZ", "POSZ", "VELXY", "POSXY" }
|
||||
if PREV_ENABLE:get() == 0 then
|
||||
return
|
||||
end
|
||||
|
||||
local function add_param(pname)
|
||||
local p = bind_param(pname)
|
||||
if p then
|
||||
params[pname] = p
|
||||
param_saved[pname] = p:get()
|
||||
param_count = param_count + 1
|
||||
-- gcs:send_text(MAV_SEVERITY.INFO, string.format("Added %s", pname))
|
||||
end
|
||||
end
|
||||
|
||||
-- add rate PIDs
|
||||
for _, atc in ipairs(ATC_prefixes) do
|
||||
for _, prefix in ipairs(PID_prefixes) do
|
||||
for _, suffix in ipairs(PID_suffixes) do
|
||||
add_param(atc .. prefix .. suffix)
|
||||
end
|
||||
end
|
||||
end
|
||||
|
||||
-- add angle Ps
|
||||
for _, atc in ipairs(ATC_prefixes) do
|
||||
for _, axis in ipairs(angle_axes) do
|
||||
add_param(atc .. "_ANG_" .. axis .. "_P" )
|
||||
end
|
||||
end
|
||||
|
||||
-- add fixed wing tuning
|
||||
for _, suffix in ipairs(PID_suffixes) do
|
||||
add_param("RLL_RATE_" .. suffix)
|
||||
add_param("PIT_RATE_" .. suffix)
|
||||
add_param("YAW_RATE_" .. suffix)
|
||||
end
|
||||
|
||||
-- add PSC tuning
|
||||
for _, psc in ipairs(PSC_prefixes) do
|
||||
for _, ptype in ipairs(PSC_types) do
|
||||
for _, suffix in ipairs(PID_suffixes) do
|
||||
add_param(psc .. "_" .. ptype .. "_" .. suffix)
|
||||
end
|
||||
end
|
||||
end
|
||||
|
||||
|
||||
local function revert_parameters()
|
||||
local count = 0
|
||||
for pname, p in pairs(params) do
|
||||
local v1 = p:get()
|
||||
local v2 = param_saved[pname]
|
||||
if v1 ~= v2 then
|
||||
p:set_and_save(param_saved[pname])
|
||||
count = count + 1
|
||||
end
|
||||
end
|
||||
return count
|
||||
end
|
||||
|
||||
gcs:send_text(MAV_SEVERITY.INFO, string.format("Stored %u parameters", param_count))
|
||||
|
||||
local done_revert = false
|
||||
|
||||
-- main update function
|
||||
function update()
|
||||
local sw_pos = rc:get_aux_cached(PREV_RC_FUNC:get())
|
||||
if not sw_pos then
|
||||
return
|
||||
end
|
||||
if sw_pos == 2 and not done_revert then
|
||||
done_revert = true
|
||||
count = revert_parameters()
|
||||
gcs:send_text(MAV_SEVERITY.INFO, string.format("Reverted %u parameters", count))
|
||||
return
|
||||
end
|
||||
if sw_pos == 0 then
|
||||
done_revert = false
|
||||
end
|
||||
end
|
||||
|
||||
-- wrapper around update(). This calls update() at 10Hz,
|
||||
-- and if update faults then an error is displayed, but the script is not
|
||||
-- stopped
|
||||
function protected_wrapper()
|
||||
local success, err = pcall(update)
|
||||
if not success then
|
||||
gcs:send_text(MAV_SEVERITY.EMERGENCY, "Internal Error: " .. err)
|
||||
-- when we fault we run the update function again after 1s, slowing it
|
||||
-- down a bit so we don't flood the console with errors
|
||||
--return protected_wrapper, 1000
|
||||
return
|
||||
end
|
||||
return protected_wrapper, 1000/UPDATE_RATE_HZ
|
||||
end
|
||||
|
||||
-- start running update loop
|
||||
return protected_wrapper()
|
71
libraries/AP_Scripting/applets/revert_param.md
Normal file
71
libraries/AP_Scripting/applets/revert_param.md
Normal file
@ -0,0 +1,71 @@
|
||||
# Parameter Revert
|
||||
|
||||
This script implements a easy parameter reversion system to help with
|
||||
manual in-flight tuning. It allows you to do a wide range of manual
|
||||
tuning while flying and if you get in trouble (eg. an oscillation)
|
||||
then you can use a switch to instantly revert all the parameter
|
||||
changes to the values from startup.
|
||||
|
||||
# Parameters
|
||||
|
||||
The script adds 2 parameters to control it's behaviour. The parameters
|
||||
are:
|
||||
|
||||
## PREV_ENABLE
|
||||
|
||||
this must be set to 1 to enable the script
|
||||
|
||||
## PREV_RC_FUNC
|
||||
|
||||
The RCz_OPTIONS scripting function binding to be used for this script.
|
||||
Default RCz_OPTIONS binding is 300 (scripting1).
|
||||
|
||||
# Operation
|
||||
|
||||
Install the script in the APM/SCRIPTS folder on your microSD (you can
|
||||
use mavFTP for that). Then reboot and re-fetch parameters. You will
|
||||
find you now have PREV_ENABLE and PREV_RC_FUNC parameters.
|
||||
|
||||
Set PREV_ENABLE to 1 and set PREV_RC_FUNC to an available RC
|
||||
option. You would typically use 300 if not used by another
|
||||
script. Then set RCn_OPTION for your chosen R/C channel to revert
|
||||
parameter to the PREV_RC_FUNC value (eg. 300).
|
||||
|
||||
Now reboot to start the script. To test it try changing one of the
|
||||
covered parameter values while on the ground, then trigger the
|
||||
reversion with your R/C switch. Then fetch your parameters and you
|
||||
will see it has been reverted. You will see a message "Reverted N
|
||||
parameters" in the messages tab when this happens.
|
||||
|
||||
# Covered Parameters
|
||||
|
||||
The script covers the following parameters on quadplanes:
|
||||
|
||||
- Q_A_RAT_RLL_*
|
||||
- Q_A_RAT_PIT_*
|
||||
- Q_A_RAT_YAW_*
|
||||
- Q_A_ANG_RLL_P
|
||||
- Q_A_ANG_PIT_P
|
||||
- Q_A_ANG_YAW_P
|
||||
- RLL_RATE_*
|
||||
- PTCH_RATE_*
|
||||
- YAW_RATE_*
|
||||
- Q_P_ACCZ_*
|
||||
- Q_P_VELZ_*
|
||||
- Q_P_POSZ_*
|
||||
- Q_P_VELXY_*
|
||||
- Q_P_POSXY_*
|
||||
|
||||
The script covers the following parameters on copters:
|
||||
|
||||
- ATC_RAT_RLL_*
|
||||
- ATC_RAT_PIT_*
|
||||
- ATC_RAT_YAW_*
|
||||
- ATC_ANG_RLL_P
|
||||
- ATC_ANG_PIT_P
|
||||
- ATC_ANG_YAW_P
|
||||
- PSC_ACCZ_*
|
||||
- PSC_VELZ_*
|
||||
- PSC_POSZ_*
|
||||
- PSC_VELXY_*
|
||||
- PSC_POSXY_*
|
Loading…
Reference in New Issue
Block a user