PX4模块设计之三:自定义uORB消息
基于PX4开源软件框架简明简介和PX4模块设计之二:uORB消息代理, 了解了更多关于中间件uORB消息代理作为PX4系统内部消息传递的重要性。
关于新增消息或者消息主题,可以分为PX4代码库内部新增(通常是PX4开源组织在进行维护)和外部新增两种方式。
这里自定义uORB消息主要侧重的是外部新增主题消息,后续将会结合一个示例进行相关应用的Demo。
1. 新增自定义uORB消息步骤
- 新增与PX4-Autopilot平行目录PX4-ExternalModule;
- 建立PX4-ExternalModule下相应的msg、src目录;
- 在PX4-ExternalModule的msg目录下新建.msg文件,参考PX4-Autopilot下msg目录下的相关文件;
1 uint64 timestamp # time since system start (microseconds)
2 int8 hello # index of hello variable
3
4 # TOPICS ext_hello_world
- 在PX4-ExternalModule的msg目录下新建CMakeLists.txt文件;
- 在CMakeList.txt文件中添加.msg文件;
34 set(config_msg_list_external
35 ext_hello_world.msg
36 PARENT_SCOPE
37 )
- 在make的时候,框架代码会自动根据上述源文件生成对应的两个C/C++文件;
PX4-Autopilot\build\px4_sitl_default\uORB\topics\ext_hello_world.h
PX4-Autopilot\build\px4_sitl_default\msg\topics_sources\ext_hello_world.cpp
注:自此已经完成新增自定义uORB消息ext_hello_world。
2. 应用ext_hello_world消息示例
定义消息的目的主要是为了不同的任务之间进行通信,这里写了一个Demo:两个任务,一个任务publish消息,一个任务subscribe消息;
- 在Demo代码里面包含头文件;
#include <uORB/topics/ext_hello_world.h>
- 使用ORB_ID(ext_hello_world)唯一定位消息主题;
- 使用px4_task_spawn_cmd函数建立两个任务;
- 使用uORB消息处理接口函数Demo应用;
/****************************************************************************
*
* 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_custom_uorb.c
* extern custom uorb example for PX4 autopilot
*
* @author Example User <lida-mail@163.com>
*/
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/tasks.h>
#include <px4_platform_common/posix.h>
#include <unistd.h>
#include <stdio.h>
#include <poll.h>
#include <string.h>
#include <math.h>
#include <sys/types.h>
#include <stdlib.h>
#include <sched.h>
#include <errno.h>
#include <uORB/uORB.h>
#include <uORB/topics/ext_hello_world.h>
#define TASK_NAME_CUSTOM_UORB_SUBSCRIBE "orb subscribe"
#define TASK_NAME_CUSTOM_UORB_PUBLISH "orb publish"
#define TASK_SUBSCRIBE_NUM 8
#define TASK_PUBLISH_NUM 5
__EXPORT int px4_custom_uorb_main(int argc, char *argv[]);
int px4_custom_uorb_subscribe(int argc, char *argv[])
{
/* listen */
int hello_fd = orb_subscribe(ORB_ID(ext_hello_world));
/* limit the update rate to 5 Hz */
orb_set_interval(hello_fd, 200);
/* one could wait for multiple topics with this technique, just using one here */
px4_pollfd_struct_t fds[] = {
{ .fd = hello_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 < TASK_SUBSCRIBE_NUM; i++) {
/* wait for sensor update of 1 file descriptor for 1000 ms (1 second) */
int poll_ret = px4_poll(fds, 1, 5000);
/* 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 {
if (fds[0].revents & POLLIN) {
/* obtained data for the first file descriptor */
struct ext_hello_world_s tmp;
/* copy sensors raw data into local buffer */
orb_copy(ORB_ID(ext_hello_world), hello_fd, &tmp);
PX4_INFO("Hello world(subscribe):\t%d", tmp.hello);
}
/* there could be more file descriptors here, in the form like:
* if (fds[1..n].revents & POLLIN) {}
*/
}
}
PX4_INFO("px4_custom_uorb_subscribe exiting");
return 0;
}
int px4_custom_uorb_publish(int argc, char *argv[])
{
/* advertise */
struct ext_hello_world_s hello_world;
memset(&hello_world, 0, sizeof(hello_world));
orb_advert_t hello_world_pub = orb_advertise(ORB_ID(ext_hello_world), &hello_world);
for (int i = 0; i < TASK_PUBLISH_NUM; i++) {
/* Wait for subscriber */
sleep(5);
/* set att and publish this information for other apps
the following does not have any meaning, it's just an example
*/
hello_world.hello = i + 1;
PX4_INFO("Hello world(puslish):\t%d", hello_world.hello);
orb_publish(ORB_ID(ext_hello_world), hello_world_pub, &hello_world);
}
PX4_INFO("px4_custom_uorb_publish exiting");
return 0;
}
int px4_custom_uorb_main(int argc, char *argv[])
{
int task_subscribe, task_publish;
task_publish = px4_task_spawn_cmd(TASK_NAME_CUSTOM_UORB_PUBLISH, SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 2000, px4_custom_uorb_publish, argv);
PX4_INFO("creating %s task_publish = %d", TASK_NAME_CUSTOM_UORB_PUBLISH, task_publish);
sleep(1);
task_subscribe = px4_task_spawn_cmd(TASK_NAME_CUSTOM_UORB_SUBSCRIBE, SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 2000, px4_custom_uorb_subscribe, argv);
PX4_INFO("creating %s task_subscribe = %d", TASK_NAME_CUSTOM_UORB_SUBSCRIBE, task_subscribe);
while(px4_task_is_running(TASK_NAME_CUSTOM_UORB_SUBSCRIBE) || px4_task_is_running(TASK_NAME_CUSTOM_UORB_PUBLISH)){
sleep(1);
}
PX4_INFO("px4_custom_uorb_main exiting");
return 0;
}
整个DEMO结构如下所示:
目录结构
├── PX4-Autopilot
│ └── build/px4_sitl_default
│ ├── external_modules
│ │ └── examples
│ │ └── px4_custom_uorb/libexamples__px4_custom_uorb.a
│ ├── uORB
│ │ └── topics/ext_hello_world.h
│ └── msg
│ └── ttopics_sources/ext_hello_world.cpp
└── PX4-ExternalModule
├── msg
│ ├── CMakeLists.txt
│ └── ext_hello_world.msg
└── src
├── CMakeLists.txt
└── examples
└── px4_custom_uorb
├── CMakeLists.txt
├── Kconfig
└── px4_custom_uorb.c
完整的PX4-ExternalModule代码,请链接下载。
3. 编译执行结果
基于SITL仿真环境,在PX4-Autopilot目录下,进行编译;
$ make px4_sitl EXTERNAL_MODULES_LOCATION=../PX4-ExternalModule/
然后,执行仿真环境;
$ make px4_sitl jmavsim
最后,测试下效果。
pxh> px4_custom_uorb
INFO [px4_custom_uorb] creating orb publish task_publish = 13
INFO [px4_custom_uorb] creating orb subscribe task_subscribe = 14
INFO [px4_custom_uorb] Hello world(subscribe): 0
INFO [px4_custom_uorb] Hello world(puslish): 1
INFO [px4_custom_uorb] Hello world(subscribe): 1
INFO [px4_custom_uorb] Hello world(puslish): 2
INFO [px4_custom_uorb] Hello world(subscribe): 2
INFO [px4_custom_uorb] Hello world(puslish): 3
INFO [px4_custom_uorb] Hello world(subscribe): 3
INFO [px4_custom_uorb] Hello world(puslish): 4
INFO [px4_custom_uorb] Hello world(subscribe): 4
INFO [px4_custom_uorb] Hello world(puslish): 5
INFO [px4_custom_uorb] px4_custom_uorb_publish exiting
INFO [px4_custom_uorb] Hello world(subscribe): 5
ERROR [px4_custom_uorb] Got no data within a second
ERROR [px4_custom_uorb] Got no data within a second
INFO [px4_custom_uorb] px4_custom_uorb_subscribe exiting
INFO [px4_custom_uorb] px4_custom_uorb_main exiting