PX4入门到精通之内部通信(2)

UORB作用:

在这里插入图片描述内部使相互独立的各个模块实现通信,外部是mavlink(比如上图的飞行控制和状态估计)在这里插入图片描述
(每次只能储存最新的数据,一个消息)
在这里插入图片描述
在这里插入图片描述

UORB的使用:

步骤,先发布,再订阅:
在这里插入图片描述

发布数据:

orb_advert_t orb_advertise(const struct orb_metadata *meta, const void *data)

功能:先公告主题,相当于注册,只要一次就行了。meta公告的消息ID,data公告的原始数据。
说明:在发布主题之前是必须的;否则订阅者虽然能订阅,但是得不到数据;

int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data)

功能:公告之后就可以发布主题数据。meta公告的消息ID,handle公告返回的句柄,这个句柄初始化为null,data发布的数据,要发布什么数据,自己填充。

使用数据(调用的传感器结构体数据在msg下):

int orb_subscribe(const struct orb_metadata *meta)

功能:订阅主题(topic);
说明:即使订阅的主题没有被公告,但是也能订阅成功;但是在这种情况下,却得不到数据,直到主题被公告;
这就是为什么发布数据之前需要先公告,公告相当于注册吧。在消息主题中,句柄用的很多,都是对句柄直接操作的。句柄的初始化是放在进程的初始化部分的。
参数:
meta:uORB元对象,可以认为是主题id;
返回值:
正确返回一个句柄,句柄是你自己定义的,初始化为-1,如int my_topic_sub=-1;
int my_topic_sub = orb_subscribe(ORB_ID(my_topic));
注意:订阅的句柄常常起名为_sub指的就是subscribe,看到不要以为是sub副的意思;而发布的主题,后缀常常是_pub是publish的意思。

int orb_set_interval(int handle, unsigned interval)

功能:设置订阅的最小时间间隔;
说明:如果设置了,则在这间隔内发布的数据将订阅不到;需要注意的是,设置后,第一次的数据订阅还是由起初设置的频率来获取。handle句柄,订阅主题返回的句柄,interval间隔时间,系统常设置的是33ms,就是30hz的更新频率。
订阅了消息主题,如何检查数据更新了吗?下面就是两种方式,区别自己比较吧,之前我提到过。

int poll(struct pollfd fds[], nfds_t nfds, int timeout)

功能:监控文件描述符(多个);
说明:timeout就是最大阻塞这么长时间等待你的数据,因为我不可能一直等你,那样岂不是什么也干不了,所以限制一个时间,就等这么常时间。返回为0那就是时间都用完了也没等到数据,>0就是时间内拿到了数据,<0那就是出错了,看到没有返回的是拿到你数据时我还剩多少阻塞时间。
输入:
fds:struct pollfd结构类型的数组,进程可以同时等待很多个主题数据,当有数据更新时,判断一下是谁
nfds:用于标记数组fds中的结构体元素的总数量;
timeout:是poll函数调用阻塞的时间,单位:毫秒;
返回值:

0:阻塞时间内拿到了数据;
==0:抱歉时间都用完了,也没能拿到数据;
-1:poll函数调用失败;

int orb_check(int handle, bool *updated)

功能:检查一个主题数据有没有更新,更新了updated会被设置为true。但一旦调用ob_copy来接收、处理过后,updated会被自动设置为false,所以这种方式数据只能被第一个人检测到,后面人再检测到时updated已经是fals。
两种方式检查到数据已经更新了,怎么取出,怎么使用?

int orb_copy(const struct orb_metadata *meta, int handle, void *buffer)

功能:从订阅的主题中获取数据并将数据保存到buffer中。meta消息的ID,handle句柄,哪个句柄,你订阅时返回的句柄,从消息中拷贝数据放到buffer中。buffer是自己消息的数据结构类型自己定义的。例:sensor_combined_s raw ;orb_copy(ORB_ID(sensor_combined), sensor_sub_fd, &raw);

代码举例(官方列子在src下px4_simple_app下):

//订阅使用数据
#include <nuttx/config.h>
#include <unistd.h>
#include <stdio.h>
#include <poll.h>
#include <uORB/uORB.h>
#include <uORB/topics/sensor_combined.h>

__EXPORT int px4_simple_app_main(int argc, char *argv[]);

int px4_simple_app_main(int argc, char *argv[])
{
    printf("Hello Sky!\n");

    /*订阅sensor_combined 主题*/
    int sensor_sub_fd = orb_subscribe(ORB_ID(sensor_combined));  //1订阅主题

    //这是订阅的主题的数组,因为一个应用还可以等待多个主题,这里是用于下面的监控
    struct pollfd fds[] = {
        { .fd = sensor_sub_fd,   .events = POLLIN },
    };//这里指等待一个主题 句柄是sensor_sub_fd 主题是sensor_combined 

    int error_counter = 0;

    while (true) {
        /*poll函数调用阻塞的时间为1s*/
        int poll_ret = poll(fds, 1, 1000);  //2监控内容

        /*处理poll返回的结果 */
        if (poll_ret == 0) {
            /* 这表示时间溢出了,在1s内没有获取到发布者的数据 */
            printf("[px4_simple_app] Got no data within a second\n");
        } else if (poll_ret < 0) {
            /* 出现问题 */
            if (error_counter < 10 || error_counter % 50 == 0) {
                /* use a counter to prevent flooding (and slowing us down) */
                printf("[px4_simple_app] ERROR return value from poll(): %d\n"
                    , poll_ret);
            }
            error_counter++;
        } else {
 				
   //3 If(poll_ret>0) 订阅的主题 有新数据发布
            if (fds[0].revents & POLLIN) {
                /*从文件描述符中获取订阅的数据*/
                struct sensor_combined_s raw;
                /* copy sensors raw data into local buffer */
                orb_copy(ORB_ID(sensor_combined), sensor_sub_fd, &raw);//4 取数据
                printf("[px4_simple_app] Accelerometer:\t%8.4f\t%8.4f\t%8.4f\n",
                    (double)raw.accelerometer_m_s2[0],
                    (double)raw.accelerometer_m_s2[1],
                    (double)raw.accelerometer_m_s2[2]);
            }
            /* 如果有更多的文件描述符,可以这样:
             * if (fds[1..n].revents & POLLIN) {}
             */
        }
    }
    return 0;
}
//发布数据
#include <nuttx/config.h>
#include <unistd.h>
#include <stdio.h>
#include <poll.h>
#include <uORB/uORB.h>
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/vehicle_attitude.h>

__EXPORT int px4_simple_app_main(int argc, char *argv[]);

int px4_simple_app_main(int argc, char *argv[])
{
    printf("Hello Sky!\n");

    /* 订阅 sensor_combined 主题 */
    int sensor_sub_fd = orb_subscribe(ORB_ID(sensor_combined));
    orb_set_interval(sensor_sub_fd, 1000);

    /* 公告 attitude 主题 */
    struct vehicle_attitude_s att;
    memset(&att, 0, sizeof(att));
    int att_pub_fd = orb_advertise(ORB_ID(vehicle_attitude), &att);//1、公告主题

    /*一个应用可以等待多个主题,在这里只等待一个主题*/
    struct pollfd fds[] = {
        { .fd = sensor_sub_fd,   .events = POLLIN },
        /* there could be more file descriptors here, in the form like:
         * { .fd = other_sub_fd,   .events = POLLIN },
         */
    };

    int error_counter = 0;

    while (true) {
        /* wait for sensor update of 1 file descriptor for 1000 ms (1 second) */
        int poll_ret = poll(fds, 1, 1000);

        /* handle the poll result */
        if (poll_ret == 0) {
            /* this means none of our providers is giving us data */
            printf("[px4_simple_app] Got no data within a second\n");
        } else if (poll_ret < 0) {
            /* this is seriously bad - should be an emergency */
            if (error_counter < 10 || error_counter % 50 == 0) {
                /* use a counter to prevent flooding (and slowing us down) */
                printf("[px4_simple_app] ERROR return value from poll(): %d\n"
                    , poll_ret);
            }
            error_counter++;
        } else {
            if (fds[0].revents & POLLIN) {
                /* obtained data for the first file descriptor */
                struct sensor_combined_s raw;
                /* copy sensors raw data into local buffer */
                orb_copy(ORB_ID(sensor_combined), sensor_sub_fd, &raw);
                printf("[px4_simple_app] Accelerometer:\t%8.4f\t%8.4f\t%8.4f\n",
                    (double)raw.accelerometer_m_s2[0],
                    (double)raw.accelerometer_m_s2[1],
                    (double)raw.accelerometer_m_s2[2]);

                /* 赋值 att 并且发布这些数据给其他的应用 */
                att.roll = raw.accelerometer_m_s2[0];
                att.pitch = raw.accelerometer_m_s2[1];
                att.yaw = raw.accelerometer_m_s2[2];//2、初始化数据
                orb_publish(ORB_ID(vehicle_attitude), att_pub_fd, &att);//3、发布主题
            }
  • 0
    点赞
  • 4
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

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

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

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值