以下是将 MAVLink协议 移植到 STM32 的详细教程,涵盖库生成、硬件适配、收发消息、调试验证等全流程,适用于无人机、机器人等需要与地面站(如QGroundControl)通信的场景。
1. 准备工作
硬件需求
STM32开发板(如STM32F4/F7/H7系列,需支持UART/USB/CAN等通信接口)。
调试工具:USB转TTL模块、逻辑分析仪(可选)。
安卓设备(运行QGC地面站)。
软件需求
STM32开发环境:STM32CubeIDE或Keil MDK。
MAVLink代码生成工具:pymavlink。
QGC安卓版:下载地址。
2. 生成MAVLink C库
步骤
安装Python工具链(需Python 3.6+):
bash
Copy Code
pip install pymavlink --user
克隆MAVLink仓库:
bash
Copy Code
git clone https://github.com/mavlink/mavlink.git
cd mavlink
生成C代码(以common.xml协议为例):
bash
Copy Code
python -m pymavlink.tools.mavgen --lang=C --wire-protocol=2.0 --output=generated/mavlink ./message_definitions/v1.0/common.xml
关键参数:
--lang=C:生成C语言代码。
--wire-protocol=2.0:使用MAVLink 2.0协议(支持更长的消息和签名)。
--output:输出目录。
裁剪生成的代码(可选):
若资源紧张,可只保留需要的消息(如common.xml中的HEARTBEAT, ATTITUDE等),删除无关消息定义。
3. 集成MAVLink库到STM32项目
文件结构
将生成的MAVLink库添加到项目中:
text
Copy Code
Your_Project/
├── Core/
│ ├── Inc/
│ └── Src/
├── Drivers/
├── MAVLink/
│ ├── generated/ # 生成的MAVLink代码
│ ├── mavlink_adapt.c # 硬件适配代码
│ └── mavlink_adapt.h
└── ...
硬件适配
MAVLink需要底层通信接口(如UART)的支持,需实现以下函数:
修改mavlink_helpers.h
注释掉默认的错误提示:
c
Copy Code
// 注释或删除以下行
// #error YOU HAVE TO IMPLEMENT THE PLATFORM-SPECIFIC FUNCTIONS
实现发送/接收函数(以UART为例)
在mavlink_adapt.c中:
c
Copy Code
#include "stm32f4xx_hal.h" // 根据实际芯片型号调整
#include "mavlink_adapt.h"
// 定义UART句柄(例如UART1)
extern UART_HandleTypeDef huart1;
// 发送单个字节到串口
void mavlink_send_byte(uint8_t ch) {
HAL_UART_Transmit(&huart1, &ch, 1, HAL_MAX_DELAY);
}
// 从串口接收字节(阻塞方式)
uint8_t mavlink_receive_byte() {
uint8_t ch;
HAL_UART_Receive(&huart1, &ch, 1, HAL_MAX_DELAY);
return ch;
}
在mavlink_adapt.h中声明函数:
c
Copy Code
#pragma once
void mavlink_send_byte(uint8_t ch);
uint8_t mavlink_receive_byte();
4. 初始化MAVLink
配置通信接口
在main.c中初始化UART(以STM32CubeMX生成的代码为例):
c
Copy Code
// 初始化UART1(波特率115200,8N1)
void MX_USART1_UART_Init(void) {
huart1.Instance = USART1;
huart1.Init.BaudRate = 115200;
huart1.Init.WordLength = UART_WORDLENGTH_8B;
huart1.Init.StopBits = UART_STOPBITS_1;
huart1.Init.Parity = UART_PARITY_NONE;
huart1.Init.Mode = UART_MODE_TX_RX;
HAL_UART_Init(&huart1);
}
定义MAVLink系统参数
在全局变量中定义系统ID和组件ID:
c
Copy Code
#include "mavlink.h"
mavlink_system_t mavlink_system = {
.sysid = 1, // 系统ID(STM32设备标识)
.compid = 1 // 组件ID(如飞控、传感器等)
};
5. 发送MAVLink消息
示例:发送心跳包(HEARTBEAT)
c
Copy Code
void send_heartbeat(void) {
mavlink_message_t msg;
mavlink_msg_heartbeat_pack(
mavlink_system.sysid,
mavlink_system.compid,
&msg,
MAV_TYPE_QUADROTOR, // 设备类型(四旋翼)
MAV_AUTOPILOT_PX4, // 飞控类型(PX4)
MAV_MODE_PREFLIGHT, // 模式(准备状态)
0, // 自定义模式
MAV_STATE_STANDBY // 状态(待命)
);
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
uint16_t len = mavlink_msg_to_send_buffer(buf, &msg);
HAL_UART_Transmit(&huart1, buf, len, 1000); // 发送到串口
}
示例:发送姿态数据(ATTITUDE)
c
Copy Code
void send_attitude(float roll, float pitch, float yaw) {
mavlink_message_t msg;
mavlink_msg_attitude_pack(
mavlink_system.sysid,
mavlink_system.compid,
&msg,
HAL_GetTick(), // 时间戳(毫秒)
roll, pitch, yaw,
0, 0, 0 // 角速度(可选)
);
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
uint16_t len = mavlink_msg_to_send_buffer(buf, &msg);
HAL_UART_Transmit(&huart1, buf, len, 1000);
}
6. 接收MAVLink消息
解析地面站指令
c
Copy Code
void mavlink_receive_task(void) {
mavlink_message_t msg;
mavlink_status_t status;
while (1) {
uint8_t byte = mavlink_receive_byte(); // 阻塞接收字节
if (mavlink_parse_char(MAVLINK_COMM_0, byte, &msg, &status)) {
switch (msg.msgid) {
case MAVLINK_MSG_ID_HEARTBEAT:
// 处理心跳包(例如同步状态)
break;
case MAVLINK_MSG_ID_COMMAND_LONG:
// 处理QGC发送的长指令(如航点)
mavlink_command_long_t cmd;
mavlink_msg_command_long_decode(&msg, &cmd);
if (cmd.command == MAV_CMD_NAV_WAYPOINT) {
// 执行航点任务
}
break;
}
}
}
}
7. 调试与验证
QGC地面站验证
连接设备:
将STM32通过USB或蓝牙连接到安卓设备。
在QGC中进入 Settings > Comm Links,添加串口连接,设置波特率(如115200)。
查看MAVLink消息:
进入 Analyze > MAVLink Inspector,确认收到HEARTBEAT、ATTITUDE等消息。
逻辑分析仪调试
捕获UART信号,验证数据是否符合MAVLink帧格式:
text
Copy Code
[起始符][载荷长度][序列号][系统ID][组件ID][消息ID][数据][校验和]
8. 高级优化
资源占用优化
裁剪MAVLink库:仅保留需要的消息(如删除ardupilotmega.xml中未使用的消息)。
启用消息流控:通过MAV_CMD_SET_MESSAGE_INTERVAL控制数据发送频率。
RTOS集成
在FreeRTOS中创建独立任务处理MAVLink通信:
c
Copy Code
void mavlink_task(void *pvParameters) {
while (1) {
send_heartbeat();
osDelay(1000); // 每秒发送一次心跳
}
}
自定义消息
修改XML定义:在message_definitions/v1.0/下创建自定义消息XML文件。
重新生成代码:指定自定义XML文件生成新的C代码。
在QGC中显示:修改QGC源码以支持自定义消息(或使用插件)。
9. 常见问题
QGC无法识别设备
原因:未发送HEARTBEAT消息或协议版本不匹配。
解决:确保STM32定时发送心跳包,并检查MAVLink版本(QGC默认支持2.0)。
数据丢包
原因:UART波特率过高或STM32处理速度不足。
解决:降低波特率(如57600),或优化代码减少阻塞。
内存不足
原因:MAVLink库占用过多RAM/Flash。
解决:裁剪无关消息,或使用内存池管理缓冲区。
通过以上步骤,可完成MAVLink协议在STM32上的移植,并与QGC地面站实现稳定通信。对于更复杂的应用(如自定义消息、安全签名),建议参考MAVLink官方文档。