Skip to content

串口映射

本主题展示了如何确定通用同步/异步收发器(USART)/通用异步收发器(UART)串口设备名称(例如“ttyS0”)与飞行控制器上相关端口(如 TELEM1TELEM2GPS1RC SBUSDebug console)之间的映射关系。

这些说明用于在飞行控制器文档中生成串口映射表。 例如:Pixhawk 4 > 串口映射

INFO

在大多数情况下,分配给每个端口的功能不一定要与端口名称匹配,并且是通过 串口配置 来设置的。 通常,端口功能会被配置为与名称匹配,这就是为什么标记为 GPS1 的端口可以直接与 GPS 设备配合使用的原因。

基于 STMxxyyy 架构的 NuttX 系统

本节展示了如何通过检查板卡配置文件,获取基于 STMxxyyy 架构的 NuttX 构建的串口映射关系。 以下说明以 FMUv5 为例,但同样可以扩展应用于其他 FMU 版本或基于 NuttX 的板卡。

default.px4board 文件

default.px4board 文件列出了一些串口映射关系(搜索文本 “SERIAL_PORTS”)。

/boards/px4/fmu-v5/default.px4board 中:

CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0"
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1"
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS2"
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS3"

或者,您可以使用 make px4_fmu-v5 boardconfig 启动板卡配置,然后进入串口菜单:

    串口  --->
        (/dev/ttyS0) GPS1 串口端口
        ()  GPS2 串口端口
        ()  GPS3 串口端口
        ()  GPS4 串口端口
        ()  GPS5 串口端口
        (/dev/ttyS1) TEL1 串口端口
        (/dev/ttyS2) TEL2 串口端口
        ()  TEL3 串口端口
        (/dev/ttyS3) TEL4 串口端口
        ()  TEL5 串口端口

nsh/defconfig 文件

nsh/defconfig 文件可让您确定已定义的端口、这些端口是 UART 还是 USART,以及 USART/UART 与设备之间的映射关系。 您还可以确定哪个端口用于 串口/调试控制台

打开板卡的 defconfig 文件,例如:/boards/px4/fmu-v5/nuttx-config/nsh/defconfig

搜索文本 “ART”,直到找到类似以下格式的条目 CONFIG_STM32xx_USARTn=y(其中 xx 是处理器类型,n 是端口号)。 例如:

CONFIG_STM32F7_UART4=y
CONFIG_STM32F7_UART7=y
CONFIG_STM32F7_UART8=y
CONFIG_STM32F7_USART1=y
CONFIG_STM32F7_USART2=y
CONFIG_STM32F7_USART3=y
CONFIG_STM32F7_USART6=y

这些条目告诉您已定义的端口,以及它们是 UART 还是 USART。

复制上述部分内容,并按 “n” 的数值顺序重新排列。 同时递增设备编号 ttySn(从 0 开始),以获取设备到串口的映射关系。

ttyS0 CONFIG_STM32F7_USART1=y
ttyS1 CONFIG_STM32F7_USART2=y
ttyS2 CONFIG_STM32F7_USART3=y
ttyS3 CONFIG_STM32F7_UART4=y
ttyS4 CONFIG_STM32F7_USART6=y
ttyS5 CONFIG_STM32F7_UART7=y
ttyS6 CONFIG_STM32F7_UART8=y

要获取调试控制台的映射关系,我们在 defconfig 文件 中搜索 SERIAL_CONSOLE。 从下面可以看到,控制台使用的是 UART7:

CONFIG_UART7_SERIAL_CONSOLE=y

board_config.h 文件

对于配备 IO 板的飞行控制器,通过在 board_config.h 中搜索 PX4IO_SERIAL_DEVICE 来确定 PX4IO 的连接情况。

例如,在 /boards/px4/fmu-v5/src/board_config.h 中:

#define PX4IO_SERIAL_DEVICE            "/dev/ttyS6"
#define PX4IO_SERIAL_TX_GPIO           GPIO_UART8_TX
#define PX4IO_SERIAL_RX_GPIO           GPIO_UART8_RX
#define PX4IO_SERIAL_BASE              STM32_UART8_BASE

所以,PX4IO 连接在 ttyS6 端口(我们还可以看到,这对应于 UART8,这与前面部分得出的结论一致)。

汇总所有信息

最终的映射关系如下:

ttyS0 CONFIG_STM32F7_USART1=y GPS1
ttyS1 CONFIG_STM32F7_USART2=y TEL1
ttyS2 CONFIG_STM32F7_USART3=y TEL2
ttyS3 CONFIG_STM32F7_UART4=y TEL4
ttyS4 CONFIG_STM32F7_USART6=y
ttyS5 CONFIG_STM32F7_UART7=y DEBUG
ttyS6 CONFIG_STM32F7_UART8=y PX4IO

飞行控制器文档 中,生成的表格如下:

UART设备端口
UART1/dev/ttyS0GPS
USART2/dev/ttyS1TELEM1(流控制)
USART3/dev/ttyS2TELEM2(流控制)
UART4/dev/ttyS3TELEM4
USART6/dev/ttyS4RC SBUS
UART7/dev/ttyS5调试控制台
UART8/dev/ttyS6PX4IO

其他架构

INFO

欢迎提供相关内容!

另请参阅