导读
uORB是PX4/Pixhawk系统中非常重要且关键的模块之一,是用于无人机模块间通信的协议机制。本篇将详细介绍uORB并详细拆解uORB消息读写与自定义实验(一)。
基础实验篇 | uORB消息读写与自定义实验(一)
ect Request Broker,微对象请求代理器)是PX4/Pixhawk系统中非常重要且关键的一个模块,它肩负了整个系统的数据传输任务,所有的传感器数据、GPS、PPM信号等都要从芯片获取后通过uORB进行传输到各个模块进行计算处理。实际上uORB是一套跨「进程」 的IPC通讯模块。在Pixhawk中, 所有的功能被独立以进程模块为单位进行实现并工作。而进程间的数据交互就由为重要,必须要能够符合实时、有序的特点。在PX4中,uORB是用于无人机模块间通信的协议机制。
01
uORB消息简介
uORB(Micro Object Request Broker,微对象请求代理器)是PX4/Pixhawk系统中非常重要且关键的一个模块,它肩负了整个系统的数据传输任务,所有的传感器数据、GPS、PPM信号等都要从芯片获取后通过uORB进行传输到各个模块进行计算处理。实际上uORB是一套跨「进程」 的IPC通讯模块。在Pixhawk中, 所有的功能被独立以进程模块为单位进行实现并工作。而进程间的数据交互就由为重要,必须要能够符合实时、有序的特点。在PX4中,uORB是用于无人机模块间通信的协议机制。
02
uORB消息的运行机制
飞控内部使用NuttX实时ARM系统, 而uORB对于NuttX而言,它仅仅是一个普通的文件设备对象,这个设备支持Open、Close、Read、Write、Ioctl以及Poll机制。通过这些接口的实现,uORB提供了一套“点对多”的跨进程广播通讯机制, “点”指的是通讯消息的“源”,“多”指的是一个源可以有多个用户来接收、处理。而“源”与“用户”的关系在于,源不需要去考虑用户是否可以收到某条被广播的消息或什么时候收到这条消息。它只需要单纯的把要广播的数据推送到uORB的消息“总线”上。对于用户而言,源推送了多少次的消息也不重要,重要的是取回最新的这条消息。也就是说在通讯过程中发送者只负责发送数据,而并不关心数据由谁接收,也不关心接收者是否能将所有的数据都接收到;而对于接收者来说并不关心数据是由谁发送的,也不关心在接收过程中是否将所有数据都接收到。
uORB在数据发布与接收过程中并不保证发送者的所有数据都可以被接收者收到,而只保证接收者在想要接收时能收到最新的数据。而发送与接收的分离可以使飞行过程中各个模块相互独立,互不干扰。实际上一个uORB可以由多个发送者发布,也可以被多个接收者接收,也就是说他们之间是多对多的关系。发布者以一定频率更新发布数据到uORB平台上,不关心谁来接收。订阅者可以随时来获取数据。
PX4软件系统中提供有丰富的例程,其中“*\PX4PSP\Firmware\src\examples\px4_simple_app”为一个简单的uORB消息订阅读取的例程,本例程中通过订阅vehicle_acceleration话题,读取加速度计数据,并将其发布到vehicle_attitude话题上。具体代码解析如下:
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
__EXPORT int px4_simple_app_main(int argc, char *argv[]);
int px4_simple_app_main(int argc, char *argv[])
{
PX4_INFO("Hello Sky!");
/* 订阅 vehicle_acceleration 话题 */
int sensor_sub_fd = orb_subscribe(ORB_ID(vehicle_acceleration));
/* 限制更新速率为 5 Hz */
orb_set_interval(sensor_sub_fd, 200);
/* 广播 attitude 话题 */
struct vehicle_attitude_s att;
memset(&att, 0, sizeof(att));
orb_advert_t att_pub = orb_advertise(ORB_ID(vehicle_attitude), &att);
/* 创建一个数组fds,其中包含一个文件描述符sensor_sub_fd以及对应的事件设置为可读事件。*/
px4_pollfd_struct_t fds[] = {
{ .fd = sensor_sub_fd, .events = POLLIN },
/* 这里还可以有更多的文件描述符,例如:
* { .fd = other_sub_fd, .events = POLLIN },
*/
};
int error_counter = 0;
for (int i = 0; i < 5; i++) {
/* 等待传感器更新,等待1个文件描述符的数据,超时时间为1000毫秒(1秒) */
int poll_ret = px4_poll(fds, 1, 1000);
/* 处理轮询结果 */
if (poll_ret == 0) {
/* 这意味着在一秒内没有数据提供者给我们数据 */
PX4_ERR("在一秒内没有获取到数据");
} else if (poll_ret < 0) {
/* 这是一个严重的错误 - 应该是紧急情况 */
if (error_counter < 10 || error_counter % 50 == 0) {
/* 使用计数器来防止过多的错误消息(以免影响性能) */
PX4_ERR("轮询返回值出现错误: %d", poll_ret);
}
error_counter++;
} else {
if (fds[0].revents & POLLIN) {
/* 获取第一个文件描述符的数据 */
struct vehicle_acceleration_s accel;
/* 将传感器的原始数据复制到本地缓冲区 */
orb_copy(ORB_ID(vehicle_acceleration), sensor_sub_fd, &accel);
PX4_INFO("加速度计:\t%8.4f\t%8.4f\t%8.4f",
(double)accel.xyz[0],
(double)accel.xyz[1],
(double)accel.xyz[2]);
/* 设置 att 并将此信息发布给其他应用程序
* 以下示例没有实际意义,仅供参考
*/
att.q[0] = accel.xyz[0];
att.q[1] = accel.xyz[1];
att.q[2] = accel.xyz[2];
orb_publish(ORB_ID(vehicle_attitude), att_pub, &att);
}
/* 这里还可以有更多的文件描述符,例如:
* if (fds[1..n].revents & POLLIN) {}
*/
}
}
PX4_INFO("程序退出");
return 0;
}
上述例程所示PX4 软件中自带的例程,但是在进行编译时,本例程默认是不运行,若想运行本例程需要在对于飞控板载文件夹中修改“*\PX4PSP\Firmware\boards\droneyee\zyfc-h7\default.cmake”文件,注:本实验中所用的飞控硬件为卓翼H7,不同飞控硬件对应各自文件夹
设置完成上述所有步骤之后,在RflySim软件桌面快捷方式文件夹中,双击运行Win10WSL子系统。运行:
# 此处编译命令应对应RflySim安装时的编译命令
make droneyee_zyfc-h7_default
等待编译成功之后,通过QGC上传该固件到飞控中,在QGC的Anslyze Tools->MAVLINK 控制台中,输入px4_simple_app即可看到本例程的运行效果如下:
04
PX4软件自定义uORB消息
在PX4中创建自定义uORB消息的过程一般分为三个步骤:定义msg文件、uORB消息发布与订阅、修改飞控板载.cmake文件。且整个过程需要修改涉及的文件较多,具体步骤如下:
1、定义msg文件:RflySim的暗转文件夹“*\PX4PSP\Firmware\msg”中,创建文件uorb_test.msg文件,文件内容如下:
uint64 timestamp # time since system start (microseconds)
uint32 test1
uint32 test2
uint32 test3
同时,需要修改同级目录下的CMakeLists.txt文件,即新增定义的msg文件。
2、uORB消息发布和订阅,与uORB消息的读取步骤相类似,我们只需在“*\PX4PSP\Firmware\src\examples”中 创建应用文件夹,新建“C:\PX4PSP\Firmware\src\examples\uORB_test”文件夹,其中,包含有CMakeLists.txt、uORB_test.c两个文件,文件具体内容如下:
CMakeLists.txt:
px4_add_module(
MODULE examples__uORB_test
MAIN uORB_test
SRCS
uORB_test.c
DEPENDS
)
uORB_test.c:
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
__EXPORT int uORB_test_main(int argc, char *argv[]);
int uORB_test_main(int argc, char *argv[])
{
PX4_INFO("Hello Sky!");
//发布消息
struct uorb_test_s test_uorb_ad;
memset(&test_uorb_ad, 0, sizeof(test_uorb_ad));
orb_advert_t test_pub = orb_advertise(ORB_ID(uorb_test), &test_uorb_ad);
test_uorb_ad.test1=1;
test_uorb_ad.test2=2;
test_uorb_ad.test3=3;
orb_publish(ORB_ID(uorb_test),test_pub,&test_uorb_ad);
// //订阅消息
// struct uorb_test_s test_uorb_sub;
// memset(&test_uorb_ad, 0, sizeof(test_uorb_sub));
// int test_sub_fd=orb_subscribe(ORB_ID(uorb_test));
// orb_copy(ORB_ID(uorb_test),test_sub_fd,&test_uorb_sub);
// PX4_INFO("test:\t%8.4f\t%8.4f\t%8.4f",
// (double)test_uorb_sub.test1,
// (double)test_uorb_sub.test2,
// (double)test_uorb_sub.test3);
PX4_INFO("exiting");
return 0;
}
3、修改飞控.cmake文件在飞控板载文件夹中修改“*\PX4PSP\Firmware\boards\droneyee\zyfc-h7\default.cmake”文件,注:本实验中所用的飞控硬件为卓翼H7,不同飞控硬件对应各自文件夹。
设置完成上述所有步骤之后,在RflySim软件桌面快捷方式文件夹中,双击运行Win10WSL子系统。运行:
# 此处编译命令应对应RflySim安装时的编译命令
make droneyee_zyfc-h7_default
等待编译成功之后,通过QGC上传该固件到飞控中,在QGC的Anslyze Tools->MAVLINK 控制台中,输入px4_simple_app即可看到本例程的运行效果如下:
参考资料
[1]. https://blog.csdn.net/sinat_16643223/article/details/113872249
[2]. https://blog.csdn.net/qq_32261101/article/details/109534659
[3]. https://blog.csdn.net/qq_38768959/article/details/122587617