Skip to content

搭建你的第一个应用(Hello Sky)

本文主要介绍如何创建并运行第一个板载应用程序,涵盖了PX4应用程序开发所需的基本概念和API。

注意事项

为简化内容,省略了如启动/停止功能和命令行参数等更高级的特性,这些内容在应用程序/模块模板中有介绍。

系统必备组件

在开始之前,你需要准备以下内容:

源代码目录[PX4 - Autopilot/src/examples/px4_simple_app](https://github.com/PX4/PX4 - Autopilot/tree/main/src/examples/px4_simple_app)包含了本教程的完整版本,若遇到困难可参考。同时,建议重命名(或删除)px4_simple_app目录。

最小的应用程序

此部分将创建一个仅打印Hello Sky!的最小应用程序,它由一个C文件和一个cmake定义文件组成,cmake文件用于指导工具链构建应用程序。具体步骤如下:

  1. 创建目录:在PX4 - Autopilot/src/examples/下创建新目录px4_simple_app
  2. 创建C文件:在新目录中创建名为px4_simple_app.c的C文件,先复制默认头部注释到文件顶部,该注释需出现在所有贡献文件中,示例如下:
c
/****************************************************************************
 *
 *   Copyright (c) 2012 - 2022 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.
 *
 ****************************************************************************/

接着,在头部注释下方复制以下代码:

c
/**
 * @file px4_simple_app.c
 * Minimal application example for PX4 autopilot
 *
 * @author Example User <mail@example.com>
 */

#include <px4_platform_common/log.h>

__EXPORT int px4_simple_app_main(int argc, char *argv[]);

int px4_simple_app_main(int argc, char *argv[])
{
    PX4_INFO("Hello Sky!");
    return OK;
}

这里有两个提示需要注意: - 主函数必须命名为<模块名>_main,并按上述方式从模块中导出。 - PX4_INFO相当于PX4外壳中的printf,包含在px4_platform_common/log.h中。PX4有不同的日志级别,如PX4_INFOPX4_WARNPX4_ERRPX4_DEBUG,警告和错误信息还会添加到ULog中,并在飞行审查中显示。 3. 创建cmake定义文件:在目录中创建并打开名为CMakeLists.txt的文件,复制以下文本:

cmake
############################################################################
#
#   Copyright (c) 2015 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.
#
############################################################################
px4_add_module(
    MODULE examples__px4_simple_app
    MAIN px4_simple_app
    STACK_MAIN 2000
    SRCS
        px4_simple_app.c
    DEPENDS
    )

px4_add_module()方法根据模块描述构建静态库,其中: - MODULE块是模块在固件中的唯一名称,按照惯例,模块名称以src为根目录的父目录作为前缀。 - MAIN块列出模块的入口点,它会在NuttX中注册该命令,以便能从PX4外壳或SITL控制台调用。 此外,还有两个提示: - px4_add_module()的格式在[PX4 - Autopilot/cmake/px4_add_module.cmake](https://github.com/PX4/PX4 - Autopilot/blob/main/cmake/px4_add_module.cmake)中有文档说明。 - 若在px4_add_module中指定DYNAMIC选项,在POSIX平台上会创建共享库而非静态库。共享库可在不重新编译PX4的情况下加载,还能以二进制文件形式分发给他人。应用程序不会成为内置命令,而是生成名为examples__px4_simple_app.px4mod的单独文件,可在运行时使用dyn命令加载该文件来运行应用:dyn ./examples__px4_simple_app.px4mod。 4. 创建Kconfig定义文件:创建并打开名为Kconfig的文件,定义用于命名的符号(可参考[Kconfig命名约定](../hardware/porting_guide_config.md#px4 - kconfig - symbol - naming - convention)),复制以下文本:

menuconfig EXAMPLES_PX4_SIMPLE_APP
    bool "px4_simple_app"
    default n
    ---help---
        Enable support for px4_simple_app

编译应用程序/固件

应用程序编写完成后,要确保其作为PX4的一部分进行构建。应用程序通过目标平台相应的板级_px4board_文件添加到构建/固件中,不同平台对应的文件如下:

  • PX4 SITL(模拟器):[PX4 - Autopilot/boards/px4/sitl/default.px4board](https://github.com/PX4/PX4 - Autopilot/blob/main/boards/px4/sitl/default.px4board)
  • Pixhawk v1/2:[PX4 - Autopilot/boards/px4/fmu - v2/default.px4board](https://github.com/PX4/PX4 - Autopilot/blob/main/boards/px4/fmu - v2/default.px4board)
  • Pixracer (px4/fmu - v4):[PX4 - Autopilot/boards/px4/fmu - v4/default.px4board](https://github.com/PX4/PX4 - Autopilot/blob/main/boards/px4/fmu - v4/default.px4board)
  • 其他板的_px4board_文件可在[PX4 - Autopilot/boards/](https://github.com/PX4/PX4 - Autopilot/tree/main/boards)中找到

要启用应用程序到固件的编译,可在_px4board_文件中添加相应的Kconfig键CONFIG_EXAMPLES_PX4_SIMPLE_APP=y,或者运行[boardconfig](../hardware/porting_guide_config.md#px4 - menuconfig - setup) make px4_fmu - v4_default boardconfig

examples  --->
    [x] PX4 Simple app  ----

多数文件中该配置行可能已存在,因为示例默认包含在固件中。

使用特定板的命令构建示例:

  • jMAVSim模拟器:make px4_sitl_default jmavsim
  • Pixhawk v1/2:make px4_fmu - v2_default(或直接make px4_fmu - v2
  • Pixhawk v3:make px4_fmu - v4_default
  • 其他板:[构建代码](../dev_setup/building_px4.md#building - for - nuttx)

测试应用

硬件测试
  • 上传固件至飞控板:启用上传器,然后重启飞控板,不同型号飞控板的命令如下:
    • Pixhawk v1/2:make px4_fmu - v2_default upload
    • Pixhawk v3:make px4_fmu - v4_default upload 在重启飞控板前,会打印一些编译消息,最后显示:
sh
Loaded firmware for X,X, waiting for the bootloader...

飞控板重启并完成固件上传后,命令行界面输出:

sh
Erase  : [====================] 100.0%
Program: [====================] 100.0%
Verify : [====================] 100.0%
Rebooting.

[100%] Built target upload
  • 连接至控制台:通过串口或USB连接到系统控制台,按下ENTER键显示外壳提示符:
sh
nsh>

输入“help”并回车,输出如下:

sh
nsh> help
  help usage:  help [-v] [<cmd>]

  [           df          kill        mkfifo      ps          sleep
  ?           echo        losetup     mkrd        pwd         test
  cat         exec        ls          mh          rm          umount
  cd          exit        mb          mount       rmdir       unset
  cp          free        mkdir       mv          set         usleep
  dd          help        mkfatfs     mw          sh          xd

Builtin Apps:
  reboot
  perf
  top
  ..
  px4_simple_app
  ..
  sercon
  serdis

可见px4_simple_app已成为可用命令之一。输入px4_simple_app并回车启动应用:

sh
nsh> px4_simple_app
Hello Sky!

这表明应用程序已正确注册到系统中,可进一步扩展以执行实用任务。

SITL测试

若使用SITL,_PX4控制台_会自动启动(参考[构建代码 > 首次构建(使用模拟器)](../dev_setup/building_px4.md#first - build - using - a - simulator))。和_nsh控制台_一样,输入help可查看内置应用列表。输入px4_simple_app运行最小应用程序:

sh
pxh> px4_simple_app
INFO  [px4_simple_app] Hello Sky!

之后可对应用程序进行扩展以实现实用功能。

订阅传感器数据

为实现实用功能,应用程序需订阅输入数据并发布输出数据(如电机或伺服命令)。PX4的硬件抽象优势在此体现,无需与传感器驱动程序交互,即使板卡或传感器更新,也无需更新应用程序。

应用程序间的单个消息通道称为主题,本教程关注[SensorCombined](https://github.com/PX4/PX4 - Autopilot/blob/main/msg/SensorCombined.msg)主题,它包含整个系统的同步传感器数据。订阅主题的代码如下:

cpp
#include <uORB/topics/sensor_combined.h>
..
int sensor_sub_fd = orb_subscribe(ORB_ID(sensor_combined));

sensor_sub_fd是主题句柄,可高效进行阻塞等待新数据。当前线程进入休眠状态,有新数据时会被调度器自动唤醒,等待时不消耗CPU周期。使用poll() POSIX系统调用实现该功能,添加poll()的伪代码如下:

cpp
#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);
        PX4_INFO("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]);
    }
}

再次编译应用程序可输入:

sh
make
测试uORB消息订阅

在nsh shell中输入以下命令将应用程序作为后台进程/任务启动:

sh
px4_simple_app &

应用程序会在控制台显示5个传感器值(需使用完整示例代码,伪代码会连续输出且无法退出),然后退出:

sh
[px4_simple_app] Accelerometer:   0.0483          0.0821          0.0332
[px4_simple_app] Accelerometer:   0.0486          0.0820          0.0336
[px4_simple_app] Accelerometer:   0.0487          0.0819          0.0327
[px4_simple_app] Accelerometer:   0.0482          0.0818          0.0323
[px4_simple_app] Accelerometer:   0.0482          0.0827          0.0331
[px4_simple_app] Accelerometer:   0.0489          0.0804          0.0328

完整应用程序的模块模板可用于编写能从命令行控制的后台进程。

发布数据

为使用计算得到的输出结果,需要发布数据。下面展示如何发布姿态主题:

c
#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);

在主循环中随时发布信息:

c
orb_publish(ORB_ID(vehicle_attitude), att_pub_fd, &att);

完整的示例代码

完整示例代码如下:

c
/****************************************************************************
 *
 *   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