HELLO SKY 例子
首先呢,我们需要在 Firmware/src 目录下创建文件example文件或者按照(http://dev.px4.io/tutorial-hello-sky.html)中的第一步进行下载。在example文件中创建文件px4_simple_app文件。该文件包含的文件: px4_simple_app.c 和Cmake文件。(其实呢,你可以在http://dev.px4.io/tutorial-hello-sky.html中看英文文档的step 1,然后下过来)
该.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<uORB/uORB.h>
#include<uORB/topics/sensor_combined.h>
#include<uORB/topics/vehicle_attitude.h>
__
EXPORT intpx4_simple_app_main(int argc, char *argv[]);
intpx4_simple_app_main(int argc, char *argv[])
{
PX4_INFO(
"Hello Sky!");
return
OK;
}
然后写好c程序之后呢,就是将我们的应用添加到Nuttshell中啦。
对于pixhawkv1/2,我们可以在
Firmware/cmake/configs/nuttx_px4fmu-v2_default.cmake
中添加examples/px4_simple_app(其实该文件中已经添加好了,仔细找一下然后删删掉就好了 没有找到的话就自己添加下喽)
再 build it:
- Pixhawk v1/2: make px4fmu-v2_default
最后,激动人心的时刻到啦,就是把程序刷到飞控板里(此次针对pixhawk):
make px4fmu-v2_default upload
就喔啦。
值得注意的是,我开始刷固件的时候,飞控板一直连不上ubuntu,搞了我好久。最后,重启下电脑后,ubuntu就找到设备了,好狗!
订阅传感器数据
通常,应用需要订阅输入和发布输出(e.g. motor or servo commands).PX4平台的硬件抽象层就体现在这(当飞控板或传感器更新的话,我们不需要重新再写传感器的驱动和更新我们自己的app)。也就是说,两个部分是独立的。
应用间的各个消息通道称为px4的主题。so,我们会对sensor_combinedtopic(整个系统实时的传感器数据)感兴趣。
对一个主题的订阅是快速且安全的:
#include<uORB/topics/sensor_combined.h>
..
int sensor_sub_fd =orb_subscribe(ORB_ID(sensor_combined));
sensor_sub_fd是一个主题的handle,且可以有效的作为一个blocking去等待新数据的到来。当前的线程可以休眠,而且当有新的可行的数据到来时可以自动唤醒(通过时刻表)。在等待的过程中,不会消耗任何CPUcycles。我们通过查询机制(poll())去做到这一点。
在订阅过程中增添poll(),例子如下:
#include<poll.h>
#include<uORB/topics/sensor_combined.h>
..
int sensor_sub_fd = orb_subscribe(ORB_ID(sensor_combined));
/* one could wait for multiple topics with this technique, just using one here */
px4_pollfd_struct_t fds[] = {
{ .fd = sensor_sub_fd, .events = POLLIN },
};
while(
true) {
/* wait for sensor update of 1 file descriptor for 1000 ms (1 second) */
int
poll_ret = px4_poll(fds,
1,
1000);
..
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]);
}
}
之后通过 make 进行编译。
Testing the uORB Subscription
最后一步是在后台中启动我们的application(也就是px4_simple_app
)。
px4_simple_app &
在console中会出现我们的传感器数据:比如
接下来会解释如何去写一个可以通过命令行控制的deamon。
Step 7: Publishing Data
去使用计算处理后的输出,下一步是发布结果(获得传感器数据并进行处理后,我们当然要发布这些数据啦)。如果我们使用"mavlink"将主题转发到QGC,我们可以直接在qgc上看到结果。so,我们使用attitude来达到这个目的。
该接口十分简单: 将某主题的结构发布再通告该主题( Initialize the struct ofthe topic to be published and advertise the topic):
#include<uORB/topics/vehicle_attitude.h>
..
/* advertise attitude topic */
struct vehicle_attitude_s att;
memset(&att,
0,
sizeof(att));
orb_advert_t att_pub_fd = orb_advertise(ORB_ID(vehicle_attitude), &att);
在main loop中,一旦某个数据准备好后就发布该消息:
orb_publish(ORB_ID(vehicle_attitude), att_pub_fd, &att);
完整的代码例子如下:
#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<uORB/uORB.h>
#include<uORB/topics/sensor_combined.h>
#include<uORB/topics/vehicle_attitude.h>
__
EXPORT intpx4_simple_app_main(int argc, char *argv[]);
intpx4_simple_app_main(int argc, char *argv[])
{
PX4_INFO(
"Hello Sky!");
/* subscribe to sensor_combined topic */
int
sensor_sub_fd = orb_subscribe(ORB_ID(sensor_combined));
orb_set_interval(sensor_sub_fd,
1000);
/* advertise attitude topic */
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_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
(
inti =
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(
"[px4_simple_app] Got no data within a second");
}
elseif
(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(
"[px4_simple_app] ERROR return value from poll(): %d"
, 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);
PX4_WARN(
"[px4_simple_app] Accelerometer:\t%8.4f\t%8.4f\t%8.4f",
(
double)raw.accelerometer_m_s2[
0],
(
double)raw.accelerometer_m_s2[
1],
(
double)raw.accelerometer_m_s2[
2]);
/* set att and publish this information for other apps */
att.roll = raw.accelerometer_m_s2[
0];
att.pitch = raw.accelerometer_m_s2[
1];
att.yaw = raw.accelerometer_m_s2[
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
;
}
Finally, 我们在来run一下px4_simple_app
。