PX4模块设计之四十五:param模块
Posted lida2003
tags:
篇首语:本文由小常识网(cha138.com)小编为大家整理,主要介绍了PX4模块设计之四十五:param模块相关的知识,希望对你有一定的参考价值。
PX4模块设计之四十五:param模块
1. param模块简介
### Description
Command to access and manipulate parameters via shell or script.
This is used for example in the startup script to set airframe-specific parameters.
Parameters are automatically saved when changed, eg. with `param set`. They are typically stored to FRAM
or to the SD card. `param select` can be used to change the storage location for subsequent saves (this will
need to be (re-)configured on every boot).
If the FLASH-based backend is enabled (which is done at compile time, e.g. for the Intel Aero or Omnibus),
`param select` has no effect and the default is always the FLASH backend. However `param save/load <file>`
can still be used to write to/read from files.
Each parameter has a 'used' flag, which is set when it's read during boot. It is used to only show relevant
parameters to a ground control station.
### Examples
Change the airframe and make sure the airframe's default parameters are loaded:
$ param set SYS_AUTOSTART 4001
$ param set SYS_AUTOCONFIG 1
$ reboot
param <command> [arguments...]
Commands:
load Load params from a file (overwrite all)
[<file>] File name (use default if not given)
import Import params from a file
[<file>] File name (use default if not given)
save Save params to a file
[<file>] File name (use default if not given)
dump Dump params from a file
[<file>] File name (use default if not given)
select Select default file
[<file>] File name
select-backup Select default file
[<file>] File name
show Show parameter values
[-a] Show all parameters (not just used)
[-c] Show only changed params (unused too)
[-q] quiet mode, print only param value (name needs to be exact)
[<filter>] Filter by param name (wildcard at end allowed, eg. sys_*)
show-for-airframe Show changed params for airframe config
status Print status of parameter system
set Set parameter to a value
<param_name> <value> Parameter name and value to set
[fail] If provided, let the command fail if param is not found
set-default Set parameter default to a value
[-s] If provided, silent errors if parameter doesn't exists
<param_name> <value> Parameter name and value to set
[fail] If provided, let the command fail if param is not found
compare Compare a param with a value. Command will succeed if equal
[-s] If provided, silent errors if parameter doesn't exists
<param_name> <value> Parameter name and value to compare
greater Compare a param with a value. Command will succeed if param is
greater than the value
[-s] If provided, silent errors if parameter doesn't exists
<param_name> <value> Parameter name and value to compare
<param_name> <value> Parameter name and value to compare
touch Mark a parameter as used
[<param_name1> [<param_name2>]] Parameter name (one or more)
reset Reset only specified params to default
[<param1> [<param2>]] Parameter names to reset (wildcard at end allowed)
reset_all Reset all params to default
[<exclude1> [<exclude2>]] Do not reset matching params (wildcard at end
allowed)
index Show param for a given index
<index> Index: an integer >= 0
index_used Show used param for a given index
<index> Index: an integer >= 0
find Show index of a param
<param> param name
注:print_usage函数是具体对应实现。
2. 模块入口函数param_main
该模块纯C语言风格,没有C++类继承或者C/C++混合的编码风格,整体看起来就很清爽。
注:C++设计一定要建模,一定要做好概念抽象。至于C/C++那种混合的编程风格,笔者是不建议的。
param_main
├──> <argc < 2> // 参数不够,直接提供打印帮助!!!
│ └──> print_usage()
├──> <!strcmp(argv[1], "save")> // save 子命令
│ ├──> <argc >= 3>
│ │ └──> do_save(argv[2])
│ └──> <else>
│ └──> do_save_default()
├──> <!strcmp(argv[1], "dump")> // dump 子命令
│ ├──> <argc >= 3>
│ │ └──> do_dump(argv[2])
│ └──> <else>
│ └──> do_dump(param_get_default_file())
├──> <!strcmp(argv[1], "load")> // load 子命令
│ ├──> <argc >= 3>
│ │ └──> do_load(argv[2])
│ └──> <else>
│ └──> do_load(param_get_default_file())
├──> <!strcmp(argv[1], "import")> // import 子命令
│ ├──> <argc >= 3>
│ │ └──> do_import(argv[2])
│ └──> <else>
│ └──> do_import()
├──> <!strcmp(argv[1], "select")> // select 子命令
│ ├──> <argc >= 3>
│ │ └──> param_set_default_file(argv[2])
│ ├──> <else>
│ │ └──> param_set_default_file(nullptr)
│ ├──> const char *default_file = param_get_default_file()
│ └──> <default_file> PX4_INFO("selected parameter default file %s", default_file)
├──> <!strcmp(argv[1], "select-backup")> // select-backup 子命令
│ ├──> <argc >= 3>
│ │ └──> param_set_backup_file(argv[2])
│ ├──> <else>
│ │ └──> param_set_backup_file(nullptr)
│ ├──> const char *backup_file = param_get_backup_file()
│ └──> <backup_file> PX4_INFO("selected parameter backup file %s", backup_file)
├──> <!strcmp(argv[1], "show")> // show 子命令
│ ├──> <argc >= 3>
│ │ ├──> <!strcmp(argv[2], "-c")> // optional argument -c to show only non-default params
│ │ │ ├──> <argc >= 4>
│ │ │ │ └──> do_show(argv[3], true)
│ │ │ └──> <else>
│ │ │ └──> do_show(nullptr, true)
│ │ ├──> <!strcmp(argv[2], "-a")>
│ │ │ └──> do_show_all()
│ │ ├──> <!strcmp(argv[2], "-q")>
│ │ │ └──> <argc >= 4> do_show_quiet(argv[3])
│ │ └──> <else>
│ │ └──> do_show(argv[2], false)
│ └──> <else>
│ └──> do_show(nullptr, false)
├──> <!strcmp(argv[1], "show-for-airframe")> // show-for-airframe 子命令
│ └──> do_show_for_airframe()
├──> <!strcmp(argv[1], "status")> // status 子命令
│ └──> param_print_status()
├──> <!strcmp(argv[1], "set")> // set 子命令
│ ├──> <argc >= 5>
│ │ ├──> bool fail = !strcmp(argv[4], "fail") //if the fail switch is provided, fails the command if not found
│ │ └──> return do_set(argv[2], argv[3], fail)
│ └──> <argc >= 4> do_set(argv[2], argv[3], false)
├──> <!strcmp(argv[1], "set-default")> // set-default 子命令
│ ├──> <argc >= 5 && !strcmp(argv[2], "-s")> do_set_custom_default(argv[3], argv[4], true)
│ └──> <argc == 4> do_set_custom_default(argv[2], argv[3])
├──> <!strcmp(argv[1], "compare")> // compare 子命令
│ ├──> <argc >= 5 && !strcmp(argv[2], "-s")> do_compare(argv[3], &argv[4], argc - 4, COMPARE_OPERATOR::EQUAL, COMPARE_ERROR_LEVEL::SILENT)
│ └──> <argc >= 4> do_compare(argv[2], &argv[3], argc - 3, COMPARE_OPERATOR::EQUAL, COMPARE_ERROR_LEVEL::DO_ERROR)
├──> <!strcmp(argv[1], "greater")> // greater 子命令
│ ├──> <argc >= 5 && !strcmp(argv[2], "-s")> do_compare(argv[3], &argv[4], argc - 4, COMPARE_OPERATOR::GREATER, COMPARE_ERROR_LEVEL::SILENT)
│ └──> <argc >= 4> do_compare(argv[2], &argv[3], argc - 3, COMPARE_OPERATOR::GREATER, COMPARE_ERROR_LEVEL::DO_ERROR)
├──> <!strcmp(argv[1], "reset")> //reset 子命令
│ └──> <argc >= 3> do_reset_specific((const char **) &argv[2], argc - 2)
├──> <!strcmp(argv[1], "reset_all")> //reset_all 子命令
│ ├──> <argc >= 3>
│ │ └──> do_reset_all((const char **) &argv[2], argc - 2)
│ └──> <else>
│ └──> do_reset_all(nullptr, 0)
├──> <!strcmp(argv[1], "touch")> // touch 子命令
│ └──> <argc >= 3> do_touch((const char **) &argv[2], argc - 2)
├──> <!strcmp(argv[1], "index_used")> // index_used 子命令
│ └──> <argc >= 3> do_show_index(argv[2], true)
├──> <!strcmp(argv[1], "index")> // index 子命令
│ └──> <argc >= 3> do_show_index(argv[2], false)
└──> <!strcmp(argv[1], "find")> // find 子命令
└──> <argc >= 3> do_find(argv[2])
3 重要函数列表
所有参数相关操作都是使用了Parameters API,关于全局参数存储 Parameters API这里不做展开,详见:src/lib/Parameters, param.h
- do_save
- do_save_default
- do_dump
- do_load
- do_import
- param_set_default_file
- param_set_backup_file
- do_show
- do_show_for_airframe
- param_print_status
- do_set
- do_set_custom_default
- do_compare
- do_reset_specific
- do_reset_all
- do_touch
- do_show_index
- do_find
4. 总结
该模块主要提供了系统参数的动态更新/固化保存,以及提供了参数修正的底层操作方法。
5. 参考资料
【1】PX4开源软件框架简明简介
【2】PX4模块设计之十一:Built-In框架
【3】PX4模块设计之十二:High Resolution Timer设计
【4】PX4模块设计之十三:WorkQueue设计
【5】PX4模块设计之十七:ModuleBase模块
【6】PX4模块设计之三十:Hysteresis类
【7】PX4 modules_main
以上是关于PX4模块设计之四十五:param模块的主要内容,如果未能解决你的问题,请参考以下文章