# 参数设置

PX4 使用 *param subsystem *(floatint32_t 类型的二维表)和文本文件(用于混控器和启动脚本)来存储其配置。

本节详细讨论 param 子系统。 它涵盖如何列出、保存和加载参数,以及如何定义这些参数。

提示

系统启动 以及 机架配置 在其他页面上的详细工作方式。

# 命令行用法

PX4 系统控制台提供了参数工具,可用于设置参数,读取参数值,保存参数,以及导出和还原参数。

# 获取和设置参数

param show 命令列出所有系统参数:

param show

为了更具选择性,参数明可以使用通配符 "*":

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.

可以使用 -c 标志显示已更改的所有参数(从其默认值):

param show -c

您可以使用param show-for-airframe来显示所有修改了默认值的参数,只显示当前机架定义的文件(默认导入)。

# 导出和加载参数

您可以保存自上次将所有参数重置为其固件定义的默认值以来 touched 的任何参数(这包括已更改的任何参数,即使这些参数已更改为默认值)。

标准的 param save 命令将参数存储在当前默认文件中:

param save

如果提供了参数,它会将参数存储到这个新位置:

param save /fs/microsd/vtol_param_backup

有两个不同的命令可用于 load 参数:

  • param load 首先将所有参数完全重置为默认值,然后用存储在文件中的任何值覆盖参数值。
  • param import 只是用文件中的值覆盖参数值,然后保存结果(即有效调用 param save)。

load 有效地将参数重置为保存参数时的状态(我们说 "有效",因为保存在文件中的任何参数都将被更新,但其他参数可能有不同于参数文件创建时的固件定义默认值)。

相比之下,import 是将文件中的参数与无人机的当前状态合并。 例如,这可以用来只导入包含校准数据的参数文件,而不覆盖系统配置的其余部分。

这两种情况的示例如下所示:

# 文件保存时重置参数
param load /fs/microsd/vtol_param_backup
# 选择性的保存参数 (不自动加载)
param save
# 将保存的参数与当前参数合并
param import /fs/microsd/vtol_param_backup  

# 参数名称

参数名称不得超过 16 个 ASCII 字符。

  • orb_check() 告诉我们是否有 任何 更新 param_update 的 uorb 消息 (但不是受影响的参数),并设置 updated bool。
  • 如果更新了 "某些" 参数,我们会将更新复制到 parameter_update_s (param_upd)

按照惯例,组中的每个参数都应共享相同的 (有意义的) 字符串前缀,后跟下划线,MC_FW_ 用于与多旋翼或固定翼系统具体相关的参数。 此惯例不强制执行。

# C++ API

该名称必须在代码和 parameter metadatata 中匹配,才能正确地将参数与其元数据(包括固件中的默认值)相关联。

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.

API 之间的一个重要区别是,C++ 版本具有更有效的标准化机制,可与参数值的更改(即来自 GCS 的更改)同步。

# 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).

C++ API 提供像类属性一样的宏来声明参数。 您添加了一些"boilerplate"代码来定期监听 uORB topic任意 参数更新相关的更改。 然后,框架代码(在不可见的情况下)处理跟踪 uORB 消息,这些消息会影响您的参数属性并使它们保持同步。

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.

# 多实例(模块化)元数据

ModuleParams 派生类,并使用 DEFINE_PARAMETERS 指定参数李彪及其关联的参数属性。 参数的名称必须与其参数元数据定义相同。 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!

使用模板更新 CPP 文件,以检查与参数更新相关的 uORB 消息。

#include <px4_platform_common/module_params.h>

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.
     class MyModule : ..., public ModuleParams
{
public:
    ...
private:
    /**
     * Check for parameter changes and update them if needed.
     * @param parameter_update_sub uorb subscription to parameter_update
     */
    void parameters_update(int parameter_update_sub, bool force = false);
    DEFINE_PARAMETERS(
        (ParamInt<px4::params::SYS_AUTOSTART>) _sys_autostart,   /**< example parameter */
        (ParamFloat<px4::params::ATT_BIAS_MAX>) _att_bias_max  /**< another parameter */
    )
};

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

调用 parameters_update(parameter_update_sub); 在代码中定期检查是否有更新(这是模板):

#include <uORB/topics/parameter_update.h>

Subscribe to the update message when the module/driver starts and un-subscribe when it is stopped. parameter_update_sub returned by orb_subscribe() is a handle we can use to refer to this particular subscription.

# 订阅 parameter_update 消息
int parameter_update_sub = orb_subscribe(ORB_ID(parameter_update));
...
# 取消订阅 parameter_update 消息
orb_unsubscribe(parameter_update_sub);

然后,参数属性 (_sys_autostart_att_bias_max 在本例中) 可用于表示参数,并随时更新参数值的变化。

void Module::parameters_update(int parameter_update_sub, bool force)
{
    bool updated;
    struct parameter_update_s param_upd;
    // Check if any parameter updated
    orb_check(parameter_update_sub, &updated);
    // If any parameter updated copy it to: param_upd
    if (updated) {
        orb_copy(ORB_ID(parameter_update), parameter_update_sub, &param_upd);
    }
    if (force || updated) {
        // If any parameter updated, call updateParams() to check if
        // this class attributes need updating (and do so). 
        updateParams();
    }
}

In the above method:

  • YAML 参数元数据架构在此处: validation/module_schema.yaml (opens new window)
  • 正在使用的 YAML 定义示例可以在 MAVLink 参数定义中找到: /src/modules/mavlink/module.yaml (opens new window)
  • Then we call ModuleParams::updateParams(). This "under the hood" checks if the specific parameter attributes listed in our DEFINE_PARAMETERS list need updating, and then does so if needed.
  • This example doesn't call Module::parameters_update() with force=True. If you had other values that needed to be set up a common pattern is to include them in the function, and call it once with force=True during initialisation.

C API 可以在模块和驱动程序中使用。

提示

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>

param_find() 是一个“昂贵”操作,返回一个可以被 param_get() 使用的句柄。 如果要多次读取该参数,可以缓存句柄,并在需要时在 param_get() 中使用

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

注解

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.

提示

正确的元数据对于地面站的良好用户体验至关重要。 If you're going to read the parameter multiple times, you may cache the handle and use it in param_get() when needed

# 获取参数句柄
param_t my_param_handle = PARAM_INVALID;
my_param_handle = param_find("PARAM_NAME");
# 查询我们需要的参数
int32_t my_param = 0;
param_get(my_param_handle, &my_param);

# c 参数元数据

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.

提示

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

注意

添加了一个 新的 参数文件后,你应该在产生新参数(被添加的参数文件作为cmake配置步骤中的一部分,在清理构建和 cmake 被修改后会被添加)之前调用make clean。 Typically it is stored alongside its associated module.

传统方法是将定义的参数元数据写在一个扩展名为**.c**的文件中(在撰写本文时,这是源代码中最常用的方法)。

注意

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

注解

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

注释块中的行都是可选的,主要用于控制地面站内的显示和编辑选项。 下面给出了每行的用途(有关详细信息,请参阅 module_schema.yaml (opens new window))。

# Multi-Instance (Templated) YAML Meta Data

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

YAML 元数据是为了完全替换 .c 文件定义。 它支持所有相同的元数据,以及多实例定义等新功能。

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

YAML 参数定义 (opens new window) 支持模块化参数定义(不支持模块化参数代码)。

  • 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

以下 YAML 定义提供起始和结束索引。

关于完整的示例,请参阅MAVLink参数定义: /src/modules/mavlink/module.yaml (opens new window)

/**
 * Acceleration compensation based on GPS
 * velocity.
 *
 * @group Attitude Q estimator
 * @boolean
 */
PARAM_DEFINE_INT32(ATT_ACC_COMP, 1);
 *
 * @group Attitude Q estimator
 * @boolean
 */
PARAM_DEFINE_INT32(ATT_ACC_COMP, 1);
/**
 * <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.

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>
 */

# C / C++ API