参数与配置
PX4使用 参数子系统(一个包含 float
和 int32_t
值的扁平表)和文本文件(用于启动脚本)来存储其配置。
本节详细探讨 参数 子系统,涵盖如何列出、保存和加载参数,以及如何定义这些参数并使其在地面站上显示。
命令行使用方法
PX4 系统控制台 提供了 param 工具,可用于设置参数、读取参数值、保存参数,以及导出和还原文件。
获取和设置参数
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
仅显示当前机架定义文件(及其导入的默认值)中所有已从默认值更改的参数。
导出和加载参数
可以保存任何已更改的参数(与机架默认值不同)。
标准的 param save
命令会将参数存储在当前默认文件中:
param save
如果提供了参数,它会将参数存储到指定的新位置:
param save /fs/microsd/vtol_param_backup
加载参数有两个不同的命令:
param load
首先会将所有参数完全重置为默认值,然后用文件中存储的任何值覆盖参数值。param import
只需用文件中的值覆盖参数值,然后保存结果(即实际上调用了param save
)。
load
操作有效地将参数重置为保存参数时的状态(说“有效”是因为文件中保存的任何参数都会被更新,但其他参数的固件定义默认值可能与创建参数文件时不同)。
相比之下,import
会将文件中的参数与飞行器的当前状态合并。例如,这可用于仅导入包含校准数据的参数文件,而不覆盖系统配置的其余部分。
以下是这两种情况的示例:
# 文件保存时重置参数
param load /fs/microsd/vtol_param_backup
# 选择性的保存参数 (不自动加载)
param save
# 将保存的参数与当前参数合并
param import /fs/microsd/vtol_param_backup
参数创建/定义
参数定义包含两部分:
以下介绍编写元数据和代码的几种方法。在可能的情况下,代码应使用较新的 YAML 元数据 和 C++ API,与旧的 C 参数/代码定义相比,它们更灵活、更健壮。
参数元数据会 编译到固件中,并通过 MAVLink 组件信息服务 提供。
参数名称
参数名称不得超过 16 个 ASCII 字符。
按照惯例,组中的每个参数都应共享相同的(有意义的)字符串前缀,后跟下划线,“MC_”和“FW_” 用于专门与多旋翼或固定翼系统相关的参数。不过此惯例并非强制要求。
名称必须在代码和 参数元数据 中保持一致,以便将参数与其元数据(包括固件中的默认值)正确关联。
C / C++ API
有单独的 C 和 C++ API 可用于从 PX4 模块和驱动程序中访问参数值。
API 之间的一个重要区别是,C++ 版本具有更有效的标准化机制,可与参数值的更改(即来自地面控制站的更改)同步。
同步很重要,因为参数可能随时被更改为另一个值。代码应始终使用参数存储中的当前值。如果无法获取最新版本,则需要在更改参数后重新启动(使用 @reboot_required
元数据设置此要求)。
此外,C++ 版本具有更好的类型安全性和更小的 RAM 开销。缺点是参数名称必须在编译时确定,而 C 语言 API 可以将动态创建的名称作为字符串。
C++ API
C++ API 提供了将参数声明为 类属性 的宏。需要添加一些“样板”代码,以定期监听与任何参数更新相关的 uORB 主题。框架代码随后(在不可见的情况下)处理追踪影响 uORB 消息,并保持参数属性和 uORB 消息同步。在代码的其余部分,只需使用定义的参数属性,它们将始终是最新的!
首先,在模块或驱动程序的类头文件中包含所需的头文件:
px4_platform_common/module_params.h 以获取
DEFINE_PARAMETERS
宏:cpp#include <px4_platform_common/module_params.h>
parameter_update.h 以访问 uORB
parameter_update
消息:cpp#include <uORB/topics/parameter_update.h>
Subscription.hpp 用于 uORB C++ 订阅 API:
cpp#include <uORB/Subscription.hpp>
从 ModuleParams
派生类,并使用 DEFINE_PARAMETERS
指定参数列表及其相关参数属性。参数的名称必须与其参数元数据定义相同。
class MyModule : ..., public ModuleParams
{
public:
...
private:
/**
* 检查参数是否更改,如有需要则更新。
*/
void parameters_update();
DEFINE_PARAMETERS(
(ParamInt<px4::params::SYS_AUTOSTART>) _sys_autostart, /**< 示例参数 */
(ParamFloat<px4::params::ATT_BIAS_MAX>) _att_bias_max /**< 另一个参数 */
)
// 订阅
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
};
在 CPP 文件中使用模板来检查与参数更新相关的 uORB 消息。
在代码中定期调用 parameters_update();
以检查是否有更新:
void Module::parameters_update()
{
if (_parameter_update_sub.updated()) {
parameter_update_s param_update;
_parameter_update_sub.copy(¶m_update);
// 如果有任何参数更新,调用 updateParams() 检查
// 此类属性是否需要更新(如有需要则更新)。
updateParams();
}
}
在上述方法中:
_parameter_update_sub.updated()
告知我们param_update
uORB 消息是否有更新(但不指明受影响的参数)。- 如果有“一些”参数更新,我们将更新复制到
parameter_update_s
(param_update
) 中,以清除待处理的更新。 - 然后调用
ModuleParams::updateParams()
。 这个操作会在“幕后”更新DEFINE_PARAMETERS
列表中列出的所有参数属性。
参数属性(在这种情况下为 _sys_autostart
和 _att_bias_max
)可用于表示参数,并在参数值发生变化时自动更新。
C API
C API 可在模块和驱动程序中使用。
首先包含参数 API 头文件:
#include <parameters/param.h>
然后检索参数并将其分配给变量(这里是 my_param
),如下所示,参数名为 PARAM_NAME
。变量 my_param
随后可在模块代码中使用。
int32_t my_param = 0;
param_get(param_find("PARAM_NAME"), &my_param);
INFO
如果 PARAM_NAME
在参数元数据中声明了参数,则会设置其默认值,并且上述查找参数的调用应始终成功。
param_find()
是一个“昂贵”的操作,它返回一个可供 param_get()
使用的句柄。如果要多次读取参数,可以缓存句柄并在需要时使用 param_get()
:
# 获取参数的句柄
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);
参数元数据
PX4 使用广泛的参数元数据系统来驱动面向用户的参数表示,并设置固件中每个参数的默认值。
TIP
正确的元数据对于地面站良好的用户体验至关重要。
参数元数据可以存储在源树中的任何位置,例如 .c 或 .yaml 参数定义(YAML 定义较新,且更灵活)。通常,它与关联的模块一起存储。
参数元数据可以通过(使用 make parameters_metadata
)构建 参数参考 和地面站 使用的参数信息。
WARNING
添加新的参数文件后,在构建以生成新参数之前应调用 make clean
(参数文件作为 cmake 配置步骤的一部分添加,这适用于干净构建和修改 cmake 文件)。
YAML 元数据
INFO
在编写本文时,YAML 参数定义不能在库中使用。
YAML 元数据旨在完全替代 .c 定义。它支持所有相同的元数据,以及多实例定义等新功能。
YAML 参数元数据模式位于:validation/module_schema.yaml。
正在使用的 YAML 定义示例可在 MAVLink 参数定义中找到:/src/modules/mavlink/module.yaml。
通过添加到 cmake 构建系统中来注册一个 YAML 文件,在该模块的
CMakeLists.txt
文件的px4_add_module
部分添加:cmakeMODULE_CONFIG module.yaml
多实例(模块化)YAML 元数据
YAML 参数定义 支持模板化参数定义(不支持模板化参数代码)。
YAML 允许使用 ${i}
在参数名称、描述等中定义实例号。例如,下面的定义将生成 MY_PARAM_1_RATE、MY_PARAM_2_RATE 等。
MY_PARAM_${i}_RATE:
description:
short: Maximum rate for instance ${i}
以下 YAML 定义提供起始和结束索引:
num_instances
(默认值为 1):要生成的实例数量(>=1)。instance_start
(默认值为 0):第一个实例编号。如果为 0,${i}
扩展为[0, N - 1]
。
有关完整示例,请参阅 MAVLink 参数定义:/src/modules/mavlink/module.yaml
C 参数元数据
定义参数元数据的传统方法是在扩展名为 .c 的文件中进行(在编写本文时,这是源树中最常用的方法)。
参数的元数据部分看起来像下面的例子:
/**
* 俯仰比例增益
*
* 俯仰比例增益,即误差为 1 弧度时所需的角速度(弧度/秒)。
*
* @unit 1/s
* @min 0.0
* @max 10
* @decimal 2
* @increment 0.0005
* @reboot_required true
* @group 多旋翼姿态控制
*/
PARAM_DEFINE_FLOAT(MC_PITCH_P, 6.5f);
/**
* 基于 GPS 速度的加速度补偿
*
* @group 姿态四元数估计器
* @boolean
*/
PARAM_DEFINE_INT32(ATT_ACC_COMP, 1);
末尾的 PARAM_DEFINE_*
宏指定参数的类型(PARAM_DEFINE_FLOAT
或 PARAM_DEFINE_INT32
)、参数的名称(必须与代码中使用的名称匹配)和固件中的默认值。
注释块中的行都是可选的,主要用于控制地面站内的显示和编辑选项。每行的用途如下(更多详细信息请参见 module_schema.yaml):
/**
* <标题>
*
* <更详细的描述,可以多行>
*
* @unit <单位,例如米用 m 表示>
* @min <合理的最小值。用户可以覆盖此值>
* @max <合理的最大值。用户可以覆盖此值>
* @decimal <小数位数>
* @increment <在用户界面中此值递增的“步长”>
* @reboot_required true <如果更改此参数需要系统重启,请添加此选项>
* @boolean <对于表示布尔值的整数参数,请添加此选项>
* @group <参数组的标题>
*/
发布参数的元数据到地面站
参数元数据 JSON 文件被编译到固件中(或托管在互联网上),并通过 MAVLink 组件元数据服务 提供。这确保了元数据始终与飞行器上运行的代码保持最新。
此过程与 事件元数据 类似。有关更多信息,请参阅 PX4 元数据(翻译与发布)。