PX4 Board 层硬件配置

一、Board 层的定位

PX4 在 boards/<vendor>/<model> 路径下为每块飞控硬件维护一套独立的配置文件。第二层是厂家名,第三层是型号。这套机制的意义在于:将同一份 PX4 源码绑定到具体的硬件板,把硬件差异集中收敛到一个目录内,避免其扩散进驱动层、算法层与应用层,从而保证代码的可维护性与可移植性。

每块飞控的差异信息分为四类:

类别 内容
硬件事实 引脚分配、外设实例、总线拓扑、Flash/RAM 布局、是否含 IO MCU
RTOS 配置 NuttX 内核裁剪、驱动开关、堆栈/内存区、链接脚本
系统装配 默认启动哪些驱动、传感器、参数覆盖
可选变体 同一板的不同固件组合:default/protected/cyphal/debug/test 等

二、目录文件结构

boards/px4/fmu-v5/ 为例:

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
boards/px4/fmu-v5/
├── board_config.h # 核心:GPIO/ADC/定时器/外设宏定义
├── CMakeLists.txt # 板级 CMake
├── src/
│ ├── init.c # NuttX bringup 入口(stm32_boardinitialize)
│ ├── board_config.h # 同上
│ └── timer_config.cpp # PWM 通道到 TIM 的映射表
├── extras/ # bootloader bin、IO MCU 固件等
├── init/ # 启动脚本(rc.board_sensors 等)
└── nuttx-config/ # NuttX defconfig 变体
├── nsh/defconfig # 常规调试配置(带 NSH Shell)
├── debug/defconfig # 调试版:严格断言、符号表
├── protected/defconfig # 内存保护版:kernel/user 分离
├── cyphal/defconfig # Cyphal 网络栈配置
└── stackcheck/defconfig# 栈水位检测配置

extras/ 目录

该目录存放板级配套镜像,会被打包进 ROMFS,属于硬件生命周期管理的一部分,不参与模块逻辑:

  • px4_fmu-v5_bootloader.bin:bootloader,比固件先运行,负责固件升级
  • PX4_io-v2_default.bin:IO MCU 侧的固件镜像

FMU-v5 采用 FMU + IO 双 MCU 架构:FMU 运行 PX4 主系统,IO 专职处理 PWM/RC 等实时 IO,分担 FMU 负载。

init/ 目录

存放启动装配脚本。不同板的传感器配置不同,例如 CUAV 7nano 与 FMU-v5 的默认 IMU 驱动存在差异。关键文件:

  • rc.board_defaults:设置该板的默认参数与环境变量
  • rc.board_sensors:启动并配置传感器驱动,指定总线、片选、安装方向

三、.px4board 与 defconfig 的关系

.px4board 是板级 defconfig 配方,用于生成最终的 .config,包含:

  • CONFIG_MODULES_*:哪些 PX4 模块编译进固件
  • Drivers:驱动配置
  • SYSCMDS:命令
  • BOARD:默认串口映射、架构、工具链

Kconfig 定义所有可选项与依赖规则,default.px4board 给出 FMU-v5 的默认配置快照,依赖求解后生成最终的 .config,CMake/编译器再消费 .configautoconf.h,决定固件内容。

板级变体的两个维度相互配套但不绝对一一对应:

维度 说明
NuttX Profile(defconfig) RTOS 形态变体,决定 NuttX 如何编译
PX4 board variant(.px4board) 决定固件包含哪些模块/ROMFS/参数

四、GPIO 常量定义

板级 GPIO 宏本质是一个位域常量,将每个引脚的端口、复用、编号、上下拉、速度、默认电平编码为一个 uint32_t

1
2
3
4
5
6
7
8
9
10
11
12
13
14
// 位域编码示意
// 端口与引脚号
GPIO_PORTx | GPIO_PINn
// 模式
GPIO_INPUT / GPIO_OUTPUT / GPIO_ALT / GPIO_ANALOG
// 上下拉
GPIO_PULLUP / GPIO_PULLDOWN / GPIO_FLOAT
// 输出类型
GPIO_PUSHPULL / GPIO_OPENDRAIN
// 速度
GPIO_SPEED_*
// 默认输出电平
GPIO_OUTPUT_SET / GPIO_OUTPUT_CLEAR
// 复用功能号 AF

n 前缀(如 GPIO_nARMED)表示该信号硬件上低有效,board 层会封装一层 True_logic 宏屏蔽反相细节:

1
2
// GPIO_nxxx 低有效:on_true 时执行 !(value)
// GPIO_xxx 正相:on_true 时执行 value

boards/px4/fmu-v5/src/board_config.h 集中定义了所有引脚宏,位域编码由 platforms/nuttx/Nuttx/nuttx/arch/arm/src/stm32f7/stm32_gpio.h 提供。


五、ADC 通道映射

Board 层将对应 GPIO 配成模拟输入,并为每个采样功能分配逻辑通道。ADC_CHANNELS 位图决定驱动实际采样哪些通道,该位图会配合 BOARD_HAS_NBAT_V / BOARD_HAS_NBAT_T 条件编译生成不同结果,以适配不同的电池监控配置。


六、HRT/PPM 定时器

HRT(High Resolution Timer)提供系统微秒级时间基准:

  • hrt_absolute_time():整个系统的唯一微秒时间戳来源
  • 定时回调:周期任务触发
  • 与传感器/控制周期相关的精确定时

选择一个硬件定时器作 free-running 基准与比较中断,以 FMU-v5 为例:

1
2
3
#define HRT_TIMER           8      // 使用 TIM8
#define HRT_TIMER_CHANNEL 3 // CH3 做比较捕获
#define HRT_PPM_CHANNEL 1 // CH1 做 PPM 输入捕获

PPM 捕获与 HRT 时基共用同一颗定时器:PPM 捕获依赖输入捕获记录脉冲时刻,挂在 HRT 的 TIM 上可保证时间域一致。

PWM 输入(PWMIN)

单通道 PWM 捕获使用独立定时器:

1
2
3
#define PWMIN_TIMER         4      // TIM4
#define PWMIN_TIMER_CHANNEL 2 // CH2(T4C2)
// GPIO_PWM_IN 配置为 TIM4_CH2 输入

区别:PPM 一条线上串多个通道信息,解析帧间隔与通道脉宽序列;PWMIN 单路 PWM,直接测占空比与高电平脉宽。


七、蜂鸣器定时器

蜂鸣器采用脚复用切换方式控制:

1
2
#define TONE_ALARM_TIMER    9     // TIM9
#define TONE_ALARM_CHANNEL 1 // CH1(PE5)
  • 不响时:配置为 GPIO 输出固定电平,避免漂浮/杂音
  • 要响时:切换到 TIM9_CH1,由定时器改变频率与占空比产生音调

八、PX4IO 串口链路

FMU-v5 将 FMU 与 IO MCU 之间的高速通信链路固定为 UART8:

1
2
3
4
5
#define BOARD_USES_PX4IO_VERSION     2
#define PX4IO_SERIAL_DEVICE "/dev/ttyS6" // NuttX 设备节点
#define PX4IO_SERIAL_BASE STM32_UART8_BASE
#define PX4IO_SERIAL_VECTOR STM32_IRQ_UART8
#define PX4IO_SERIAL_BITRATE 1500000 // 1.5 Mbps

完整宏集合还包括 TX/RX 引脚复用宏、DMA 映射、RCC 时钟门控寄存器等。

ttyS6 到 UART8 的映射链

NuttX 串口驱动层在启动时根据 nuttx-config 决定启用哪些 UART 实例,注册顺序决定编号。board_config.h 通过宏将关键链路固定到具体设备节点,并同时提供底层寄存器信息供驱动直接使用,不依赖 NuttX 通用串口驱动层的动态查找。


九、PX4_GPIO_INIT_LIST

上电阶段一次性将关键引脚配置到正确状态,主要工作:

操作 目的
ADC 引脚切模拟输入 避免数字模式造成错误电压读取与噪声耦合
板版本驱动引脚初始化 配合 ADC 读数识别硬件版本
CAN TX/RX 复用 AF,收发器静默脚默认电平 保证总线上电后不被错误驱动
I2C SCL/SDA 强制拉低 清理可能挂死的 I2C 总线

I2C 总线恢复原理:外设异常复位或上电顺序不一致时,SCL/SDA 可能被拉住导致总线挂死。将线路临时改为 GPIO 并输出低/释放序列,可抢回总线控制权,随后再切换到 I2C 复用模式由驱动接管。


十、I2C 功能实现

I2C 功能的最小闭环:

1
2
3
传感器驱动调用 I2C transfer -> 写寄存器地址(参照数据手册 WHOAMI 等) -> 读数据
-> 驱动解析数据并发布 uORB(磁力计、气压计、距离传感器)
-> 上层模块订阅 uORB 使用

常见 I2C 挂死原因:

  • 传输过程中外设掉电/复位,状态机停在等待时钟或拉住 SDA
  • 外设时钟拉伸异常或内部卡死(调试期不要打印大量日志,否则 WorkQueue 阻塞后 I2C 超时概率上升)
  • 上电时序导致外设误识别起始条件

十一、Board 层梳理

board_config.h 是板级硬件抽象层,被 NuttX bringupPX4 平台层驱动层共同使用,集中定义:

  • GPIO 配置宏:LED、电源使能、过流输入、PPM/PWMIN、蜂鸣器等
  • ADC 通道定义与位图
  • HRT/PPM/TONE alarm/PWMIN 的定时器选择
  • PX4IO 串口链路完整参数

init.c 作为 NuttX 板级 bringup 的入口,执行顺序:

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
stm32_boardinitialize()(早期)
-> board_on_reset(-1):PWM 引脚到安全态
-> board_autoled_initialize():最早可用的 LED 输出
-> px4_gpio_init(PX4_GPIO_INIT_LIST):引脚初始化到确定状态
-> board_control_spi_sensor_power_configgpio:SPI 传感器供电配置
-> stm32_usbinitialize():USB 早期初始化

board_app_initialize()(应用层初始化,PX4 起来前的最后板级准备)
-> 打开各路电源 rail(SD、5V 外设、5V hipower、RC 等)
-> px4_platform_init():要求 HRT 已可用
-> board_determine_hw_info():读取 HW version/revision
-> stm32_spiinitialize():确定 HW 版本后配置 SPI
-> board_dma_alloc_init():DMA allocator
-> drv_led_start():进入 PX4 LED 驱动
-> stm32_sdio_initialize():SD 卡初始化

下一篇:SOC 与 BSP 层平台抽象