AP_Scripting: added bindings for adding parameter tables

This commit is contained in:
Andrew Tridgell 2022-01-07 16:26:14 +11:00 committed by Peter Barker
parent 1343af85e2
commit 10b1f46997
3 changed files with 50 additions and 0 deletions

View File

@ -963,6 +963,20 @@ function param:set(name, value) end
---@return number|nil
function param:get(name) end
-- desc
---@param table_key number
---@param prefix string
---@param num_params number
---@return boolean
function param:add_table(table_key, prefix, num_params) end
-- desc
---@param table_key number
---@param param_num number
---@param name string
---@param default_value number
---@return boolean
function param::add_param(table_key, param_num, name, default_value) end
-- desc
---@class esc_telem

View File

@ -0,0 +1,34 @@
-- example for adding parameters to a lua script
-- the table key must be used by only one script on a particular flight
-- controller. If you want to re-use it then you need to wipe your old parameters
-- the key must be a number between 0 and 200. The key is persistent in storage
local PARAM_TABLE_KEY = 72
-- create a parameter table with 2 parameters in it. A table can have
-- at most 63 parameters. The table size for a particular table key
-- cannot increase without a reboot. The prefix "MY_" is used with
-- every parameter in the table. This prefix is used to ensure another
-- script doesn't use the same PARAM_TABLE_KEY.
assert(param:add_table(PARAM_TABLE_KEY, "MY_", 2), 'could not add param table')
-- create two parameters. The param indexes (2nd argument) must
-- be between 1 and 63. All added parameters are floats, with the given
-- default value (4th argument).
assert(param:add_param(PARAM_TABLE_KEY, 1, 'TEST', 3.14), 'could not add param1')
assert(param:add_param(PARAM_TABLE_KEY, 2, 'TEST2', 5.7), 'could not add param2')
gcs:send_text(0, string.format("Added two parameters"))
-- bind a parameter to a variable
function bind_param(name)
local p = Parameter()
assert(p:init(name), string.format('could not find %s parameter', name))
return p
end
local param1 = bind_param("MY_TEST")
local param2 = bind_param("MY_TEST2")
gcs:send_text(0, string.format("param1=%f", param1:get()))
gcs:send_text(0, string.format("param2=%f", param2:get()))

View File

@ -298,6 +298,8 @@ singleton AP_Param method set_by_name boolean string float'skip_check
singleton AP_Param method set_by_name alias set
singleton AP_Param method set_and_save_by_name boolean string float'skip_check
singleton AP_Param method set_and_save_by_name alias set_and_save
singleton AP_Param method add_table boolean uint8_t 0 200 string uint8_t 1 63
singleton AP_Param method add_param boolean uint8_t 0 200 uint8_t 1 63 string float'skip_check
include AP_Scripting/AP_Scripting_helpers.h
userdata Parameter method init boolean string