Adding parameters via scripting

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!

7 Likes

This is really nice.
Thanks…

1 Like

Hellow, i am new to lua scripting!
First of all thank’s for this example, i tried the example on github but i had an error, yours example works great!
I just want to ask @Yuri_Rage how can i read the value of a new parameter for example(ROUGH_SPEED) in the “QUICK” tab, is it possible?
Thank you for your time!

gcs:send_named_float() is what you’re looking for.

Thank you very much for that tip @Yuri_Rage

I will attach also an example that i found in examples in github, i hope to help someone else!

Thanks for all of your scripting discussions @Yuri_Rage . I’m hoping to learn more about this soon, and have in mind a particular application for a script. Based on your post I would imagine it would work, but would it be possible to “swap” parameters based on a script trigger? I have a copter that I can fly on 3 or 4S, but when switching between those batteries, naturally I need to change some parameters. Do you know if this would be a viable use for a script?

Certainly possible. Just need to establish said trigger as something available within the scripting bindings.

Good news! Thank you. I’ll start doing some reading up in the wiki on this.

This is a great way to add parameter to the autopilot, however I am facing an issue regarding the ‘non-volatility’ of the parameters.
I tried adding a custom parameter named COUNT_TOT_FLIGHT which I intend to increment everytime the copter takes a flight.
The process I am following is as stated below:
I created a script named “addParam.lua” that has the following code.

local PARAM_TABLE_KEY = 80
assert(param:add_table(PARAM_TABLE_KEY, "COUNT_", 1), 'could not add param table')
assert(param:add_param(PARAM_TABLE_KEY, 1,  'TOT_FLIGHT', 0), 'could not add the param')

local TOT_FLIGHT = Parameter()
TOT_FLIGHT:init('COUNT_TOT_FLIGHT')
local total_flights = TOT_FLIGHT:get()
param:set('COUNT_TOT_FLIGHT', total_flights)

if total_flights == 0.0 then
    gcs:send_text(7, "Parameter COUNT_TOTAL_FLIGHT set to value " .. tostring(total_flights))
else 
    gcs:send_text(7, "Parameter COUNT_TOTAL_FLIGHT Not set! Something went wrong..")
end

I uploaded this script on the flight controller. I get the confirmation message that the parameter is set to 0. The parameter ‘COUNT_TOT_FLIGHT’ is also visible in the parameter list.

Then I delete this script and upload another script named “flight_counts.lua” that has the following code.

local TOT_FLIGHT = Parameter()
TOT_FLIGHT:init('COUNT_TOT_FLIGHT')
local total_flights = TOT_FLIGHT:get()

if (vehicle:get_likely_flying()) then
    total_flights = total_flights + 1
    param:set('COUNT_TOT_FLIGHT', total_flights)
    gcs:send_text(7, "Flight Number = " .. tostring(total_flights))

else
    gcs:send_text(7, "Param not found !!!!!!!!!! = " )
end

But on booting with this script, the parameter COUNT_TOT_FLIGHT is not visible and accessible to this new script. Basically that parameter gets deleted.

This is mentioned in the documentation: “LUA created parameters exist in the same manner as firmware created parameters. User/Script changes are stored in non-volatile memory. But their names only exist for a lookup if a “param:add_table” and “param:add_param” has been executed after bootup by a script. Then they will appear in the GCS parameter list and can be accessed by name from LUA scripts. Without this, the data would still exist in non-volatile memory, but is invisible and non-existent for all intents and purposes.” So I changed the flight_counts.lua to:

local PARAM_TABLE_KEY = 80
assert(param:add_table(PARAM_TABLE_KEY, "COUNT_", 1), 'could not add param table')
assert(param:add_param(PARAM_TABLE_KEY, 1,  'TOT_FLIGHT', 0), 'could not add the param')

local TOT_FLIGHT = Parameter()
TOT_FLIGHT:init('COUNT_TOT_FLIGHT')
local total_flights = TOT_FLIGHT:get()

if (vehicle:get_likely_flying()) then
    total_flights = total_flights + 1
    param:set('COUNT_TOT_FLIGHT', total_flights)
    gcs:send_text(7, "Flight Number = " .. tostring(total_flights))
else
    gcs:send_text(7, "Param not found !!!!!!!!!! = " )
end

But now everytime I boot the flight controller, the value of the parameter starts from 0 and is not saved for the next boot.
Any solutions about how I can save the parameter permanently on the flight controller?

Thanks!

Use the set_and_save binding…

Thanks a lot for the reply. It works now.