PX4模块设计之十一:Built-In框架
Posted lida2003
tags:
篇首语:本文由小常识网(cha138.com)小编为大家整理,主要介绍了PX4模块设计之十一:Built-In框架相关的知识,希望对你有一定的参考价值。
PX4模块设计之十一:Built-In框架
前面介绍了PX4模块设计之十:PX4启动过程,在应用上,最为重要的阶段就是飞控应用初始化,这个过程是通过nsh启动脚本实现的。也许对于linux bash熟悉的同学会马上说“这不就是进程按照顺序启动嘛”。当然这个说法是不错的,那么现在的问题是Nuttx没有进程的概念。
注:当然在px4模拟程序里面确实大家看到了大量的二进制bin文件,那是因为在Linux系统上模拟。那么可以想想也许他是通过函数调用的方式进行任务的启动,如果采用这种方式就必须知道这些应用的函数入口。
网上搜了下资料,关于这块的内容其实并没有太多的介绍,也许太简单,也许应用的角度不需要关注。但是从理解和逻辑的角度我们更应该知道整个应用是如何启动起来的,这属于框架设计的一部分。
接下来我们就来看看这个启动是如何依赖脚本实现的。
1. Nuttx Built-In框架
NuttX是一个实时操作系统,主要强调POSIX和ANSI标准的兼容性,同时占用资源小。适合于8位或者更高的MCU环境。但是该系统与Linux不同步区分内核态和用户态,整个系统在一个地址空间。
这里先给出Nuttx NSH Build-In Framework,这个使我们理解的基础,虽然部分内容和实际代码有所差异,但是可以看出大概的思路。
通过builtin_list.c代码,可以看出有builtin_list被添加到了g_builtins数组。
41 #include "builtin_proto.h"
42
43 const struct builtin_s g_builtins[] =
44
45 # include "builtin_list.h"
46 NULL, 0, 0, 0
47 ;
48
49 const int g_builtin_count = sizeof(g_builtins) / sizeof(g_builtins[0]);
到这里,我们可以比较清楚的理解Nuttx下是如何将引用和NSH联系起来的。接下去我们要重点关注当前PX4代码是如何将PX4下的应用和NSH联系起来的。
2. PX4 Built-In框架
PX4 Built-In框架框架涉及两部分:
- Nuttx Built-In应用
- PX4 Built-In应用
注:这里使用holybro_kakutef7作为例子。
2.1 NSH Built-In关联文件
两个关联文件(函数定义和符号表数组),其中大部分是PX4的应用:
注:NSH应用是sercon_main、serdis_main、nsh_main、sh_main。
platforms\\nuttx\\NuttX\\apps\\builtin\\builtin_proto.h
int sercon_main(int argc, char *argv[]);
int atxxxx_main(int argc, char *argv[]);
int bmp280_main(int argc, char *argv[]);
int board_adc_main(int argc, char *argv[]);
int dshot_main(int argc, char *argv[]);
int frsky_telemetry_main(int argc, char *argv[]);
int icm20689_main(int argc, char *argv[]);
int mpu6000_main(int argc, char *argv[]);
int pwm_out_main(int argc, char *argv[]);
int rc_input_main(int argc, char *argv[]);
int manual_control_main(int argc, char *argv[]);
int attitude_estimator_q_main(int argc, char *argv[]);
int battery_status_main(int argc, char *argv[]);
int commander_main(int argc, char *argv[]);
int control_allocator_main(int argc, char *argv[]);
int dataman_main(int argc, char *argv[]);
int flight_mode_manager_main(int argc, char *argv[]);
int land_detector_main(int argc, char *argv[]);
int logger_main(int argc, char *argv[]);
int mavlink_main(int argc, char *argv[]);
int mc_att_control_main(int argc, char *argv[]);
int mc_pos_control_main(int argc, char *argv[]);
int mc_rate_control_main(int argc, char *argv[]);
int navigator_main(int argc, char *argv[]);
int rc_update_main(int argc, char *argv[]);
int sensors_main(int argc, char *argv[]);
int mixer_main(int argc, char *argv[]);
int param_main(int argc, char *argv[]);
int pwm_main(int argc, char *argv[]);
int nsh_main(int argc, char *argv[]);
int sh_main(int argc, char *argv[]);
int serdis_main(int argc, char *argv[]);
platforms\\nuttx\\NuttX\\apps\\builtin\\builtin_list.h
"sh", 100, 2048, sh_main ,
"sercon", SCHED_PRIORITY_DEFAULT, 2048, sercon_main ,
"atxxxx", SCHED_PRIORITY_DEFAULT, 2048, atxxxx_main ,
"bmp280", SCHED_PRIORITY_DEFAULT, 2048, bmp280_main ,
"board_adc", SCHED_PRIORITY_DEFAULT, 2048, board_adc_main ,
"dshot", SCHED_PRIORITY_DEFAULT, 2048, dshot_main ,
"frsky_telemetry", SCHED_PRIORITY_DEFAULT, 2048, frsky_telemetry_main ,
"icm20689", SCHED_PRIORITY_DEFAULT, 2048, icm20689_main ,
"mpu6000", SCHED_PRIORITY_DEFAULT, 2048, mpu6000_main ,
"pwm_out", SCHED_PRIORITY_DEFAULT, 2048, pwm_out_main ,
"rc_input", SCHED_PRIORITY_DEFAULT, 2048, rc_input_main ,
"manual_control", SCHED_PRIORITY_DEFAULT, 2048, manual_control_main ,
"attitude_estimator_q", SCHED_PRIORITY_DEFAULT, 2048, attitude_estimator_q_main ,
"battery_status", SCHED_PRIORITY_DEFAULT, 2048, battery_status_main ,
"commander", SCHED_PRIORITY_DEFAULT, 2048, commander_main ,
"control_allocator", SCHED_PRIORITY_DEFAULT, 3000, control_allocator_main ,
"dataman", SCHED_PRIORITY_DEFAULT, 2048, dataman_main ,
"flight_mode_manager", SCHED_PRIORITY_DEFAULT, 2048, flight_mode_manager_main ,
"land_detector", SCHED_PRIORITY_DEFAULT, 2048, land_detector_main ,
"logger", SCHED_PRIORITY_MAX-30, 2048, logger_main ,
"mavlink", SCHED_PRIORITY_DEFAULT, 2048, mavlink_main ,
"mc_att_control", SCHED_PRIORITY_DEFAULT, 2048, mc_att_control_main ,
"mc_pos_control", SCHED_PRIORITY_DEFAULT, 2048, mc_pos_control_main ,
"mc_rate_control", SCHED_PRIORITY_DEFAULT, 2048, mc_rate_control_main ,
"navigator", SCHED_PRIORITY_DEFAULT, 2048, navigator_main ,
"rc_update", SCHED_PRIORITY_DEFAULT, 2048, rc_update_main ,
"sensors", SCHED_PRIORITY_DEFAULT, 2048, sensors_main ,
"mixer", SCHED_PRIORITY_DEFAULT, 4096, mixer_main ,
"param", SCHED_PRIORITY_DEFAULT, 2048, param_main ,
"pwm", SCHED_PRIORITY_DEFAULT, 2048, pwm_main ,
"nsh", 100, 2048, nsh_main ,
"serdis", SCHED_PRIORITY_DEFAULT, 2048, serdis_main ,
2.2 NSH Built-In关联文件生成
关联文件是通过Makefile脚本通过将.pdat/.bdat文件中的内容合并生成的。
27 # Registry entry lists
28
29 PDATLIST = $(strip $(call RWILDCARD, registry, *.pdat))
30 BDATLIST = $(strip $(call RWILDCARD, registry, *.bdat))
31
32 builtin_list.c: builtin_list.h builtin_proto.h
33
34 registry$(DELIM).updated:
35 $(Q) touch registry$(DELIM).updated
36
37 builtin_list.h: registry$(DELIM).updated
38 ifeq ($(BDATLIST),)
39 $(call DELFILE, builtin_list.h)
40 $(Q) touch builtin_list.h
41 else
42 $(call CATFILE, builtin_list.h, $(BDATLIST))
43 endif
44
45 builtin_proto.h: registry$(DELIM).updated
46 ifeq ($(PDATLIST),)
47 $(call DELFILE, builtin_proto.h)
48 $(Q) touch builtin_proto.h
49 else
50 $(call CATFILE, builtin_proto.h, $(PDATLIST))
51 endif
2.3 NSH Built-In注册文件生成
通过分析,可以看到找到各个文件的主要出处如下:
- platforms\\nuttx\\NuttX\\CMakeLists.txt ==》 px4 px4_kernel
- platforms\\nuttx\\NuttX\\apps\\system\\nsh ==》 nsh sh
- platforms\\nuttx\\NuttX\\apps\\system\\cdcacm ==》sercon serdis
注:px4.bdat/.pdat是px4的应用,其他是Nuttx的应用。
./platforms/nuttx/NuttX/apps/builtin/registry/
├── px4.bdat
├── px4.pdat
├── nsh.bdat
├── nsh.pdat
├── sercon.bdat
├── sercon.pdat
├── serdis.bdat
├── serdis.pdat
├── sh.bdat
└── sh.pdat
注:Google/Baidu并没有给出什么信息。PX4论坛上也咨询了下,不过没有什么反馈。估计大家的重点是在应用。How .bdat/.pdat files generated in NuttX/apps/builtin/registry/? 。
2.4 NSH应用.pdat/.bdat生成途径
NSH应用的Makefile文件会提前引用
include $(APPDIR)/Make.defs
该文件platforms\\nuttx\\NuttX\\apps\\Make.defs将每个应用的入口函数通过符号重命名脚本define.sh进行了整理,输出到注册文件中。
86 define REGISTER
87 $(Q) echo Register: $1
88 $(Q) echo \\"$1\\", $2, $3, $4 , > "$(BUILTIN_REGISTRY)$(DELIM)$1.bdat"
89 $(Q) if [ ! -z $4 ]; then \\
90 echo "int $4(int argc, char *argv[]);" > "$(BUILTIN_REGISTRY)$(DELIM)$1.pdat"; \\
91 fi;
92 $(Q) touch "$(BUILTIN_REGISTRY)$(DELIM).updated"
93 endef
2.5 PX4应用.pdat/.bdat生成途径
PX4应用的符号通过CMakeList下的px4_add_module添加到全局变量,并在通过.in文件输出到.bdat/.pdat注册文件
111 configure_file($CMAKE_CURRENT_SOURCE_DIR/px4_kernel.bdat.in $CMAKE_CURRENT_BINARY_DIR/px4_kernel.bdat)
112 configure_file($CMAKE_CURRENT_SOURCE_DIR/px4_kernel.pdat.in $CMAKE_CURRENT_BINARY_DIR/px4_kernel.pdat)
...
117 COMMAND $CMAKE_COMMAND -E copy_if_different $CMAKE_CURRENT_BINARY_DIR/px4_kernel.bdat kernel_builtin_list.h
118 COMMAND $CMAKE_COMMAND -E copy_if_different $CMAKE_CURRENT_BINARY_DIR/px4_kernel.pdat kernel_builtin_proto.h
...
125 configure_file($CMAKE_CURRENT_SOURCE_DIR/px4.bdat.in $CMAKE_CURRENT_BINARY_DIR/px4.bdat)
126 configure_file($CMAKE_CURRENT_SOURCE_DIR/px4.pdat.in $CMAKE_CURRENT_BINARY_DIR/px4.pdat)
...
138 COMMAND $CMAKE_COMMAND -E copy_if_different $CMAKE_CURRENT_BINARY_DIR/px4.bdat $APPS_DIR/builtin/registry/px4.bdat
139 COMMAND $CMAKE_COMMAND -E copy_if_different $CMAKE_CURRENT_BINARY_DIR/px4.pdat $APPS_DIR/builtin/registry/px4.pdat
3. Nuttx Built-In代码实现
执行脚本最关键的Built-In函数是下面两个:
- builtin_isavail
- builtin_for_index
nsh_script
└──> nsh_parse
└──> nsh_parse_command
└──> nsh_execute
└──> nsh_builtin
└──> exec_builtin
├──> builtin_isavail
├──> builtin_for_index
└──> task_spawn(builtin->name, builtin->main, &file_actions,
&attr, (argv) ? &argv[1] : (FAR char * const *)NULL,
(FAR char * const *)NULL);
3.1 builtin_isavail
lib_builtin_isavail.c 实现了builtin_isavail函数,确认命令是否未有效Built-In命令。
56 int builtin_isavail(FAR const char *appname)
57
58 FAR const char *name;
59 int i;
60
61 for (i = 0; (name = builtin_getname(i)) != NULL; i++)
62
63 if (strcmp(name, appname) == 0)
64
65 return i;
66
67
68
69 return -ENOENT;
70
3.2 builtin_for_index
lib_builtin_forindex.c实现了builtin_for_index函数,返回该命令相关执行参数(优先级,堆栈大小,函数入口符号等)。
52 FAR const struct builtin_s *builtin_for_index(int index)
53
54 if (index < g_builtin_count)
55
56 return &g_builtins[index];
57
58
59 return NULL;
60
4. 总结
-
Nuttx官网的Built-In介绍的REGISTER和实际PX4工程的主要差异是PX4采用的.bdat/.pdat中间文件的方式(详见:2.4 NSH应用.pdat/.bdat生成途径)
-
PX4使用了大量的submodule,相关整合方面的介绍比较欠缺,尤其是工程面的。(对于C背景的研发人员可能会有一点的不习惯。通常C背景的会将每行代码都搞得一清二楚。不想现在大量使用组件方式,不太关注框架,更重视应用的快节奏。)
-
关于符号重命名脚本define.sh这里没有展开,感兴趣的朋友可以自己研究,其主要功能就是将main符号转换成另一个不重复的符号,比如:sh_main
-Dmain=shmain
5. 参考资料
【1】PX4开源软件框架简明简介
【2】PX4开源工程结构简明介绍
【3】Nuttx NSH Build-In Framework
以上是关于PX4模块设计之十一:Built-In框架的主要内容,如果未能解决你的问题,请参考以下文章