# Parameters & Configurations

PX4 uses the param subsystem (a flat table of float and int32_t values) and text files (for startup scripts) to store its configuration.

This section discusses the param subsystem in detail. It covers how to list, save and load parameters, and how to define them and make them available to ground stations.

TIP

System startup and the way that frame configuration startup scripts work are detailed on other pages.

# Command Line Usage

The PX4 system console offers the param tool, which can be used to set parameters, read their value, save them, and export and restore to/from files.

# Getting and Setting Parameters

The param show command lists all system parameters:

param show

To be more selective, a partial parameter name with wildcard "*" can be used:

nsh> param show RC_MAP_A*
Symbols: x = used, + = saved, * = unsaved
x   RC_MAP_AUX1 [359,498] : 0
x   RC_MAP_AUX2 [360,499] : 0
x   RC_MAP_AUX3 [361,500] : 0
x   RC_MAP_ACRO_SW [375,514] : 0

 723 parameters total, 532 used.

You can use the -c flag to show all parameters that have changed (from their defaults):

param show -c

You can use param show-for-airframe to show all parameters that have changed from their defaults for just the current airframe's definition file (and defaults it imports).

# Exporting and Loading Parameters

You can save any parameters that have been changed (that are different from airframe defaults).

The standard param save command will store the parameters in the current default file:

param save

If provided with an argument, it will store the parameters instead to this new location:

param save /fs/microsd/vtol_param_backup

There are two different commands to load parameters:

  • param load first does a full reset of all parameters to their defaults, and then overwrites parameter values with any values stored in the file.
  • param import just overwrites parameter values with the values from the file and then saves the result (i.e. effectively calls param save).

The load effectively resets the parameters to the state when the parameters were saved (we say "effectively" because any parameters saved in the file will be updated, but other parameters may have different firmware-defined default values than when the parameters file was created).

By contrast, import merges the parameters in the file with the current state of the vehicle. This can be used, for example, to just import a parameter file containing calibration data, without overwriting the rest of the system configuration.

Examples for both cases are shown below:

# Reset the parameters to when file was saved
param load /fs/microsd/vtol_param_backup
# Optionally save params (not done automatically with load)
param save
# Merge the saved parameters with current parameters
param import /fs/microsd/vtol_param_backup

# Creating/Defining Parameters

Parameters definitions have two parts:

  • Parameter metadata specifies the default value for each parameter in firmware along with other metadata for presentation (and editing) of parameters in ground control stations and documentation.
  • C/C++ Code that provides access to get and/or subscribe to parameter values from within PX4 modules and drivers.

Several approaches are described below for writing both the metadata and code. Where possible code should use newer YAML metadata and C++ API over the older C parameter/code definitions, as these are more flexible and robust.

Parameter metadata is compiled into the firmware, and made available to ground stations via the MAVLink Component Information service (opens new window).

# Parameter Names

Parameter names must be no more than 16 ASCII characters.

By convention, every parameter in a group should share the same (meaningful) string prefix followed by an underscore, and MC_ and FW_ are used for parameters related specifically to Multicopter or Fixed-wing systems. This convention is not enforced.

The name must match in both code and parameter metadata to correctly associate the parameter with its metadata (including default value in Firmware).

# C / C++ API

There are separate C and C++ APIs that can be used to access parameter values from within PX4 modules and drivers.

One important difference between the APIs is that the C++ version has a more efficient standardized mechanism to synchronize with changes to parameter values (i.e. from a GCS).

Synchronization is important because a parameter can be changed to another value at any time. Your code should always use the current value from the parameter store. If getting the latest version is not possible, then a reboot will be required after the parameter is changed (set this requirement using the @reboot_required metadata).

In addition, the C++ version has also better type-safety and less overhead in terms of RAM. The drawback is that the parameter name must be known at compile-time, while the C API can take a dynamically created name as a string.

# C++ API

The C++ API provides macros to declare parameters as class attributes. You add some "boilerplate" code to regularly listen for changes in the uORB Topic associated with any parameter update. Framework code then (invisibly) handles tracking uORB messages that affect your parameter attributes and keeping them in sync. In the rest of the code you can just use the defined parameter attributes and they will always be up to date!

First include the required needed headers in the class header for your module or driver:

  • px4_platform_common/module_params.h to get the DEFINE_PARAMETERS macro:
    #include <px4_platform_common/module_params.h>
    
  • parameter_update.h to access the uORB parameter_update message:
    #include <uORB/topics/parameter_update.h>
    
  • Subscription.hpp for the uORB C++ subscription API:
    #include <uORB/Subscription.hpp>
    

Derive your class from ModuleParams, and use DEFINE_PARAMETERS to specify a list of parameters and their associated parameter attributes. The names of the parameters must be the same as their parameter metadata definitions.

class MyModule : ..., public ModuleParams
{
public:
	...

private:

	/**
	 * Check for parameter changes and update them if needed.
	 */
	void parameters_update();

	DEFINE_PARAMETERS(
		(ParamInt<px4::params::SYS_AUTOSTART>) _sys_autostart,   /**< example parameter */
		(ParamFloat<px4::params::ATT_BIAS_MAX>) _att_bias_max  /**< another parameter */
	)

	// Subscriptions
	uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};

};

Update the cpp file with boilerplate to check for the uORB message related to parameter updates.

Call parameters_update(); periodically in code to check if there has been an update:

void Module::parameters_update()
{
	if (_parameter_update_sub.updated()) {
		parameter_update_s param_update;
		_parameter_update_sub.copy(&param_update);

		// If any parameter updated, call updateParams() to check if
		// this class attributes need updating (and do so).
		updateParams();
	}
}

In the above method:

  • _parameter_update_sub.updated() tells us if there is any update to the param_update uORB message (but not what parameter is affected).
  • If there has been "some" parameter updated, we copy the update into a parameter_update_s (param_update), to clear the pending update.
  • Then we call ModuleParams::updateParams(). This "under the hood" updates all parameter attributes listed in our DEFINE_PARAMETERS list.

The parameter attributes (_sys_autostart and _att_bias_max in this case) can then be used to represent the parameters, and will be updated whenever the parameter value changes.

TIP

The Application/Module Template uses the new-style C++ API but does not include parameter metadata.

# C API

The C API can be used within both modules and drivers.

First include the parameter API:

#include <parameters/param.h>

Then retrieve the parameter and assign it to a variable (here my_param), as shown below for PARAM_NAME. The variable my_param can then be used in your module code.

int32_t my_param = 0;
param_get(param_find("PARAM_NAME"), &my_param);

Note

If PARAM_NAME was declared in parameter metadata then its default value will be set, and the above call to find the parameter should always succeed.

param_find() is an "expensive" operation, which returns a handle that can be used by param_get(). If you're going to read the parameter multiple times, you may cache the handle and use it in param_get() when needed

# Get the handle to the parameter
param_t my_param_handle = PARAM_INVALID;
my_param_handle = param_find("PARAM_NAME");

# Query the value of the parameter when needed
int32_t my_param = 0;
param_get(my_param_handle, &my_param);

# Parameter Metadata

PX4 uses an extensive parameter metadata system to drive the user-facing presentation of parameters, and to set the default value for each parameter in firmware.

TIP

Correct metadata is critical for good user experience in a ground station.

Parameter metadata can be stored anywhere in the source tree as either .c or .yaml parameter definitions (the YAML definition is newer, and more flexible). Typically it is stored alongside its associated module.

The build system extracts the metadata (using make parameters_metadata) to build the parameter reference and the parameter information used by ground stations.

WARNING

After adding a new parameter file you should call make clean before building to generate the new parameters (parameter files are added as part of the cmake configure step, which happens for clean builds and if a cmake file is modified).

# YAML Metadata

Note

At time of writing YAML parameter definitions cannot be used in libraries.

YAML meta data is intended as a full replacement for the .c definitions. It supports all the same metadata, along with new features like multi-instance definitions.

# Multi-Instance (Templated) YAML Meta Data

Templated parameter definitions are supported in YAML parameter definitions (opens new window) (templated parameter code is not supported).

The YAML allows you to define instance numbers in parameter names, descriptions, etc. using ${i}. For example, below will generate MY_PARAM_1_RATE, MY_PARAM_2_RATE etc.

MY_PARAM_${i}_RATE:
            description:
                short: Maximum rate for instance ${i}

The following YAML definitions provide the start and end indexes.

  • num_instances (default 1): Number of instances to generate (>=1)
  • instance_start (default 0): First instance number. If 0, ${i} expands to [0, N-1]`.

For a full example see the MAVLink parameter definitions: /src/modules/mavlink/module.yaml (opens new window)

# c Parameter Metadata

The legacy approach for defining parameter metadata is in a file with extension .c (at time of writing this is the approach most commonly used in the source tree).

Parameter metadata sections look like the following examples:

/**
 * Pitch P gain
 *
 * Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad.
 *
 * @unit 1/s
 * @min 0.0
 * @max 10
 * @decimal 2
 * @increment 0.0005
 * @reboot_required true
 * @group Multicopter Attitude Control
 */
PARAM_DEFINE_FLOAT(MC_PITCH_P, 6.5f);
/**
 * Acceleration compensation based on GPS
 * velocity.
 *
 * @group Attitude Q estimator
 * @boolean
 */
PARAM_DEFINE_INT32(ATT_ACC_COMP, 1);

The PARAM_DEFINE_* macro at the end specifies the type of parameter (PARAM_DEFINE_FLOAT or PARAM_DEFINE_INT32), the name of the parameter (which must match the name used in code), and the default value in firmware.

The lines in the comment block are all optional, and are primarily used to control display and editing options within a ground station. The purpose of each line is given below (for more detail see module_schema.yaml (opens new window)).

/**
 * <title>
 *
 * <longer description, can be multi-line>
 *
 * @unit <the unit, e.g. m for meters>
 * @min <the minimum sane value. Can be overridden by the user>
 * @max <the maximum sane value. Can be overridden by the user>
 * @decimal <the minimum sane value. Can be overridden by the user>
 * @increment <the "ticks" in which this value will increment in the UI>
 * @reboot_required true <add this if changing the param requires a system restart.>
 * @boolean <add this for integer parameters that represent a boolean value>
 * @group <a title for parameters that form a group>
 */

# Publishing Parameter Metadata to a GCS

Parameter metadata is collected into a JSON or XML file during each PX4 build.

For most flight controllers (as most have enough FLASH available), the JSON file is xz-compressed and stored within the generated binary. The file is then shared to ground stations using the MAVLink Component Information Protocol (opens new window). This ensures that parameter metadata is always up-to-date with the code running on the vehicle.

Binaries for flight controller targets with constrained memory do not store the parameter metadata in the binary, but instead reference the same data stored on px4-travis.s3.amazonaws.com. This applies, for example, to the Omnibus F4 SD. The metadata is uploaded via github CI (opens new window) for all build targets (and hence will only be available once parameters have been merged into master).

Note

You can identify memory constrained boards because they specify CONFIG_BOARD_CONSTRAINED_FLASH=y in their px4board definition file (opens new window).

Note

The metadata on px4-travis.s3.amazonaws.com is used if parameter metadata is not present on the vehicle. It may also be used as a fallback to avoid a very slow download over a low-rate telemetry link.

Anyone doing custom development on a FLASH-constrained board can adjust the URL here (opens new window) to point to another server.

The XML file of the master branch is copied into the QGC source tree via CI and is used as a fallback in cases where no metadata is available via the component information service (this approach predates the existence of the component information protocol).

# Further Information