uORB通信机制和添加自己的topics学习笔记

本文参考 Ubuntu16.04下PX4环境快速搭建及uORB通信机制进行操作,结合网上一篇uROB的介绍PX4/Pixhawk—uORB深入理解和应用进行深入的了解。

1.简介

uORB(Micro Object Request Broker,微对象请求代理器)是PX4/Pixhawk系统中非常重要且关键的一个模块,它肩负了整个系统的数据传输任务,所有的传感器数据、GPS、PPM信号等都要从芯片获取后通过uORB进行传输到各个模块进行计算处理。实际上uORB是一套跨「进程」 的IPC通讯模块。在Pixhawk中, 所有的功能被独立以进程模块为单位进行实现并工作。而进程间的数据交互就由为重要,必须要能够符合实时、有序的特点。 

  Pixhawk使用的是NuttX实时ARM系统,uORB实际上是多个进程打开同一个设备文件,进程间通过此文件节点进行数据交互和共享。进程通过命名的「总线」交换的消息称之为「主题」(topic),在Pixhawk 中,一个主题仅包含一种消息类型,通俗点就是数据类型。每个进程可以「订阅」或者「发布」主题,可以存在多个发布者,或者一个进程可以订阅多个主题,但是一条总线上始终只有一条消息。
  uROB通信机制介绍uORB的通信机制从下图可以看得很清楚,就是在数据管道上每个模块都可以给数据给这个通道(publish),也可以在这个通道获得数据(subscribe),每个模块就是一个进程,它们可以彼此独立,它们不需要知道把数据给哪个模块,也不需要知道从哪个模块获取数据,有uORB作为桥梁,这也防止了程序的死锁问题。下面具体演示如何添加自己的topics:

2.添加自己的topics

2.1添加自己的msg

在Firmware/msg下新建uROB成员变量:lulu.msg

  uint8 lulu1
  # TOPICS lulu lulu_x lulu_y    //这一步生成三个主题ID,注意#号和TOPICS之间有空格

2.2在Firmware/msg/CMakeLists.txt中添加话题的xxx.msg,作为cmake的索引

time_offset.msg
    transponder_report.msg
    uavcan_parameter_request.msg
    uavcan_parameter_value.msg
    ulog_stream.msg
    ulog_stream_ack.msg
    vehicle_attitude.msg
    vehicle_attitude_setpoint.msg
    vehicle_command.msg
    vehicle_command_ack.msg
    vehicle_control_mode.msg
    vehicle_force_setpoint.msg
    vehicle_global_position.msg
    vehicle_gps_position.msg
    vehicle_land_detected.msg
    vehicle_local_position.msg
    vehicle_local_position_setpoint.msg
    vehicle_rates_setpoint.msg
    vehicle_roi.msg
    vehicle_status.msg
    vehicle_status_flags.msg
    vtol_vehicle_status.msg
    wind_estimate.msg
    lulu.msg
    )

2.3 编译工程

cd ~/src/Firmware
make px4fmu-v2_default

现在在src/Firmware/build_px4fmu-v2_default/src/modules/uROB/topics目录下会产生相应的头文件

这里写图片描述

打开该文件后,我们看到里面定义了一个结构体,用到了我们写msg中的lulu1变量,这个结构体我们自己定义发布和订阅要用到

#pragma once

#include <stdint.h>
#ifdef __cplusplus
#include <cstring>
#else
#include <string.h>
#endif

#include <uORB/uORB.h>

#ifndef __cplusplus

#endif

struct microCDR;
#ifdef __cplusplus
struct __EXPORT lulu_s {
#else
struct lulu_s {
#endif
    uint64_t timestamp; // required for logger
    uint8_t lulu1;
    uint8_t _padding0[7]; // required for logger


#ifdef __cplusplus

#endif
};

void serialize_lulu(const struct lulu_s *input, char *output, uint32_t *length, struct microCDR *microCDRWriter);
void deserialize_lulu(struct lulu_s *output, char *input, struct microCDR *microCDRReader);

/* register this as object request broker structure */
ORB_DECLARE(lulu);
ORB_DECLARE(lulu_x);
ORB_DECLARE(lulu_y);

下面可以开始进行自己数据的发布和订阅,我为了不更改原本的文件,在Firmware/src/examples下新建了文件夹取名为px4_simple_app1,在这个文件夹里添加CMakeLists.txt将px4_simple_app文件中的CMakeLists.txt文件名稍微改下就行。新建文件px4_simple_app1.c内容如下:

#include <px4_config.h>
#include <px4_tasks.h>
#include <px4_posix.h>
#include <unistd.h>
#include <stdio.h>
#include <poll.h>
#include <string.h>
#include <math.h>

#include <uORB/uORB.h>
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/lulu.h>  
//添加自己的头文件


__EXPORT int px4_simple_app1_main(int argc, char *argv[]);   //主函数声明,必须要写

int px4_simple_app1_main(int argc, char *argv[])
{
    PX4_INFO("Hello lulu!");//PX4_INFO为打印函数,printf也可以

    /*定义话题结构*/
    struct lulu_s test;  //这个结构体就是lulu.h文件中定义的
    /*初始化数据*/
    memset(&test, 0, sizeof(test));

    /*公告主题*/
    /*test_pub 为handle指针*/
    orb_advert_t test_pub = orb_advertise(ORB_ID(lulu), &test);

    /*test数据赋值*/
     test.lulu1 = 200;


    /*发布测试数据*/
    orb_publish(ORB_ID(lulu), test_pub, &test);

    /*订阅数据,在copy之前,必须要订阅*/
    /*test_sub_fd为handle*/
    int test_sub_fd = orb_subscribe(ORB_ID(lulu));

    struct lulu_s data_copy;

    /*copy数据*/
    orb_copy(ORB_ID(lulu), test_sub_fd, &data_copy);

    /*打印*/
    PX4_WARN("[px4_simple_app1] GanTA:\t%8.4f",
                         (double)data_copy.lulu1
                          );

    return 0;
}

具体的发布和订阅函数可以参考博客:PX4中uORB发布订阅自己的topic

2.4配置启动脚本,进入nsh系统

在默认的脚本中px4_simple_app1并不会被编译执行,需要到Firmware/cmake/configs/nuttx_px4fmu-v2_default.cmake下将px4_simple_app1的文件添加进去,就是把注释去掉:
这里写图片描述

此时我们连接飞控到计算机,编译并刷固件:

makepx4fmu-v2_default upload

这里写图片描述

这里有个查看我们pixhawk固件的端口号的命令:

ls /dev/tty*

这里写图片描述

我们需要进入nsh系统,我用的是pymavlink,如果没有安装,按提示安装即可,也可以安装MAVProxy,我的电脑安装这个总是fail。
运行以下命令

cd Tools
./mavlink_shell.py /dev/ttyACM0
help
px4_simple_app1

这里写图片描述
至此,整个过程结束!

  • 1
    点赞
  • 4
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

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

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

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值