ps:第1章简介是参考 uORB深入理解和应用
PX4/Pixhawk的软件体系结构主要被分为四个层次,这可以让我们更好的理解PX4/Pixhawk的软件架构和运作:
应用层中操作基础飞行的应用之间都是隔离的,这样提供了一种安保模式,以确保基础操作独立的高级别系统状态的稳定性。而沟通它们的就是uORB。
topics : 系统通用接口定义的标准主题,比如电池电量转态、GPS的位置参数等
module.mk : uORB模块makefile文件
objects_common.cpp: 通用接口标准主题定义集合,如添加新主题在这里定义
ORBMap.hpp : 对象请求器节点链表管理(驱动节点)
ORBSet.hpp : 对象请求器节点管理(非驱动节点)
Publication.cpp : 在不同的发布中遍历使用
Publication.hpp : 在不同的发布中遍历使用
Subscription.cpp : 在不同的订阅中遍历使用
Subscription.hpp : 在不同的订阅中遍历使用
uORB.cpp : uORB的实现
uORB.h : uORB头文件
uORBCommon.hpp : uORB公共部分变量定义实现
uORBCommunicator.hpp : 远程订阅的接口实现,实现了对不同的通信通道管理,如添加/移除订阅者,可以基于TCP/IP或fastRPC;传递给通信链路的实现,以提供在信道上接收消息的回调。
uORBDevices.hpp :
uORBDevices_nuttx.cpp : 节点操作,close,open,read,write
uORBDevices_nuttx.hpp :
uORBDevices_posix.cpp :
uORBDevices_posix.hpp :
uORBMain.cpp : uORB入口
uORBManager.hpp : uORB功能函数实现头文件
uORBManager_nuttx.cpp : uORB功能函数实现(Nuttx)
uORBManager_posix.cpp : uORB功能函数实现(Posix)
uORBTest_UnitTest.cpp : uORB测试
uORBTest_UnitTest.hpp : uORB测试头文件,包括主题定义和声明等
uORBUtiles.cpp :
uORBUtiles.hpp :
int poll(struct pollfd fds[], nfds_t nfds, int timeout)
功能:监控文件描述符(多个);
说明:timemout=0,poll()函数立即返回而不阻塞;timeout=INFTIM(-1),poll()会一直阻塞下去,直到检测到return > 0;
参数:
fds:struct pollfd结构类型的数组;
nfds:用于标记数组fds中的结构体元素的总数量;
timeout:是poll函数调用阻塞的时间,单位:毫秒;
返回值:
>0:数组fds中准备好读、写或出错状态的那些socket描述符的总数量;
==0:poll()函数会阻塞timeout所指定的毫秒时间长度之后返回;
-1:poll函数调用失败;同时会自动设置全局变量errno;
int orb_subscribe(const struct orb_metadata *meta)
功能:订阅主题(topic);
说明:即使订阅的主题没有被公告,但是也能订阅成功;但是在这种情况下,却得不到数据,直到主题被公告;
参数:
meta:uORB元对象,可以认为是主题id,一般是通过ORB_ID(主题名)来赋值;
返回值:
错误则返回ERROR;成功则返回一个可以读取数据、更新话题的句柄;如果待订阅的主题没有定义或声明则会返回-1,然后会将errno赋值为ENOENT;
eg:
int fd = orb_subscribe(ORB_ID(topicName));
int orb_copy(const struct orb_metadata *meta, int handle, void *buffer)
功能:从订阅的主题中获取数据并将数据保存到buffer中;
参数:
meta:uORB元对象,可以认为是主题id,一般是通过ORB_ID(主题名)来赋值;
handle:订阅主题返回的句柄;
buffer:从主题中获取的数据;
返回值:
返回OK表示获取数据成功,错误返回ERROR;否则则有根据的去设置errno;
eg:
struct sensor_combined_s raw;
orb_copy(ORB_ID(sensor_combined), sensor_sub_fd, &raw);
orb_advert_t orb_advertise(const struct orb_metadata *meta, const void *data)
功能:公告发布者的主题;
说明:在发布主题之前是必须的;否则订阅者虽然能订阅,但是得不到数据;
参数:
meta:uORB元对象,可以认为是主题id,一般是通过ORB_ID(主题名)来赋值;
data:指向一个已被初始化,发布者要发布的数据存储变量的指针;
返回值:错误则返回ERROR;成功则返回一个可以发布主题的句柄;如果待发布的主题没有定义或声明则会返回-1,然后会将errno赋值为ENOENT;
eg:
struct vehicle_attitude_s att;
memset(&att, 0, sizeof(att));
int att_pub_fd = orb_advertise(ORB_ID(vehicle_attitude), &att);
int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data)
功能:发布新数据到主题;
参数:
meta:uORB元对象,可以认为是主题id,一般是通过ORB_ID(主题名)来赋值;
handle:orb_advertise函数返回的句柄;
data:指向待发布数据的指针;
返回值:OK表示成功;错误返回ERROR;否则则有根据的去设置errno;
eg:
orb_publish(ORB_ID(vehicle_attitude), att_pub_fd, &att);
int orb_set_interval(int handle, unsigned interval)
功能:设置订阅的最小时间间隔;
说明:如果设置了,则在这间隔内发布的数据将订阅不到;需要注意的是,设置后,第一次的数据订阅还是由起初设置的频率来获取,
参数:
handle:orb_subscribe函数返回的句柄;
interval:间隔时间,单位ms;
返回值:OK表示成功;错误返回ERROR;否则则有根据的去设置errno;
eg:
orb_set_interval(sensor_sub_fd, 1000);
orb_advert_t orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance, int priority)
功能:设备/驱动器的多个实例实现公告,利用此函数可以注册多个类似的驱动程序;
说明:例如在飞行器中有多个相同的传感器,那他们的数据类型则类似,不必要注册几个不同的话题;
参数:
meta:uORB元对象,可以认为是主题id,一般是通过ORB_ID(主题名)来赋值;
data:指向一个已被初始化,发布者要发布的数据存储变量的指针;
instance:整型指针,指向实例的ID(从0开始);
priority:实例的优先级。如果用户订阅多个实例,优先级的设定可以使用户使用优先级高的最优数据源;
返回值:
错误则返回ERROR;成功则返回一个可以发布主题的句柄;如果待发布的主题没有定义或声明则会返回-1,然后会将errno赋值为ENOENT;
eg:
struct orb_test t;
t.val = 0;
int instance0;
orb_advert_t pfd0 = orb_advertise_multi(ORB_ID(orb_multitest), &t, &instance0, ORB_PRIO_MAX);
int orb_subscribe_multi(const struct orb_metadata *meta, unsigned instance)
功能:订阅主题(topic);
说明:通过实例的ID索引来确定是主题的哪个实例;
参数:
meta:uORB元对象,可以认为是主题id,一般是通过ORB_ID(主题名)来赋值;
instance:主题实例ID;实例ID=0与orb_subscribe()实现相同;
返回值:
错误则返回ERROR;成功则返回一个可以读取数据、更新话题的句柄;如果待订阅的主题没有定义或声明则会返回-1,然后会将errno赋值为ENOENT;
eg:
int sfd1 = orb_subscribe_multi(ORB_ID(orb_multitest), 1);
int orb_unsubscribe(int handle)
功能:取消订阅主题;
参数:
handle:主题句柄;
返回值:
OK表示成功;错误返回ERROR;否则则有根据的去设置errno;
eg:
ret = orb_unsubscribe(handle);
int orb_check(int handle, bool *updated)
功能:订阅者可以用来检查一个主题在发布者上一次更新数据后,有没有订阅者调用过ob_copy来接收、处理过;
说明:如果主题在在被公告前就有人订阅,那么这个API将返回“not-updated”直到主题被公告。可以不用poll,只用这个函数实现数据的获取。
参数:
handle:主题句柄;
updated:如果当最后一次更新的数据被获取了,检测到并设置updated为ture;
返回值:
OK表示检测成功;错误返回ERROR;否则则有根据的去设置errno;
eg:
if (PX4_OK != orb_check(sfd, &updated)) {
return printf("check(1) failed");
}
if (updated) {
return printf("spurious updated flag");
}
//or
bool updated;
struct random_integer_data rd;
/* check to see whether the topic has updated since the last time we read it */
orb_check(topic_handle, &updated);
if (updated) {
/* make a local copy of the updated data structure */
orb_copy(ORB_ID(random_integer), topic_handle, &rd);
printf("Random integer is now %d\n", rd.r);
}
int orb_stat(int handle, uint64_t *time)
功能:订阅者可以用来检查一个主题最后的发布时间;
参数:
handle:主题句柄;
time:存放主题最后发布的时间;0表示该主题没有发布或公告;
返回值:
OK表示检测成功;错误返回ERROR;否则则有根据的去设置errno;
eg:
ret = orb_stat(handle,time);
int orb_exists(const struct orb_metadata *meta, int instance)
功能:检测一个主题是否存在;
参数:
meta:uORB元对象,可以认为是主题id,一般是通过ORB_ID(主题名)来赋值;
instance:ORB 实例ID;
返回值:
OK表示检测成功;错误返回ERROR;否则则有根据的去设置errno;
eg:
ret = orb_exists(ORB_ID(vehicle_attitude),0);
int orb_priority(int handle, int *priority)
功能:获取主题优先级别;
参数:
handle:主题句柄;
priority:存放获取的优先级别;
返回值:
OK表示检测成功;错误返回ERROR;否则则有根据的去设置errno;
eg:
ret = orb_priority(handle,&priority);
make px4_fmu-v2_default upload
编译固件并且下载固件到飞控板。具体参考官方指导教程Development Environment on Ubuntu LTS / Debian Linux/****************************************************************************
*
* Copyright (c) 2012-2019 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file px4_simple_app.c
* Minimal application example for PX4 autopilot
*
* @author Example User
*/
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
//知识点: 1 消息的阻塞订阅 px4_poll,orb_subscribe,orb_cpy
// 2 终端打印调试语句 px4_INFO
// 3 消息发布的声明 orb_advertise, orb_publish
//这里是主函数声明,必须要有
__EXPORT int px4_simple_app_main(int argc, char *argv[]);
int px4_simple_app_main(int argc, char *argv[])
{
//与printf功能一样,两者可以互用
PX4_INFO("Hello Sky!");
/*订阅一个名为vehicle_acceleration的主题,返回值是可以读取这个主题的句柄(文件描述符) */
int sensor_sub_fd = orb_subscribe(ORB_ID(vehicle_acceleration));
/* 每200ms去订阅,看是否到来*/
orb_set_interval(sensor_sub_fd, 200);
/* 定义一个与主题变量对应的结构体 */
struct vehicle_attitude_s att;
//清空该变量地址
memset(&att, 0, sizeof(att));
//公告发布者的主题
orb_advert_t att_pub = orb_advertise(ORB_ID(vehicle_attitude), &att);
/* one could wait for multiple topics with this technique, just using one here */
//后面使用px4_poll函数来自动检测是否有数据写入该文件描述符,属于多进程通信之间的知识
//初始化文件描述符 socket通信
px4_pollfd_struct_t 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;
for (int i = 0; i < 5; i++) {
/* wait for sensor update of 1 file descriptor for 1000 ms (1 second) */
int poll_ret = px4_poll(fds, 1, 1000);
/* handle the poll result */
if (poll_ret == 0) {
/* this means none of our providers is giving us data */
PX4_ERR("Got no data within a second");
} 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) */
PX4_ERR("ERROR return value from poll(): %d", poll_ret);
}
error_counter++;
//正常会执行该代码
} else {
//如果有进程向socket写,那么通过poll函数会把revents赋值给POLLIN,代表有写时间发生
if (fds[0].revents & POLLIN) {
/* obtained data for the first file descriptor */
struct vehicle_acceleration_s accel;//这是系统袭击定义的结构体,不是人为,具体后面再说
/* 复制主题携带的数据到定的结构体 */
orb_copy(ORB_ID(vehicle_acceleration), sensor_sub_fd, &accel);
PX4_INFO("Accelerometer:\t%8.4f\t%8.4f\t%8.4f",//终端打印调试语句
(double)accel.xyz[0],
(double)accel.xyz[1],
(double)accel.xyz[2]);
/* set att and publish this information for other apps
the following does not have any meaning, it's just an example
*/
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);//发布姿态数据
}
/* there could be more file descriptors here, in the form like:
* if (fds[1..n].revents & POLLIN) {}
*/
}
}
PX4_INFO("exiting");
return 0;
}
整体代码注释我都标注在文档,整篇代码所实现的功能就是先订阅一个加速度数据的主题,然后通过poll函数检测是否有主题到来,等到有写事件发生的时候,能够将主题中的数据copy出来并且打印显示。
打开PX4-Autopilot->boards->px4->fmu-v2->default.Cmake
文件,将历程examples里的px4_simple_app注释去掉即可
保存退出。
QDC->MAVLink Console
启动历程打开MAVLink Console,使用help命令调出当前所有进程,使用进程名+start启动进程。
至此,关于官方所给历程已经展示完毕。
- PX4-Autopilot-> msg
下新建uORB成员Mytest.msg,并填写以下代码uint64 timestamp //时间堆这个必须有
uint32 data1
uint32 data2
uint32 data3
uint32 data4
PS:注意,当你不知道怎么写,就打开别人写好的仿照着写。
- PX4-Autopilot-> msg->CMakeLists.txt
中添加Mytest.msg作为索引- PX4-Autopilot-> build->px4_fmu-v2_default->uORB->topics
自动生成Mytest.h文件,里面自动生成与主题对应的结构体。- PX4-Autopilot->src->examples
新建Mytest文件夹在文件夹下新建Mytest.c和CMakeLists.txt两个文件。#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
__EXPORT int Mytest_main(int argc, char *argv[]);
int Mytest_main(int argc, char *argv[])
{
//在Mytest.h中会生成Mytest_s结构体
struct Mytest_s orbtest;
memset(&orbtest, 0, sizeof(orbtest));
//第一步:公告主题
orb_advert_t pub_fd = orb_advertise(ORB_ID(Mytest), &orbtest);
orbtest.data1 = 1;
orbtest.data2 = 2;
orbtest.data3 = 3;
orbtest.data4 = 4;
//第二步:发布主题
orb_publish(ORB_ID(Mytest), pub_fd, &orbtest);
//第三步:订阅主题
int sub_fd = orb_subscribe(ORB_ID(Mytest));
//第四步:复制主题
struct Mytest_s data_copy;
orb_copy(ORB_ID(Mytest), sub_fd, &data_copy);
printf("DATA:\t%4.2f\t%4.2f\t%4.2f\t%4.2f",
(double)data_copy.data1,
(double)data_copy.data2,
(double)data_copy.data3,
(double)data_copy.data4);
PX4_INFO("exiting");
return 0;
}
px4_add_module(
MODULE examples__Mytest
MAIN Mytest
SRCS
Mytest.c
DEPENDS
)
- PX4-Autopilot->ROMFS->px4fmu_common->init.d
的rc(总的启动文件)或者re.mc_default(多旋翼的启动文件)末尾加上文件名 start
即可。官网新更新代码以后,有不少地方与之前的教程不一致,故做此教程,方便自己记忆以及帮助大家。