Did you know that you can fairly easily add your own parameters to ArduPilot?!
It’s actually a fairly well documented yet seldom used feature that I just discovered myself after some excellent discussions with the dev team.
As described in the wiki (linked above), parameters added by scripting must be explicitly initialized on each boot cycle by a script, otherwise, they will not be made available for script access or editing across a MAVLink connection.
What’s very cool is that the values will be retained in EEPROM even if a script has not activated them, so you have a non-volatile, unambiguous mechanism to store and retrieve script data at will, and your scripts can interact with these values just like any other parameter. You are not always bound to use the SCR_USERx
parameter set!
The wiki covers things reasonably well, but I can understand a little bit of confusion when it comes to implementing custom parameters in your own scripts. To ease the pain, I’ve written a function that takes care of it somewhat cleanly. Here’s a snippet from my rover-TerrainDetector.lua
script that will likely be merged with libraries/AP_Scripting/examples in the near future:
local PARAM_TABLE_KEY = 117 -- unique index value between 0 and 200
-- create custom parameter set
local function add_params(key, prefix, tbl)
assert(param:add_table(key, prefix, #tbl), string.format('Could not add %s param table.', prefix))
for num = 1, #tbl do
assert(param:add_param(key, num, tbl[num][1], tbl[num][2]), string.format('Could not add %s%s.', prefix, tbl[num][1]))
end
end
-- edit this function call to suit your use case
add_params(PARAM_TABLE_KEY, 'ROUGH_', {
-- { name, default value },
{ 'SPEED', 0.7 },
{ 'GZ_MAX', 1.33 },
{ 'RATE_MAX', 28 },
{ 'GZ_GAIN', 0.9 },
{ 'RATE_GAIN', 0.8 },
{ 'TIMEOUT_MS', 7500 }
})
This snippet adds ROUGH_SPEED, ROUGH_GZ_MAX, etc parameters for access by any active script and allows a user to tune script behavior without editing the script or restarting the scripting engine.
It’s important to note that the default value for each parameter must be specified during script initialization, regardless of whether that parameter already exists in EEPROM, but the value WILL NOT be overwritten by the specified default if the parameter already exists (again, a non-volatile mechanism).
I hope that’s helpful!