PX4/Pixhawk 教程 - 可视化参数配置和自启动 - param

px4常见的设置模块自启动的方式有两种,一种是在rx.xxx文件中添加需要启动的项,另一种是通过yaml参数配置文件。

通过添加系统启动项

通过修改系统的启动项实现模块的自启动:

px4/ROMFS/px4fmu_common/init.d/rc.xxx,xxx为类别的名称,目录截图如下:
在这里插入图片描述

这种方式的优点是可以为不同的机型设置不同的启动项,缺点是如果启动指令添加可变参数角为困难。

通过yaml文件配置参数

在模块的目录(CMakeLists)下新建module.yaml文件,例子如下:

module_name: Lanbao PSK-CM8JL65-CC5
serial_config:
    - command: cm8jl65 start -d ${SERIAL_DEV} -R p:SENS_CM8JL65_R_0
      port_config_param:
        name: SENS_CM8JL65_CFG
        group: Sensors

parameters:
    - group: Sensors
      definitions:
        SENS_CM8JL65_R_0:
            description:
                short: Distance Sensor Rotation
                long: |
                    Distance Sensor Rotation as MAV_SENSOR_ORIENTATION enum

            type: enum
            values:
                25: ROTATION_DOWNWARD_FACING
                24: ROTATION_UPWARD_FACING
                12: ROTATION_BACKWARD_FACING
                0: ROTATION_FORWARD_FACING
                6: ROTATION_LEFT_FACING
                2: ROTATION_RIGHT_FACING
            reboot_required: true
            default: 25
  • module_name:是模块名称,当不同的模块有同一个参数,就是通过这个名字来分辨;

  • serial_config:串口配置,模块添加了这个参数就会按里面的参数自动启动

    • command: 自动启动的指令,这个指令支持3个变量,(1)${SERIAL_DEV} 串口设备的路径(如/dev/ttyS1);(2)${BAUD_PARAM} 串口配置的波特率; (3)${i} instance in [0, N-1] (for multi-instance commands)
    • port_config_param: 这个参数的配置信息,包含的主要子节点(1)name,参数名称,字符串,主义不能超过16个字符;(2)group,分类,就是在QGC时这个参数的父级目录名称。(3)description_extended,描述信息,会在QGC里面出现。
  • parameters: 模块的参数列表。

    • group: 同上
    • definitions:参数定义,SENS_CM8JL65_R_0是这个参数的名称。这个参数用有以下子节点:(1)description,描述,描述字段又用有两个子节点,一个是short,短的描述,一个是long长的描述。这个会在QGC里显示;(2) type,类型,表明这个参数的类型有'int32', 'float', 'boolean', 'enum', 'bitmask'等值;(3)default:默认值;(4)value:用于enum类型,提供可选的值列表;(5)reboot_required: 是否需要重启生效;(6)minmax,可选,参数的最大值和最小值,仅支持int和float类型;(7)decimal,可选,显示的小数位数,仅支持float类型;(8)increment,可选,仅用于GCS下的浮点型;(9)unit,可选,单位。

支持的单位有:
| ‘%’, ‘Hz’, ‘mAh’, |
| | ‘rad’, ‘%/rad’, ‘rad/s’, ‘rad/s^2’, ‘%/rad/s’, ‘rad s^2/m’,‘rad s/m’, |
| | ‘bit/s’, ‘B/s’, |
| | ‘deg’, ‘deg1e7’, ‘deg/s’, |
| | ‘celcius’, ‘gauss’, ‘gauss/s’, ‘mgauss’, ‘mgauss^2’, |
| | ‘hPa’, ‘kg’, ‘kg/m^2’, ‘kg m^2’, |
| | ‘mm’, ‘m’, ‘m/s’, ‘m^2’, ‘m/s^2’, ‘m/s^3’, ‘m/s^2/sqrt(Hz)’, ‘m/s/rad’, |
| | ‘Ohm’, ‘V’, |
| | ‘us’, ‘ms’, ‘s’, |
| | ‘S’, ‘A/%’, ‘(m/s2)2’, ‘m/m’, ‘tan(rad)^2’, ‘(m/s)^2’, ‘m/rad’, |
| | ‘m/s^3/sqrt(Hz)’, ‘m/s/sqrt(Hz)’, 's/(1000
PWM)’, ‘%m/s’, ‘min’, ‘us/C’, |
| | ‘N/(m/s)’, ‘Nm/(rad/s)’, ‘Nm’, ‘N’, |
| | ‘normalized_thrust/s’, ‘normalized_thrust’, ‘norm’, ‘SD’ |

添加完module.yaml后,需要在CMAkeLists中添加配置信息:

px4_add_module(
	MODULE drivers__cm8jl65
	MAIN cm8jl65
	SRCS
		CM8JL65.cpp
		CM8JL65.hpp
		cm8jl65_main.cpp
	MODULE_CONFIG
		module.yaml
	DEPENDS
		drivers_rangefinder
	)

编译成功下载后,在csh里面输入以下指令可以看到新添加的参数

param show

如果要查询RC_MAP_A开头的参数:

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

除了命令行的方式,还可以在QGC的parameter的可视化里面看到参数:
在这里插入图片描述

获取参数的c和cpp接口

未完待续

参考:

px4文档-配置参数

  • 1
    点赞
  • 9
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值