mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting:Add parameter controller applet
This commit is contained in:
parent
03476704ce
commit
df90b640ca
|
@ -0,0 +1,94 @@
|
||||||
|
--[[
|
||||||
|
a script to select other parameters using an auxillary switch
|
||||||
|
from subdirectories in scripts directory labeled /1,/2, or /3
|
||||||
|
--]]
|
||||||
|
|
||||||
|
local SEL_CH = 302
|
||||||
|
local PARAM_FILENAME = "params.param"
|
||||||
|
|
||||||
|
--[[
|
||||||
|
check that directory exists
|
||||||
|
--]]
|
||||||
|
function check_subdir_exists(n)
|
||||||
|
return dirlist(get_scripts_dir() .. "/" .. n )
|
||||||
|
end
|
||||||
|
|
||||||
|
--[[
|
||||||
|
get the path to the scripts directory. This will be scripts/ on SITL
|
||||||
|
and APM/scripts on a ChibiOS board
|
||||||
|
--]]
|
||||||
|
function get_scripts_dir()
|
||||||
|
local dlist1 = dirlist("APM/scripts")
|
||||||
|
if dlist1 and #dlist1 > 0 then
|
||||||
|
return "APM/scripts"
|
||||||
|
end
|
||||||
|
-- otherwise assume scripts/
|
||||||
|
return "scripts"
|
||||||
|
end
|
||||||
|
|
||||||
|
--[[
|
||||||
|
load parameters from a file PARAM_FILENAME from directory n
|
||||||
|
--]]
|
||||||
|
function param_load(n)
|
||||||
|
count = 0
|
||||||
|
failed = false
|
||||||
|
file_name = get_scripts_dir() .. "/" .. n .."/" .. PARAM_FILENAME
|
||||||
|
-- Open file
|
||||||
|
file = io.open(file_name)
|
||||||
|
if not file then
|
||||||
|
gcs:send_text(0,string.format("%s not present",file_name))
|
||||||
|
return
|
||||||
|
end
|
||||||
|
while true do
|
||||||
|
local line = file:read()
|
||||||
|
if not line then
|
||||||
|
break
|
||||||
|
end
|
||||||
|
-- trim trailing spaces
|
||||||
|
line = string.gsub(line, '^(.-)%s*$', '%1')
|
||||||
|
local _, _, parm, value = string.find(line, "^([%w_]+)%s*([%d]*.[%d]*)")
|
||||||
|
if parm then
|
||||||
|
if not param:set(parm,value) then
|
||||||
|
failed = true
|
||||||
|
else
|
||||||
|
count = count +1
|
||||||
|
end
|
||||||
|
end
|
||||||
|
end
|
||||||
|
if not failed then
|
||||||
|
gcs:send_text(6,string.format("Loaded %u parameters",count))
|
||||||
|
else
|
||||||
|
gcs:send_text(6,string.format("Loaded %u parameters but some params did not exist to set",count))
|
||||||
|
end
|
||||||
|
end
|
||||||
|
|
||||||
|
local sw_last = -1
|
||||||
|
local load_param = true
|
||||||
|
|
||||||
|
function update()
|
||||||
|
local sw_current = rc:get_aux_cached(SEL_CH)
|
||||||
|
if (sw_current == sw_last) or (sw_current == nil) then
|
||||||
|
return update, 500
|
||||||
|
end
|
||||||
|
if sw_current == 0 then
|
||||||
|
subdir = 1
|
||||||
|
elseif sw_current == 2 then
|
||||||
|
subdir = 3
|
||||||
|
else
|
||||||
|
subdir = 2
|
||||||
|
end
|
||||||
|
sw_last = sw_current
|
||||||
|
if not check_subdir_exists(subdir) then
|
||||||
|
gcs:send_text(0,string.format("Scripts subdirectory /%s does not exist!",subdir))
|
||||||
|
return update, 500
|
||||||
|
end
|
||||||
|
if load_param then
|
||||||
|
param_load(subdir)
|
||||||
|
load_param = false
|
||||||
|
end
|
||||||
|
|
||||||
|
return update, 500
|
||||||
|
end
|
||||||
|
|
||||||
|
gcs:send_text(5,"Loaded Parameter_Controller.lua")
|
||||||
|
return update, 500
|
|
@ -0,0 +1,9 @@
|
||||||
|
# Param_Controller LUA script
|
||||||
|
|
||||||
|
This script allows the user to have different parameters (in files named "params.parm") in three subdirectories of the main scripting directory and load them based on the position of a switch with the auxiliary function of "302". This allows easy, at the field selection of parameter sets. It uses the same switch function and directories as the Scripting_Controller.lua script selector and the two may be used together, if desired.
|
||||||
|
|
||||||
|
# Setup and Operation
|
||||||
|
|
||||||
|
The user must setup an RCx_OPTION to function 302 to determine which of the three scripts subdirectories will be used: LOW:scripts/1, MIDDLE:scripts/2, or HIGH:scripts/3. If no RC has been established during ground start, it will behave as if subdirectory 1 is selected. Changing this switch position either prior to ground start or after, will load a "params.param" file from the desginated subdirectory (if it and its subdirectory exists). Mission Planner also provides a means of executing the same function as an RC switch assigned to 302 in its AUX Function tab, so a transmitter switch does not necessarily need to be used.
|
||||||
|
|
||||||
|
Note that loaded parameter changes are not saved across reboots, that must be done manually.
|
Loading…
Reference in New Issue