PX4串口通信
一、硬件准备
1.飞控型号:支持PX41.14.1的硬件(Matek H73-wing)。
2.串口接口: 选择飞控的UART端口(PX4有TELEM1、TELEM2、GPS1等),根据硬件手册及代码确认引脚定义。
3.连接设备: 电脑(串口调试助手)。
4.连接方式: 串口转USB。
二、PX4串口设置
在H7系列主控中,串口通常启用1,2,3,4,6,7,8。由于移植PX4固件,后续配置中关闭串口1 ,所以存在2,3,4,6,7,8。分别对应:
UART(STM32H7) |
Device(NuttX) |
USART2 |
/dev/ttyS0 |
USART3 |
/dev/ttyS1 |
UART4 |
/dev/ttyS2 |
USART6 |
/dev/ttyS3 |
UART7 |
/dev/ttyS4 |
UART8 |
/dev/ttyS5 |

定义自定义wing.px4board文件:
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0" CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS4" CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS5" CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS2" CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS3" CONFIG_MODULES_RW_UART=y wing.px4board
|
二、PX4固件驱动开发
1.添加串口功能:
-在modules下添加rw_uart文件。

-包括CMakeLists.txt;Kconfig和rw_uart.c文件
-在编写完所有程序后,需要make matek_h743_wing boardconfig 使能rw_uart模组。
-CMakeLists.txt文件如下:添加rw_uart模组
px4_add_module( MODULE modules__rw_uart MAIN rw_uart STACK_MAIN 2000 SRCS rw_uart.c DEPENDS ) CMakeLists.txt
|
参数说明:
参数 |
值/内容 |
说明 |
`MODULE` |
modules\ __ rw_uart |
模块在构建系统中的路径标识符 |
`MAIN` |
rw\_uart |
指定模块的主函数入口名称 |
`STACK_MAIN` |
2000 |
为主函数分配的任务堆栈大小(单位:字节) |
`SRCS` |
rw\_uart.c |
模块的源代码文件列表 |
`DEPENDS` |
(空) |
模块依赖的其他组件/库(当前未指定依赖项) |
-Kconfig文件如下:
menuconfig MODULES_RW_UART bool "rw_uart" default n ---help--- Enable support for rw_uart Kconfig
|
2.编写串口收发代码:
#include <stdio.h> #include <termios.h> #include <unistd.h> #include <stdlib.h> #include <string.h> #include <stdbool.h> #include <errno.h> #include <drivers/drv_hrt.h> #include <systemlib/err.h> #include <fcntl.h> #include <systemlib/mavlink_log.h>
#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 <drivers/drv_hrt.h> #include <uORB/topics/sensor_accel.h> #include <uORB/topics/sensor_gyro.h> #include <uORB/uORB.h>
static bool thread_should_exit = false; static bool thread_running = false; static int rw_uart_task;
static int uart_init(char * uart_name); static int set_uart_baudrate(const int fd, unsigned int baud);
__EXPORT int rw_uart_main(int argc, char *argv[]);
int rw_uart_thread_main(int argc, char *argv[]);
static void usage(const char *reason);
static void usage(const char *reason) { if (reason) { warnx("%s\n", reason); }
warnx("usage: px4_uorb_adver {start|stop|status} [-p <additional params>]\n\n"); }
int set_uart_baudrate(const int fd, unsigned int baud) { int speed;
switch (baud) { case 9600: speed = B9600; break; case 19200: speed = B19200; break; case 38400: speed = B38400; break; case 57600: speed = B57600; break; case 115200: speed = B115200; break; default: warnx("ERR: baudrate: %d\n", baud); return -EINVAL; }
struct termios uart_config; int termios_state;
tcgetattr(fd, &uart_config);
uart_config.c_oflag &= ~ONLCR;
uart_config.c_cflag &= ~(CSTOPB | PARENB); uart_config.c_cflag |= CS8;
if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) { warnx("ERR: %d (cfsetispeed)\n", termios_state); return false; }
if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) { warnx("ERR: %d (cfsetospeed)\n", termios_state); return false; }
if ((termios_state = tcsetattr(fd, TCSANOW, &uart_config)) < 0) { warnx("ERR: %d (tcsetattr)\n", termios_state); return false; }
return true; }
int uart_init(char * uart_name) { int serial_fd = open(uart_name, O_RDWR | O_NOCTTY); if (serial_fd < 0) { err(1, "failed to open port: %s", uart_name); printf("failed to open port: %s\n", uart_name); return false; } printf("Open the %d\n", serial_fd); return serial_fd; }
int rw_uart_main(int argc, char *argv[]) { if (argc < 2) { usage("missing command"); return 1; }
if (!strcmp(argv[1], "start")) {
if (thread_running) { warnx("px4_uorb_subs already running\n"); return 0; }
thread_should_exit = false; rw_uart_task = px4_task_spawn_cmd("rw_uart", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 2000, rw_uart_thread_main, (argv) ? (char *const *)&argv[2] : (char *const *)NULL); return 0; }
if (!strcmp(argv[1], "stop")) { thread_should_exit = true; return 0; }
if (!strcmp(argv[1], "status")) { if (thread_running) { warnx("\trunning\n");
} else { warnx("\tnot started\n"); }
return 0; }
usage("unrecognized command"); return 1; }
int rw_uart_thread_main(int argc, char *argv[]) { int uart_read = uart_init("/dev/ttyS2"); if (false == uart_read) return -1; if (false == set_uart_baudrate(uart_read, 57600)) { printf("[JXF]set_uart_baudrate is failed\n"); return -1; } printf("[JXF]uart init is successful\n");
thread_running = true;
char buffer_1[] = "XYT"; char buffer_2 = '\n';
while (!thread_should_exit) { printf("Sending data: %s\n", buffer_1);
write(uart_read, &buffer_1, strlen(buffer_1)); usleep(50000);
write(uart_read, &buffer_2, sizeof(buffer_2)); printf("rw_uart TX-test: running!\n");
usleep(1000000); }
warnx("[rw_uart] exiting.\n"); thread_running = false; int fd = close(uart_read); printf("close status: %d\n", fd); return 0; } rw_uart.c
|
3.映射串口设备:
-对于需要修改默认串口映射的硬件(如代码中/dev/ttyS2),即串口4。
-代码中波特率为57600,数据位8位,停止位1位,无奇偶校验。
-连接:蓝线为TXD连接RXD;绿线为RXD连接TXD,图片容易产生误导。

三、测试与验证
硬件连接检查:
- 使用万用表确认TX/RX/GND引脚连接正确,避免电平不匹配(如3.3V与5V设备)。
串口助手测试:
- 在PC端使用串口调试工具发送测试指令,观察飞控响应。
结果分析:对于字符串能够正确发送电脑。

四、注意事项
- 固件兼容性:PX4 1.14.1的API可能与旧版本存在差异,建议参考官方文档更新代码。提示出现参数错误,可升级QGC。
- 权限问题:Linux系统下需确保用户对
/dev/ttyS*
设备有读写权限(可配置udev规则)。
- 抗干扰设计:长距离通信时建议增加校验位或使用RS485转换模块。