PX4模块设计之二十一:uORB消息管理模块

Posted lida2003

tags:

篇首语:本文由小常识网(cha138.com)小编为大家整理,主要介绍了PX4模块设计之二十一:uORB消息管理模块相关的知识,希望对你有一定的参考价值。

PX4模块设计之二十一:uORB消息管理模块

前面主要给出uORB消息API接口和自定义消息的使用。这里主要来看下uORB消息管理模块是如何对uORB消息进行管理的。

1. uORB模块构建模式

鉴于Nuttx系统有两种构建模式:不同构建模式使用的源文件也有差异。

  • Flat Build
    uORB:$SRCS_COMMON + $SRCS_KERNEL
  • Protected Build
    uORB_kernel:$SRCS_COMMON + S R C S K E R N E L = = > 内核态 u O R B : SRCS_KERNEL ==> 内核态 uORB: SRCSKERNEL==>内核态uORBSRCS_COMMON + $SRCS_USER ==> 用户态

参考CMakeLists.txt主要差异在于:

  1. 总体声明定义:$SRCS_COMMON下的uORBManager.hpp
  2. 内核态实现: $SRCS_KERNEL下的uORBDeviceMaster.cppuORBDeviceNode.cppuORBManager.cpp
  3. 用户态实现: $SRCS_USER 下的uORBManagerUsr.cpp
  4. Flat编译模式:鉴于全地址访问,所以不需要使用用户态实现
39 set(SRCS_COMMON
40 	ORBSet.hpp
41 	Publication.hpp
42 	PublicationMulti.hpp
43 	Subscription.cpp
44 	Subscription.hpp
45 	SubscriptionCallback.hpp
46 	SubscriptionInterval.hpp
47 	SubscriptionMultiArray.hpp
48 	uORB.cpp
49 	uORB.h
50 	uORBCommon.hpp
51 	uORBCommunicator.hpp
52 	uORBManager.hpp
53 	uORBUtils.cpp
54 	uORBUtils.hpp
55 	uORBDeviceMaster.hpp
56 	uORBDeviceNode.hpp
57 	)
58 
59 set(SRCS_KERNEL
60 	uORBDeviceMaster.cpp
61 	uORBDeviceNode.cpp
62 	uORBManager.cpp
63 	)
64 
65 set(SRCS_USER
66 	uORBManagerUsr.cpp
67 	)
68 
69 if (NOT DEFINED CONFIG_BUILD_FLAT AND "$PX4_PLATFORM" MATCHES "nuttx")
70 	# Kernel side library in nuttx kernel/protected build
71 	px4_add_library(uORB_kernel
72 		$SRCS_COMMON
73 		$SRCS_KERNEL
74 		)
75 	target_link_libraries(uORB_kernel PRIVATE cdev uorb_msgs)
76 	target_compile_options(uORB_kernel PRIVATE $MAX_CUSTOM_OPT_LEVEL -D__KERNEL__)
77 
78 	# User side library in nuttx kernel/protected build
79 	px4_add_library(uORB
80 		$SRCS_COMMON
81 		$SRCS_USER
82 		)
83 else()
84 
85 	# Library for all other targets (flat build, posix...)
86 	px4_add_library(uORB
87 		$SRCS_COMMON
88 		$SRCS_KERNEL
89 		)
90 	target_link_libraries(uORB PRIVATE cdev)
91 endif()

2. uORB消息管理函数

2.1 状态查询

uorb_status
 ├──> [Flat Build]
 │   ├──> <g_dev != nullptr>
 │   │   └──> g_dev->printStatistics();
 │   └──> PX4_INFO("uorb is not running");
 └──> [Protected Build]
     └──> boardctl(ORBIOCDEVMASTERCMD, ORB_DEVMASTER_STATUS);

2.2 资源利用

uorb_top
 ├──> [Flat Build]
 │   ├──> <g_dev != nullptr>
 │   │   └──> g_dev->showTop(topic_filter, num_filters);
 │   └──> <g_dev == nullptr>
 │       └──> PX4_INFO("uorb is not running");
 └──> [Protected Build]
     └──> boardctl(ORBIOCDEVMASTERCMD, ORB_DEVMASTER_TOP);

2.3 模块启动

uorb_start
 ├──> <g_dev != nullptr>
 │   ├──> PX4_WARN("already loaded");
 │   └──> return OK;
 ├──> <!uORB::Manager::initialize()>
 │   ├──> PX4_ERR("uorb manager alloc failed");
 │   └──> return -ENOMEM;
 ├──> [Flat Build]
 │   ├──> g_dev = uORB::Manager::get_instance()->get_device_master();
 │   └──> <g_dev == nullptr>
 │       └──> return -errno;
 └──> return OK;
uORB::Manager::initialize
 ├──> <_Instance == nullptr)>
 │   └──> _Instance = new uORB::Manager();
 ├──> [Protected Build]
 │   └──> _px4_register_boardct_ioctl(_ORBIOCDEVBASE, orb_ioctl);  // boardctl
 └──> return _Instance != nullptr;

注:uORB_kernel+uORB两套实现代码。代码差异px4_register_boardct_ioctl。

2.4 模块停止

该函数实际上在PX4系统内部并未使用。

uORB::Manager::terminate
 ├──> <_Instance != nullptr>
 │   ├──> delete _Instance
 │   ├──> _Instance = nullptr
 │   └──> return true
 └──> return false

注:uORB_kernel+uORB两套实现代码。代码一致。

3. uORB消息接口

注:这里根据uORBManager.hpp列出接口定义(部分在uORBManager.cpp实现,部分在uORBManagerUsr.cpp实现),这里不做代码展开。

3.1 消息主题注册

uORB::Manager::orb_advertise_multi

注:orb_advertise是orb_advertise_multi的精简版本API

3.2 消息主题去注册

uORB::Manager::orb_unadvertise

3.3 消息主题发布

uORB::Manager::orb_publish

3.4 消息主题订阅

uORB::Manager::orb_subscribe
uORB::Manager::orb_subscribe_multi

3.5 消息主题去订阅

uORB::Manager::orb_unsubscribe

3.6 设置/获取间隔时间

uORB::Manager::orb_set_interval
uORB::Manager::orb_get_interval

3.7 获取订阅消息

uORB::Manager::orb_copy

3.8 主题消费检查

uORB::Manager::orb_check

3.9 主题存在性检查

uORB::Manager::orb_exists

4. uORB消息辅助接口

注:这里根据uORBManager.hpp列出接口定义(部分在uORBManager.cpp实现,部分在uORBManagerUsr.cpp实现),这里不做代码展开。

4.1 设备节点存在性检查

uORB::Manager::orb_device_node_exists

4.2 消息主题内部订阅

uORB::Manager::orb_add_internal_subscriber

4.3 消息主题内部去订阅

uORB::Manager::orb_remove_internal_subscriber

4.4 获取队列长度

uORB::Manager::orb_get_queue_size

4.5 获取ORB数据

uORB::Manager::orb_data_copy

4.6 设备节点注册回调

uORB::Manager::register_callback

4.7 设备节点去注册回调

uORB::Manager::unregister_callback

4.8 获取ORB实例

uORB::Manager::orb_get_instance

4.9 主题消息更新检查

uORB::Manager::updates_available

4.10 主题注册检查

uORB::Manager::is_advertised

5. uORB类继承关系

Subscription
 └──> SubscriptionData


SubscriptionMultiArray


SubscriptionInterval, ListNode<SubscriptionCallback *>
 └──> SubscriptionCallback
     ├──> SubscriptionCallbackWorkItem
     └──> SubscriptionBlocking

PublicationBase
 ├──> Publication
 │   └──> PublicationData
 └──> PublicationMulti
     └──> PublicationMultiData

6. 参考资料

【1】PX4开源软件框架简明简介
【2】PX4模块设计之二:uORB消息代理
【3】PX4模块设计之三:自定义uORB消息

以上是关于PX4模块设计之二十一:uORB消息管理模块的主要内容,如果未能解决你的问题,请参考以下文章

PX4模块设计之三:自定义uORB消息

PX4模块设计之二十七:LandDetector模块

PX4模块设计之二十二:FlightModeManager模块

PX4模块设计之二十六:BatteryStatus模块

PX4模块设计之二十九:RCUpdate模块

PX4模块设计之二十八:RCInput模块