PX4二次开发——uorb订阅
一、写在前面
我们写了一个一个功能的模块,这些模块并不是独立的。模块之间是有数据传递的,这样才能组合到一起实现飞行控制的目的。那么解决模块之间的数据传递的方式就是通过uorb订阅的方式。
下面举一个例子,包含了飞控串口读取外部传感器数据,飞控开启一个进程读取外部传感器发布一个 UORB 主题,另一个进程订阅前一个进程发布的主题,还有就是订阅到的主题通过 mavlink 消息发送到地面站。走了一个完整的飞控数据链路(UORB 链路和 MAVLINK 链路)。
二、新增一个自定义UORB主题
下面是源码的msg文件夹下面是飞控所有的UORB主题,这里展示的就是你所能够从现有系统订阅发布的主题,当然你还可以自定义自己需要的主题消息。
可以看到 vehicle_global_position.msg 载具全球位置,vehicle_attitude_setpoint.msg 载具姿态消息,这 个姿态消息很重要如下所示::
我们可以看到姿态的成员变量,包括横滚 roll, 俯仰 pitch,偏航 yaw, 横滚速度,俯仰速度等 等相关姿态的数据。相关的加速度计,磁力计,陀螺仪经过算法滤波整合之后会发布姿态数 据,而姿态控制进程会订阅这个 vehicle_attitude_setpoint.msg 主题。这个模式很像 linux 的消息队列, 或者进程间通信的手段。
1.1 自己定义一个主题
我们在 msg 文件夹下面添加添加一个具体的消息,比如我们的消息是
Laser_gun.msg 和 laser_gun_shoot.msg 消息。消息的成员函数可以参照其他原有的消息来写。Msg 文件里面的成员如下:
注意:新版本后每个msg都需要建立一个时间辍uint64 timestamp
这个结构体成员是自己定义的。修改 cmakelist 脚本可以让这个消息生成相应的 uorb 头文件。这个 Cmakelinst 和 msg消息是同目录的,然后我们需要cmakelsit能够把我们写的被编译路径包括,点开该文件下的cmakelist,我们修改如下:
当于把消息名字添加到这个 Cmakelist 里面,在编译源码的是就把这个消息主题相应的.h头文件自动写好了,不要我们自己写。到这里我们 make px4_fmu-v3_default 一把。结果如下:
然后在源码的~/src/Firmware/build_px4_fmu-v3_default/uORB/topics 这个文件夹下面可以看到我们自定义消息的头文件。结果如下:
[外链图片转存失败,源站可能有防盗链机制,建议将图片保存下来直接上传(img-
我们可以看到和我们在msg文件夹里面定义成员的一样。而这个结构体名为laser_gun_shoot_s,我们在以后的订阅发布进程里面,包含这个头文件就可以顺利使用了。
三、使用UORB
3.1 发布一个自定义消息
这里路径一定要修改对!
#include <stdio.h>
#include <termios.h>
#include <unistd.h>
#include <stdlib.h>
#include <string.h>
#include <stdbool.h>
#include <errno.h>
#include <drivers/drv_hrt.h>
#include <systemlib/err.h>
#include <fcntl.h>
#include <systemlib/mavlink_log.h>
#include <uORB/uORB.h>
#include <uORB/topics/test_uorb.h>
#include <px4_platform_common/defines.h>
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/posix.h>
#include <px4_platform_common/tasks.h>
#include <px4_time.h>
static bool thread_should_exit = false;
static bool thread_running = false;
static int px4_uorb_adver_task;
__EXPORT int px4_uorb_adver_main(int argc, char *argv[]);
int px4_uorb_adver_thread_main(int argc, char *argv[]);
static void usage(const char *reason);
static void
usage(const char *reason)
{
if (reason) {
warnx("%s\n", reason);
}
warnx("usage: px4_uorb_adver {start|stop|status} [-p <additional params>]\n\n");
}
int px4_uorb_adver_main(int argc, char *argv[])
{
if (argc < 2) {
usage("missing command");
return 1;
}
if (!strcmp(argv[1], "start")) {
if (thread_running) {
warnx("daemon already running\n");
return 0;
}
thread_should_exit = false;
px4_uorb_adver_task = px4_task_spawn_cmd("px4_uorb_adver",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
2000,
px4_uorb_adver_thread_main,
(argv) ? (char *const *)&argv[2] : (char *const *)NULL);
return 0;
}
if (!strcmp(argv[1], "stop")) {
thread_should_exit = true;
return 0;
}
if (!strcmp(argv[1], "status")) {
if (thread_running) {
warnx("\trunning\n");
} else {
warnx("\tnot started\n");
}四、
return 0;
}
usage("unrecognized command");
return 1;
}
int px4_uorb_adver_thread_main(int argc, char *argv[])
{
struct test_uorb_s test_uorb_ad;
memset(&test_uorb_ad, 0 , sizeof(test_uorb_ad));
orb_advert_t test_pub = orb_advertise(ORB_ID(test_uorb), &test_uorb_ad);
warnx("[daemon] starting\n");
thread_running = true;
while (!thread_should_exit) {
test_uorb_ad.test1 = 5;
test_uorb_ad.test2 = 6;
orb_publish(ORB_ID(test_uorb), test_pub, &test_uorb_ad);
usleep(1000);
}
warnx("[daemon] exiting.\n");
thread_running = false;
return 0;
}
3.2 订阅一个自定义消息
#include <stdio.h>
#include <termios.h>
#include <unistd.h>
#include <stdlib.h>
#include <string.h>
#include <stdbool.h>
#include <errno.h>
#include <drivers/drv_hrt.h>
#include <systemlib/err.h>
#include <fcntl.h>
#include <systemlib/mavlink_log.h>
#include <uORB/uORB.h>
#include <uORB/topics/test_uorb.h>
#include <px4_platform_common/defines.h>
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/posix.h>
#include <px4_platform_common/tasks.h>
#include <px4_time.h>
static bool thread_should_exit = false;
static bool thread_running = false;
static int px4_uorb_subs_task;
__EXPORT int px4_uorb_subs_main(int argc, char *argv[]);
int px4_uorb_subs_thread_main(int argc, char *argv[]);
static void usage(const char *reason);
static void
usage(const char *reason)
{
if (reason) {
warnx("%s\n", reason);
}
warnx("usage: px4_uorb_adver {start|stop|status} [-p <additional params>]\n\n");
}
int px4_uorb_subs_main(int argc, char *argv[])
{
if (argc < 2) {
usage("missing command");
return 1;
}
if (!strcmp(argv[1], "start")) {
if (thread_running) {
warnx("px4_uorb_subs already running\n");
return 0;
}
thread_should_exit = false;
px4_uorb_subs_task = px4_task_spawn_cmd("px4_uorb_subs",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
2000,
px4_uorb_subs_thread_main,
(argv) ? (char *const *)&argv[2] : (char *const *)NULL);
return 0;
}
if (!strcmp(argv[1], "stop")) {
thread_should_exit = true;
return 0;
}
if (!strcmp(argv[1], "status")) {
if (thread_running) {
warnx("\trunning\n");
} else {
warnx("\tnot started\n");
}
return 0;
}
usage("unrecognized command");
return 1;
}
int px4_uorb_subs_thread_main(int argc, char *argv[])
{
warnx("[px4_uorb_subs] starting\n");
int test_sub_fd = orb_subscribe(ORB_ID(test_uorb));
struct test_uorb_s test_uorb_sub;
memset(&test_uorb_sub, 0 , sizeof(test_uorb_sub));
int test1 = 0,test2 = 0;
thread_running = true;
while (!thread_should_exit) {
warnx("Hello px4_uorb_subs!\n");
bool updated;
orb_check(test_sub_fd, &updated);
if (updated)
{
orb_copy(ORB_ID(test_uorb),test_sub_fd,&test_uorb_sub);
test1 = test_uorb_sub.test1;
test2 = test_uorb_sub.test2;
}
warnx("test_uorb.test1 = %d, test_uorb.test2 = %d ,test_uorb.test3 = %d\n",test1,test2);
usleep(500);
}
warnx("[px4_uorb_subs] exiting.\n");
thread_running = false;
return 0;
}
四、修改编译脚本和启动脚本
参照之前即可,这里启动脚本没有修改,通过mavlink控制进程的开关,如若需要开机启动在机型那个子启动脚本start即可
五、总结
在linux中,万物皆文件。
自制主题注意:
- 在msg文件夹中创建自己的XXX.msg,新版需要加时间辍
- 把自己主题加入消息的编译脚本中
- 编译完成会在build->UORB中生成一个中包含XXX_s结构体头文件
- 使用这个包含#include <uORB/uORB.h> #include <uORB/topics/test_uorb.h>
订阅发布注意:
- 新建模块文件夹,新建C文件,新建CMAKELIST文件
- 在子编译脚本中加入自己模块名字等,在总编译加入自己的模块名字
本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)