PX4实战(三):PX4 Mavlink模块代码详解
- 前言
- 1 Mavlink协议是什么?
- 1.1 Mavlink数据格式
- 1.2 Mavlink由v1进化到v2原因
- 2 PX4中Mavlink协议代码解读
- 2.1 Mavlink模块结构
- 2.2 Mavlink模块核心代码讲解
- 2.2.1 mavlink_main(主循环)
- 2.2.1.1 单个模块如何启动的?
- 2.2.1.2 进入task_main函数周期运行
- 2.2.2 mavlink_messages(对外输出数据)
- 2.2.3 mavlink_receiver(接收数据)
- 2.2.3.1 run函数解读
- 2.2.4 mavlink_mission(航线处理逻辑)
- 2.2.4.1 模块功能与定位
- 2.2.4.2 主要类结构与核心函数
- 2.2.4.3 MAVLink Mission 通信流程与状态机
- 3 Mavlink模块实战相关
- 3.1 自定义Mavlink协议
- 3.2 Mavlink协议对外发送
- 3.2 修改对外发送频率
前言
本节主要讲解Mavlink协议基础内容、PX4中mavlink模块代码讲解、用户如何自定义mavlink协议等。
1 Mavlink协议是什么?
PX4为了实现与QGC、机载电脑、第三方硬件模块(比如光流模块等)等的数据交互,一般都是通过Mavlink协议实现。当前飞控里mavlink协议比较流行。
Mavlink不是硬件,也不是一个具体的软件,而是一套规则。就像英语有语法一样,MAVLink规定了消息应该如何组织、格式是什么样的。所有人都按这个规则来,就不会产生误解。
Mavlink协议的特点:
- 非常轻量: 它的“数据包”格式非常精简,头部开销很小。
- 非常高效: 编码和解码速度很快,不占用太多计算资源。
- 鲁棒性强: 那个校验码 让它非常抗干扰,数据传输可靠。
- 可扩展: 如果官方定义的消息不够用,你还可以自定义自己的消息类型,非常灵活。
- 双向通信: 不仅仅是无人机向地面站发数据,地面站也可以向无人机发送指令,实现完全的控制。
1.1 Mavlink数据格式
Mavlink详细内容看见官网:Mavlink协议官网,主要分v1和v2两个版本。
Mavlink v1数据包格式如下:

- STX:起始标记、1字节。v1版本:0xFE,v2版本:0xFD。告诉解析器:“一个新的 MAVLink V1 数据包开始了!”
- LEN:负载长度、1 字节,0 ~ 255。指示后面的 PAYLOAD 字段有多少个字节。
- SEQ:包序列号、1字节,0 ~ 255,然后循环。用于检测丢包。
- SYS ID:系统 ID、1 字节,标识发送此消息的整个系统(例如,一架无人机)。在一个网络内,每个系统(无人机、地面站等)应有唯一的 ID。
- COMP ID:组件 ID、 1 字节,标识系统内部的一个特定组件(例如,飞控、云台、机载电脑等)。
- MSG ID:消息 ID、1字节, 这是数据包的核心, 它定义了 PAYLOAD 数据部分的具体含义。例如,MSGID=0 代表 HEARTBEAT 消息,MSGID=33 代表 GLOBAL_POSITION_INT 消息。接收方根据 MSGID 来知道应该如何解析后面的 PAYLOAD。
- PAYLOAD:数据负载,0 ~ 255 字节(由 LEN 字段指定),存放消息的实际数据内容。例如,如果这是一个位置消息,那么 PAYLOAD 里就装着经纬度、高度、速度等具体数值。
- CHECLSUM:CRC (Cyclic Redundancy Check) - 循环冗余校验,2 字节,用于检测数据在传输过程中是否出错。它由 STX 之后 的所有字节(包括 PAYLOAD)计算得出。接收方会用同样的算法计算一遍 CRC,如果结果不匹配,则说明数据包有误,会被丢弃。
Mavlink v2数据包格式如下:

- STX:起始标记、1字节。这是与 V1 最直观的区别!解析器看到 0xFD,就知道这是一个 V2 数据包,会按照 V2 的规则来解析。
- LEN:负载长度、1 字节,0 ~ 255。指示后面的 PAYLOAD 字段有多少个字节。
- INC FLAGS:不兼容标志、1 字节, 这是一个关键字段! 它指示了此数据包包含哪些 V1 解析器无法处理的新特性。如果 V1 解析器看到一个它不认识的标志位(比如签名标志 0x01),它就会拒绝这个数据包。这保证了向后兼容的“安全降级”。
- CP FLAGS:兼容标志、1字节,指示此数据包包含哪些 V1 解析器可以安全忽略的新特性。这样,V1 解析器即使不能完全理解,也能部分处理这个消息。
- SEC:包序列号、1字节,0 ~ 255,然后循环。用于检测丢包。
- SYS ID:系统 ID、1 字节,标识发送此消息的整个系统(例如,一架无人机)。在一个网络内,每个系统(无人机、地面站等)应有唯一的 ID。
- COM ID:组件 ID、 1 字节,标识系统内部的一个特定组件(例如,飞控、云台、机载电脑等)。
- MSG ID:**消息 ID (扩展)、3字节,这是 V2 的重大改进, V1 的 1 字节 MSGID 只能定义 256 种不同的消息,远远不够。V2 将其扩展为 3 字节(约 1600 万种),为未来定义了海量的消息类型留下了充足空间。
- PAYLOAD:数据负载,0 ~ 255 字节(由 LEN 字段指定),存放消息的实际数据内容。例如,如果这是一个位置消息,那么 PAYLOAD 里就装着经纬度、高度、速度等具体数值。
- CHECKSUM:CRC (Cyclic Redundancy Check) - 循环冗余校验,2 字节,用于检测数据在传输过程中是否出错。它由 STX 之后 的所有字节(包括 PAYLOAD)计算得出。接收方会用同样的算法计算一遍 CRC,如果结果不匹配,则说明数据包有误,会被丢弃。
- SIGNAYURE:签名 (可选)、13 字节,当 INCOMPAT FLAGS 中的 0x01 位被置位时,此字段存在。提供了身份验证和防篡改能力。 它使用预共享的密钥和时间戳等信息计算得出,可以确保数据包来自可信的来源,并且在传输过程中未被修改。这是无人机在开放无线电环境中对抗恶意欺骗和攻击的关键安全特性。
1.2 Mavlink由v1进化到v2原因
MAVLink V2 的出现是为了解决 V1 在长期实践中暴露出的局限性,是一次旨在满足现代无人机和机器人系统更高要求的全面升级。
- 消息类型数量限制
| 版本 | 消息 ID 长度 | 最大消息数 | 问题描述 |
|---|---|---|---|
| MAVLink V1 | 1 字节 | 256 | 对于日益复杂的无人机、机器人应用和不断增长的硬件生态系统,256 种消息类型已经完全不够用,严重限制了协议的发展。 |
| MAVLink V2 | 3 字节 | 16,777,216 | 提供了近乎无限的消息定义空间,为未来多年的功能扩展和新设备集成奠定了坚实的基础。 |
- 安全性不足
| 版本 | 安全机制 | 风险 |
|---|---|---|
| MAVLink V1 | 无任何加密或认证机制。数据包是明文传输的。 | 1. 欺骗攻击:任何攻击者都可以伪造"起飞"、"降落"或"返航"指令。 2. 数据篡改:攻击者可以篡改传回地面站的GPS、电量等关键数据。 3. 非常危险,尤其是在开放无线电环境中。 |
| MAVLink V2 | 引入了可选的 13 字节签名机制。 | 1. 身份验证:确保数据包来自持有合法密钥的可信设备。 2. 防篡改:CRC 和签名共同保证了数据的完整性,任何修改都会被检测到。 3. 关键安全特性,极大地提升了系统对抗恶意攻击的能力。 |
- 有效负载与兼容性管理
| 版本 | 兼容性管理 | 有效负载 |
|---|---|---|
| MAVLink V1 | 没有标准机制来安全地引入新特性。如果增加新字段,旧的解析器会无法正确解析,导致通信失败。 | 理论 255 字节,但在实际无线电传输中受 MTU 限制。 |
| MAVLink V2 | 引入了不兼容标志位 和兼容标志位。 | 通过优化包结构,在增加大量功能后,依然保持了与 V1 相近的有效负载能力(通常最长 253 字节)。 |
2 PX4中Mavlink协议代码解读
2.1 Mavlink模块结构
PX4中mavlink模块目录如下:


各模块主要功能:
- mavlink文件夹:这里面就是从mavlink官方下载的官方代码,自定义协议时也是在这里面定义。
- mavlink_tests:mavlink模块相关功能测试代码。
- streams:这里面是PX4中mavlink协议对外发送数据的地方。
- mavlink_command_sender:PX4对外可靠发送vehicle_command_s命令的模块,主要通过超时重传机制实现可靠传输。单机了解可。
- mavlink_events:实现了 MAVLink 协议的事件消息系统,用于向地面站报告 PX4 飞行控制器的各种系统事件、状态变化、错误和警告信息。了解可。
- mavlink_ftp:MAVLink FTP 协议允许地面站(如 QGroundControl)通过 MAVLink 消息与飞行控制器进行文件传输和文件系统操作,类似于一个简化的 FTP 协议。了解可。
- mavlink_log_handler:PX4 中 MAVLink 日志处理器的实现代码,实时日志显示。处理的日志是实时的 STATUSTEXT 消息,把飞控内的日志消息转换成 MAVLink 消息。
- mavlink_main: PX4 中 MAVLink 主模块的实现代码,是整个 MAVLink 系统的核心调度和管理器。
- mavlink_messages:PX4 中 MAVLink 消息流系统的实现代码,负责管理和创建所有 MAVLink 数据流,将 PX4 内部的 uORB 数据转换为 MAVLink 消息并发送出去。
- mavlink_mission:实现 PX4 与地面站(如 QGroundControl)之间的任务(Mission)上传、下载、清除、状态同步等通信逻辑。
- mavlink_parameters:PX4内参数设置与同步模块。
- mavlink_rate_limiter:MAVLink 系统中的“消息发送限速器”,用于控制特定消息的发送频率,防止带宽被淹没。
- mavlink_receiver:PX4中mavlink协议接收的入口点,所有数据的接收都首先走这里,比如航线传输也会先到这里但是航线处理具体逻辑在mavlink_mission模块内。
- mavlink_shell:允许地面站(如 QGroundControl)通过 MAVLink 协议打开一个“终端窗口”,直接在飞控系统中执行命令,就像在串口终端或 nsh shell 中一样。
- mavlink_stream:mavlink对外发送频率的基类,管理所有 stream 的时间间隔、控制速率、自适应带宽,不关心消息内容。
- mavlink_timesync:时间同步模块,让飞控(PX4)与地面站或伴飞计算机(Companion Computer)之间的时间保持一致。
- mavlink_ulog:通过 MAVLink 协议发送 PX4 的完整日志文件(.ulg),是 PX4 日志传输模块,而不是实时日志显示。
2.2 Mavlink模块核心代码讲解
2.2.1 mavlink_main(主循环)
2.2.1.1 单个模块如何启动的?
每个功能模块都会有自己下面的main函数,这个函数是如何启动的呢?是PX4内部的一套流程,简单了解可,知道每个模块都会执行到自己的mian函数。
extern "C" __EXPORT int mavlink_main(int argc, char *argv[])
{
if (argc < 2) {
usage();
return 1;
}
if (!strcmp(argv[1], "start")) {
return Mavlink::start(argc, argv);
} else if (!strcmp(argv[1], "stop-all")) {
return Mavlink::destroy_all_instances();
} else if (!strcmp(argv[1], "status")) {
bool show_streams_status = argc > 2 && strcmp(argv[2], "streams") == 0;
return Mavlink::get_status_all_instances(show_streams_status);
} else if (!strcmp(argv[1], "stop")) {
return Mavlink::stop_command(argc, argv);
} else if (!strcmp(argv[1], "stream")) {
return Mavlink::stream_command(argc, argv);
} else if (!strcmp(argv[1], "boot_complete")) {
Mavlink::set_boot_complete();
return 0;
} else {
usage();
return 1;
}
return 0;
}
- PX4的模块机制
在 PX4 中,每一个像 mavlink 这样的应用或驱动,都是一个“模块”(module)。PX4 在启动时不会直接运行系统级 main(),而是运行一个 PX4 的 shell(px4 shell 或 nsh),通过命令的方式去加载和调用模块(这里就是之前讲的rcS启动脚本)。执行mavlink start命令后mavlink模块就启动了。但是,PX4 是如何知道 mavlink 命令对应的函数是 mavlink_main()呢? - __EXPORT 与模块注册机制
PX4 中每个模块的入口函数都遵循统一命名规则:
extern "C" __EXPORT int <module_name>_main(int argc, char *argv[]);
这里的关键点有两个:
extern "C"
让函数符号名保持 C 风格(避免 C++ 名字改编),保证在链接时和查找时可以直接用字符串 “mavlink_main” 找到。
__EXPORT
宏定义为:
#define __EXPORT __attribute__ ((visibility ("default")))
意思是让这个符号在最终编译成 PX4 的可执行程序或模块时是可见的(不会被优化掉或隐藏)。这样,PX4 的命令调度系统在加载时能在符号表中找到 “mavlink_main” 这个函数。
- 模块查找与命令调度机制
PX4 的命令行系统(无论是 px4 shell 还是 NSH)都通过一个模块注册系统来查找命令。在 PX4 源码中,这由 module.h 和 module_command.cpp 管理。每个模块在构建时都会自动注册成一个命令。当用户输入命令时,PX4 会在内部的命令表中查找是否存在该模块名。找到后,就调用 _main(argc, argv) 函数。这个注册过程是在编译时自动完成的,通过 构建系统(CMake) 自动为每个模块生成模块描述符。
例如:
src/modules/mavlink/CMakeLists.txt
中会包含:
px4_add_module(
MODULE modules__mavlink
MAIN mavlink
...
)
- CMake 自动生成模块注册表
px4_add_module 宏在 CMake 中的定义会自动生成一个对应的符号注册,例如:
int mavlink_main(int argc, char *argv[]);
并将 mavlink 这个模块名字与该函数指针关联。PX4 编译系统会自动创建一个模块注册表(类似于命令表):
const px4_module_t px4_modules[] = {
{"mavlink", mavlink_main},
{"commander", commander_main},
{"logger", logger_main},
...
};
因此当你输入mavlink start,它会匹配到{“mavlink”, mavlink_main},然后调用 mavlink_main(argc, argv)执行。
上面就是模块启动的过程,是PX4内部自己的一套流程,知道可。
2.2.1.2 进入task_main函数周期运行
进入周期运行函数过程:
mavlink_main()
→ Mavlink::start()
→ px4_task_spawn_cmd(...) 启动新线程
→ Mavlink::task_main()



task_main函数源码及解读:
int
Mavlink::task_main(int argc, char *argv[])
{
// If stdin, stdout and/or stderr file descriptors (0, 1, 2)
// are not open when mavlink module starts (as might be the case for USB auto-start),
// use default /dev/null so that these numbers are not used by other other files.
if (fcntl(0, F_GETFD) == -1) {
int tmp = open("/dev/null", O_RDONLY);
if (tmp != 0) {
dup2(tmp, 0);
close(tmp);
}
}
if (fcntl(1, F_GETFD) == -1) {
int tmp = open("/dev/null", O_WRONLY);
if (tmp != 1) {
dup2(tmp, 1);
close(tmp);
}
}
if (fcntl(2, F_GETFD) == -1) {
int tmp = open("/dev/null", O_WRONLY);
if (tmp != 2) {
dup2(tmp, 2);
close(tmp);
}
}
int ch;
_baudrate = 57600;
_datarate = 0;
_mode = MAVLINK_MODE_COUNT;
FLOW_CONTROL_MODE _flow_control = FLOW_CONTROL_AUTO;
_interface_name = nullptr;
// We don't care about the name and verb at this point.
argc -= 2;
argv += 2;
/* don't exit from getopt loop to leave getopt global variables in consistent state,
* set error flag instead */
bool err_flag = false;
int myoptind = 1;
const char *myoptarg = nullptr;
#if defined(CONFIG_NET) || defined(__PX4_POSIX)
int temp_int_arg;
#endif
// 命令行参数解析,比如:mavlink start -d /dev/ttyS1 -b 57600 -m onboard
/**
* -d:指定设备名(如 /dev/ttyS1)
* -b:串口波特率
* 等等
*/
while ((ch = px4_getopt(argc, argv, "b:r:d:n:u:o:m:t:c:fswxzZp", &myoptind, &myoptarg)) != EOF) {
switch (ch) {
case 'b':
if (px4_get_parameter_value(myoptarg, _baudrate) != 0) {
PX4_ERR("baudrate parsing failed");
err_flag = true;
}
if (_baudrate < 9600 || _baudrate > 3000000) {
PX4_ERR("invalid baud rate '%s'", myoptarg);
err_flag = true;
}
break;
case 'r':
if (px4_get_parameter_value(myoptarg, _datarate) != 0) {
PX4_ERR("datarate parsing failed");
err_flag = true;
}
if (_datarate > MAX_DATA_RATE) {
PX4_ERR("invalid data rate '%s'", myoptarg);
err_flag = true;
}
break;
case 'd':
_device_name = myoptarg;
set_protocol(Protocol::SERIAL);
if (access(_device_name, F_OK) == -1) {
PX4_ERR("Device %s does not exist", _device_name);
err_flag = true;
}
break;
case 'n':
_interface_name = myoptarg;
break;
#if defined(MAVLINK_UDP)
case 'u':
if (px4_get_parameter_value(myoptarg, temp_int_arg) != 0) {
PX4_ERR("invalid data udp_port");
err_flag = true;
} else {
_network_port = temp_int_arg;
set_protocol(Protocol::UDP);
}
break;
case 'o':
if (px4_get_parameter_value(myoptarg, temp_int_arg) != 0) {
PX4_ERR("invalid remote udp_port");
err_flag = true;
} else {
_remote_port = temp_int_arg;
set_protocol(Protocol::UDP);
}
break;
case 't':
_src_addr.sin_family = AF_INET;
if (inet_aton(myoptarg, &_src_addr.sin_addr)) {
_src_addr_initialized = true;
} else {
PX4_ERR("invalid partner ip '%s'", myoptarg);
err_flag = true;
}
break;
case 'p':
_mav_broadcast = BROADCAST_MODE_ON;
break;
#if defined(CONFIG_NET_IGMP) && defined(CONFIG_NET_ROUTE)
// multicast
case 'c':
_src_addr.sin_family = AF_INET;
if (inet_aton(myoptarg, &_src_addr.sin_addr)) {
_src_addr_initialized = true;
_mav_broadcast = BROADCAST_MODE_MULTICAST;
} else {
PX4_ERR("invalid partner ip '%s'", myoptarg);
err_flag = true;
}
break;
#else
case 'c':
PX4_ERR("Multicast option is not supported on this platform");
err_flag = true;
break;
#endif
#else
case 'p':
case 'u':
case 'o':
case 't':
PX4_ERR("UDP options not supported on this platform");
err_flag = true;
break;
#endif
// case 'e':
// _mavlink_link_termination_allowed = true;
// break;
case 'm': {
int mode;
if (px4_get_parameter_value(myoptarg, mode) == 0) {
if (mode >= 0 && mode < (int)MAVLINK_MODE_COUNT) {
_mode = (MAVLINK_MODE)mode;
} else {
PX4_ERR("invalid mode");
err_flag = true;
}
} else {
if (strcmp(myoptarg, "custom") == 0) {
_mode = MAVLINK_MODE_CUSTOM;
} else if (strcmp(myoptarg, "camera") == 0) {
// left in here for compatibility
_mode = MAVLINK_MODE_ONBOARD;
} else if (strcmp(myoptarg, "onboard") == 0) {
_mode = MAVLINK_MODE_ONBOARD;
} else if (strcmp(myoptarg, "osd") == 0) {
_mode = MAVLINK_MODE_OSD;
} else if (strcmp(myoptarg, "magic") == 0) {
_mode = MAVLINK_MODE_MAGIC;
} else if (strcmp(myoptarg, "config") == 0) {
_mode = MAVLINK_MODE_CONFIG;
} else if (strcmp(myoptarg, "iridium") == 0) {
_mode = MAVLINK_MODE_IRIDIUM;
set_telemetry_status_type(telemetry_status_s::LINK_TYPE_IRIDIUM);
} else if (strcmp(myoptarg, "minimal") == 0) {
_mode = MAVLINK_MODE_MINIMAL;
} else if (strcmp(myoptarg, "extvision") == 0) {
_mode = MAVLINK_MODE_EXTVISION;
} else if (strcmp(myoptarg, "extvisionmin") == 0) {
_mode = MAVLINK_MODE_EXTVISIONMIN;
} else if (strcmp(myoptarg, "gimbal") == 0) {
_mode = MAVLINK_MODE_GIMBAL;
} else if (strcmp(myoptarg, "onboard_low_bandwidth") == 0) {
_mode = MAVLINK_MODE_ONBOARD_LOW_BANDWIDTH;
} else if (strcmp(myoptarg, "uavionix") == 0) {
_mode = MAVLINK_MODE_UAVIONIX;
} else {
PX4_ERR("invalid mode");
err_flag = true;
}
}
break;
}
case 'f':
_forwarding_on = true;
break;
case 's':
_use_software_mav_throttling = true;
break;
case 'w':
_wait_to_transmit = true;
break;
case 'x':
_ftp_on = true;
break;
case 'z':
_flow_control = FLOW_CONTROL_ON;
break;
case 'Z':
_flow_control = FLOW_CONTROL_OFF;
break;
default:
err_flag = true;
break;
}
}
if (err_flag) {
usage();
return PX4_ERROR;
}
/* USB serial is indicated by /dev/ttyACMx */
// 自动识别 /dev/ttyACM* 为 USB 连接,
if (strncmp(_device_name, "/dev/ttyACM", 11) == 0) {
if (_datarate == 0) {
_datarate = 100000;
}
/* USB has no baudrate, but use a magic number for 'fast' */
_baudrate = 2000000;
if (_mode == MAVLINK_MODE_COUNT) {
_mode = MAVLINK_MODE_CONFIG;
}
_ftp_on = true;
_is_usb_uart = true;
// Always forward messages to/from the USB instance.
_forwarding_on = true;
set_telemetry_status_type(telemetry_status_s::LINK_TYPE_USB);
}
if (_mode == MAVLINK_MODE_COUNT) {
_mode = MAVLINK_MODE_NORMAL;
}
if (_datarate == 0) {
/* convert bits to bytes and use 1/2 of bandwidth by default */
_datarate = _baudrate / 20;
}
if (_datarate > MAX_DATA_RATE) {
_datarate = MAX_DATA_RATE;
}
if (get_protocol() == Protocol::SERIAL) {
if (Mavlink::serial_instance_exists(_device_name, this)) {
PX4_ERR("%s already running", _device_name);
return PX4_ERROR;
}
PX4_INFO("mode: %s, data rate: %d B/s on %s @ %dB",
mavlink_mode_str(_mode), _datarate, _device_name, _baudrate);
/* flush stdout in case MAVLink is about to take it over */
fflush(stdout);
}
#if defined(MAVLINK_UDP)
else if (get_protocol() == Protocol::UDP) {
if (Mavlink::get_instance_for_network_port(_network_port) != nullptr) {
PX4_ERR("port %hu already occupied", _network_port);
return PX4_ERROR;
}
PX4_INFO("mode: %s, data rate: %d B/s on udp port %hu remote port %hu",
mavlink_mode_str(_mode), _datarate, _network_port, _remote_port);
}
#endif // MAVLINK_UDP
// 设置实例 ID、互斥锁与缓存,每个 MAVLink 通道(串口/UDP)有唯一 instance ID,分配对应的 MAVLink 通道号(channel)
// 创建互斥锁(发送、消息缓存、radio 状态保护),若启用了 forwarding(比如串口1启动了,串口1发出的数据也将透传到其他串口),
// 初始化消息环形缓冲区 _message_buffer
if (set_instance_id()) {
if (!set_channel()) {
PX4_ERR("set channel failed");
return PX4_ERROR;
}
// set thread name
char thread_name[13];
snprintf(thread_name, sizeof(thread_name), "mavlink_if%d", get_instance_id());
px4_prctl(PR_SET_NAME, thread_name, px4_getpid());
} else {
PX4_ERR("no instances available");
return PX4_ERROR;
}
pthread_mutex_init(&_message_buffer_mutex, nullptr);
pthread_mutex_init(&_send_mutex, nullptr);
pthread_mutex_init(&_radio_status_mutex, nullptr);
/* if we are passing on mavlink messages, we need to prepare a buffer for this instance */
if (get_forwarding_on()) {
/* initialize message buffer if multiplexing is on.
* make space for two messages plus off-by-one space as we use the empty element
* marker ring buffer approach.
*/
LockGuard lg{_message_buffer_mutex};
if (!_message_buffer.allocate(2 * sizeof(mavlink_message_t) + 1)) {
PX4_ERR("msg buf alloc fail");
return PX4_ERROR;
}
}
/* Activate sending the data by default (for the IRIDIUM mode it will be disabled after the first round of packages is sent)*/
_transmitting_enabled = true;
_transmitting_enabled_commanded = true;
if (_mode == MAVLINK_MODE_IRIDIUM) {
_transmitting_enabled_commanded = false;
}
/* add default streams depending on mode */
if (_mode != MAVLINK_MODE_IRIDIUM) {
/* HEARTBEAT is constant rate stream, rate never adjusted */
configure_stream("HEARTBEAT", 1.0f);
/* STATUSTEXT stream */
configure_stream("STATUSTEXT", 20.0f);
/* COMMAND_LONG stream: use unlimited rate to send all commands */
configure_stream("COMMAND_LONG");
}
if (configure_streams_to_default() != 0) {
PX4_ERR("configure_streams_to_default() failed");
}
/* set main loop delay depending on data rate to minimize CPU overhead */
_main_loop_delay = (MAIN_LOOP_DELAY * 1000) / _datarate;
/* hard limit to 1000 Hz at max */
if (_main_loop_delay < MAVLINK_MIN_INTERVAL) {
_main_loop_delay = MAVLINK_MIN_INTERVAL;
}
/* hard limit to 100 Hz at least */
if (_main_loop_delay > MAVLINK_MAX_INTERVAL) {
_main_loop_delay = MAVLINK_MAX_INTERVAL;
}
/* open the UART device after setting the instance, as it might block */
// 打开通信设备,
if (get_protocol() == Protocol::SERIAL) {
_uart_fd = mavlink_open_uart(_baudrate, _device_name, _flow_control);
if (_uart_fd < 0) {
PX4_ERR("could not open %s", _device_name);
return PX4_ERROR;
}
}
#if defined(MAVLINK_UDP)
/* init socket if necessary */
if (get_protocol() == Protocol::UDP) {
init_udp();
}
#endif // MAVLINK_UDP
_task_id = px4_getpid();
/* if the protocol is serial, we send the system version blindly */
if (get_protocol() == Protocol::SERIAL) {
send_autopilot_capabilities();
}
_receiver.start(); // 开启接收器,px4内所有数据的接收在这里面进行
uint16_t event_sequence_offset = 0; // offset to account for skipped events, not sent via MAVLink
_mavlink_start_time = hrt_absolute_time();
_task_running.store(true);
// 主循环:通信核心
/**
* should_exit():检查是否收到退出信号(例如模块被 stop)。若为真,跳出循环并清理.
* px4_usleep(_main_loop_delay):按 _main_loop_delay 微秒睡眠,控制循环频率(节省CPU,限定处理速率)
*/
while (!should_exit()) {
/* main loop */
px4_usleep(_main_lo op_delay);
if (!should_transmit()) {
check_requested_subscriptions();
continue;
}
perf_count(_loop_interval_perf);
perf_begin(_loop_perf);
const hrt_abstime t = hrt_absolute_time();
update_rate_mult();
// check for parameter updates 参数更新检查
if (_parameter_update_sub.updated()) {
// clear update
parameter_update_s pupdate;
_parameter_update_sub.copy(&pupdate);
// update parameters from storage
mavlink_update_parameters();
}
configure_sik_radio();
// vehicle_status 更新
if (_vehicle_status_sub.updated()) {
vehicle_status_s vehicle_status;
if (_vehicle_status_sub.copy(&vehicle_status)) {
/* switch HIL mode if required */
set_hil_enabled(vehicle_status.hil_state == vehicle_status_s::HIL_STATE_ON);
if (_mode == MAVLINK_MODE_IRIDIUM) {
if (_transmitting_enabled && vehicle_status.high_latency_data_link_lost &&
!_transmitting_enabled_commanded && _first_heartbeat_sent) {
_transmitting_enabled = false;
mavlink_log_info(&_mavlink_log_pub, "Disable transmitting with IRIDIUM mavlink on device %s\t", _device_name);
events::send<int8_t>(events::ID("mavlink_iridium_disable"), events::Log::Info,
"Disabling transmitting with IRIDIUM mavlink on instance {1}", _instance_id);
} else if (!_transmitting_enabled && !vehicle_status.high_latency_data_link_lost) {
_transmitting_enabled = true;
mavlink_log_info(&_mavlink_log_pub, "Enable transmitting with IRIDIUM mavlink on device %s\t", _device_name);
events::send<int8_t>(events::ID("mavlink_iridium_enable"), events::Log::Info,
"Enabling transmitting with IRIDIUM mavlink on instance {1}", _instance_id);
}
}
}
}
// MAVLINK_MODE_IRIDIUM: handle VEHICLE_CMD_CONTROL_HIGH_LATENCY
if (_mode == MAVLINK_MODE_IRIDIUM) {
int vehicle_command_updates = 0;
while (_vehicle_command_sub.updated() && (vehicle_command_updates < vehicle_command_s::ORB_QUEUE_LENGTH)) {
vehicle_command_updates++;
const unsigned last_generation = _vehicle_command_sub.get_last_generation();
vehicle_command_s vehicle_cmd;
if (_vehicle_command_sub.update(&vehicle_cmd)) {
if (_vehicle_command_sub.get_last_generation() != last_generation + 1) {
PX4_ERR("vehicle_command lost, generation %u -> %u", last_generation, _vehicle_command_sub.get_last_generation());
}
if ((vehicle_cmd.command == vehicle_command_s::VEHICLE_CMD_CONTROL_HIGH_LATENCY) &&
_mode == MAVLINK_MODE_IRIDIUM) {
if (vehicle_cmd.param1 > 0.5f) {
if (!_transmitting_enabled) {
mavlink_log_info(&_mavlink_log_pub, "Enable transmitting with IRIDIUM mavlink on device %s by command\t",
_device_name);
events::send<int8_t>(events::ID("mavlink_iridium_enable_cmd"), events::Log::Info,
"Enabling transmitting with IRIDIUM mavlink on instance {1} by command", _instance_id);
}
_transmitting_enabled = true;
_transmitting_enabled_commanded = true;
} else {
if (_transmitting_enabled) {
mavlink_log_info(&_mavlink_log_pub, "Disable transmitting with IRIDIUM mavlink on device %s by command\t",
_device_name);
events::send<int8_t>(events::ID("mavlink_iridium_disable_cmd"), events::Log::Info,
"Disabling transmitting with IRIDIUM mavlink on instance {1} by command", _instance_id);
}
_transmitting_enabled = false;
_transmitting_enabled_commanded = false;
}
// send positive command ack
vehicle_command_ack_s command_ack{};
command_ack.command = vehicle_cmd.command;
command_ack.result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
command_ack.from_external = !vehicle_cmd.from_external;
command_ack.target_system = vehicle_cmd.source_system;
command_ack.target_component = vehicle_cmd.source_component;
command_ack.timestamp = vehicle_cmd.timestamp;
_vehicle_command_ack_pub.publish(command_ack);
}
}
}
}
/* send command ACK */
bool cmd_logging_start_acknowledgement = false;
bool cmd_logging_stop_acknowledgement = false;
if (_vehicle_command_ack_sub.updated()) {
static constexpr size_t COMMAND_ACK_TOTAL_LEN = MAVLINK_MSG_ID_COMMAND_ACK_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
while ((get_free_tx_buf() >= COMMAND_ACK_TOTAL_LEN) && _vehicle_command_ack_sub.updated()) {
vehicle_command_ack_s command_ack;
const unsigned last_generation = _vehicle_command_ack_sub.get_last_generation();
if (_vehicle_command_ack_sub.update(&command_ack)) {
if (_vehicle_command_ack_sub.get_last_generation() != last_generation + 1) {
PX4_ERR("vehicle_command_ack lost, generation %u -> %u", last_generation,
_vehicle_command_ack_sub.get_last_generation());
}
const bool is_target_known = _receiver.component_was_seen(command_ack.target_system, command_ack.target_component);
if (!command_ack.from_external
&& command_ack.command < vehicle_command_s::VEHICLE_CMD_PX4_INTERNAL_START
&& is_target_known) {
mavlink_command_ack_t msg{};
msg.result = command_ack.result;
msg.command = command_ack.command;
msg.progress = command_ack.result_param1;
msg.result_param2 = command_ack.result_param2;
msg.target_system = command_ack.target_system;
msg.target_component = command_ack.target_component;
mavlink_msg_command_ack_send_struct(get_channel(), &msg);
if (command_ack.command == vehicle_command_s::VEHICLE_CMD_LOGGING_START) {
cmd_logging_start_acknowledgement = true;
} else if (command_ack.command == vehicle_command_s::VEHICLE_CMD_LOGGING_STOP
&& command_ack.result == vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED) {
cmd_logging_stop_acknowledgement = true;
}
}
}
}
}
// For legacy gimbals using the mavlink gimbal v1 protocol, we need to send out commands.
// We don't care about acks for these though.
if (_gimbal_v1_command_sub.updated()) {
vehicle_command_s cmd;
_gimbal_v1_command_sub.copy(&cmd);
// FIXME: filter for target system/component
mavlink_command_long_t msg{};
msg.param1 = cmd.param1;
msg.param2 = cmd.param2;
msg.param3 = cmd.param3;
msg.param4 = cmd.param4;
msg.param5 = cmd.param5;
msg.param6 = cmd.param6;
msg.param7 = cmd.param7;
msg.command = cmd.command;
msg.target_system = cmd.target_system;
msg.target_component = cmd.target_component;
msg.confirmation = 0;
mavlink_msg_command_long_send_struct(get_channel(), &msg);
}
/* check for shell output 检查 shell 输出并通过 SERIAL_CONTROL 发送*/
if (_mavlink_shell && _mavlink_shell->available() > 0) {
if (get_free_tx_buf() >= MAVLINK_MSG_ID_SERIAL_CONTROL_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) {
mavlink_serial_control_t msg;
msg.baudrate = 0;
msg.flags = SERIAL_CONTROL_FLAG_REPLY;
msg.timeout = 0;
msg.device = SERIAL_CONTROL_DEV_SHELL;
msg.count = _mavlink_shell->read(msg.data, sizeof(msg.data));
msg.target_system = _mavlink_shell->targetSysid();
msg.target_component = _mavlink_shell->targetCompid();
mavlink_msg_serial_control_send_struct(get_channel(), &msg);
}
}
check_requested_subscriptions();
/* update streams 更新消息流(streams),消息流可以认为是对外发送数据*/
for (const auto &stream : _streams) {
stream->update(t); // 依据当前时间决定是否发送该流的下一个消息(内部会检查频率、带宽、是否被订阅等)
if (!_first_heartbeat_sent) {
if (_mode == MAVLINK_MODE_IRIDIUM) {
if (stream->get_id() == MAVLINK_MSG_ID_HIGH_LATENCY2) {
_first_heartbeat_sent = stream->first_message_sent();
}
} else {
if (stream->get_id() == MAVLINK_MSG_ID_HEARTBEAT) {
_first_heartbeat_sent = stream->first_message_sent();
}
}
}
}
/* check for ulog streaming messages ulog(飞行日志)流处理*/
if (_mavlink_ulog) {
if (cmd_logging_stop_acknowledgement) {
_mavlink_ulog->stop();
_mavlink_ulog = nullptr;
} else {
if (cmd_logging_start_acknowledgement) {
_mavlink_ulog->start_ack_received();
}
int ret = _mavlink_ulog->handle_update(get_channel());
if (ret < 0) { //abort the streaming on error
if (ret != -1) {
PX4_WARN("mavlink ulog stream update failed, stopping (%i)", ret);
}
_mavlink_ulog->stop();
_mavlink_ulog = nullptr;
}
}
}
/* handle new events 事件(events)处理 */
if (check_events()) {
if (_event_sub.updated()) {
LockGuard lg{mavlink_module_mutex};
event_s orb_event;
while (_event_sub.update(&orb_event)) {
if (events::externalLogLevel(orb_event.log_levels) == events::LogLevel::Disabled) {
++event_sequence_offset; // skip this event
} else {
events::Event e;
e.id = orb_event.id;
e.timestamp_ms = orb_event.timestamp / 1000;
e.sequence = orb_event.event_sequence - event_sequence_offset;
e.log_levels = orb_event.log_levels;
static_assert(sizeof(e.arguments) == sizeof(orb_event.arguments),
"uorb message event: arguments size mismatch");
memcpy(e.arguments, orb_event.arguments, sizeof(orb_event.arguments));
_event_buffer->insert_event(e);
}
}
}
}
_events.update(t);
/* pass messages from other instances 转发来自其他实例的消息*/
if (get_forwarding_on()) {
mavlink_message_t msg;
size_t available_bytes;
{
// We only send one message at a time, not to put too much strain on a
// link from forwarded messages.
LockGuard lg{_message_buffer_mutex};
available_bytes = _message_buffer.pop_front(reinterpret_cast<uint8_t *>(&msg), sizeof(msg));
// We need to make sure to release the lock here before sending the
// bytes out via IP or UART which could potentially take longer.
}
if (available_bytes > 0) {
resend_message(&msg);
}
}
/* update TX/RX rates*/
if (t > _bytes_timestamp + 1_s) {
if (_bytes_timestamp != 0) {
const float dt = (t - _bytes_timestamp) * 1e-6f;
_tstatus.tx_rate_avg = _bytes_tx / dt;
_tstatus.tx_error_rate_avg = _bytes_txerr / dt;
_tstatus.rx_rate_avg = _bytes_rx / dt;
_bytes_tx = 0;
_bytes_txerr = 0;
_bytes_rx = 0;
}
_bytes_timestamp = t;
}
// publish status at 1 Hz, or sooner if HEARTBEAT has updated
if ((hrt_elapsed_time(&_tstatus.timestamp) >= 1_s) || _tstatus_updated) {
publish_telemetry_status();
}
perf_end(_loop_perf);
}
_receiver.stop();
delete _subscribe_to_stream;
_subscribe_to_stream = nullptr;
/* delete streams */
_streams.clear();
if (_uart_fd >= 0) {
/* discard all pending data, as close() might block otherwise on NuttX with flow control enabled */
tcflush(_uart_fd, TCIOFLUSH);
/* close UART */
::close(_uart_fd);
}
if (_socket_fd >= 0) {
close(_socket_fd);
_socket_fd = -1;
}
if (_mavlink_ulog) {
_mavlink_ulog->stop();
_mavlink_ulog = nullptr;
}
pthread_mutex_destroy(&_send_mutex);
pthread_mutex_destroy(&_radio_status_mutex);
pthread_mutex_destroy(&_message_buffer_mutex);
PX4_INFO("exiting channel %i", (int)_channel);
_task_running.store(false);
return OK;
}
流程总结:
初始化文件描述符(stdin/stdout/stderr)
↓
解析命令行参数(波特率、设备、模式等)
↓
根据协议类型(Serial / UDP)进行初始化
↓
设置实例 ID 与 MAVLink 通道号
↓
创建互斥锁与缓存区
↓
配置默认的消息流(streams,如 HEARTBEAT、STATUSTEXT)
↓
打开串口或 UDP socket
↓
启动接收线程(_receiver)
↓
进入主循环(发送、事件、参数、转发等逻辑)
↓
退出清理(关闭设备、销毁锁、释放资源)
2.2.2 mavlink_messages(对外输出数据)
PX4内对外流输出结构:
┌──────────────────────────────┐
│ PX4 内核 │
│ ┌────────────────────────┐ │
│ │ uORB Topics │ │
│ │ (vehicle_status, imu等)│ │
│ └────────────────────────┘ │
└──────────────┬───────────────┘
│
│ uORB 数据订阅
▼
┌──────────────────────────────────────┐
│ Mavlink 模块 (mavlink_main) │
│ ┌──────────────────────────────────┐ │
│ │ mavlink_messages.cpp │ │
│ │ ┌────────────────────────────┐ │ │
│ │ │ streams_list (注册表) │ │ │
│ │ ├────────────────────────────┤ │ │
│ │ │ create_mavlink_stream() │ │ │
│ │ ├────────────────────────────┤ │ │
│ │ │ 各 MavlinkStream 实现类 │ │ │
│ │ └────────────────────────────┘ │ │
│ └──────────────────────────────────┘ │
│ ▲ 发送 Mavlink 消息 │
└────────┴──────────────────────────────┘
│
▼
GCS / Companion Computer
mavlink_messages只是注册了数据流而已。

数据流发送的具体位置:

2.2.3 mavlink_receiver(接收数据)
2.2.3.1 run函数解读
初始化缓冲区与poll()
while (!should_exit) {
检查参数更新
poll等待数据
if (收到数据) {
read/recvfrom()
对每个字节:
mavlink_parse_char()
handle_message()
}
更新统计、mission、param、ftp等模块
}
┌──────────────────────────┐
│ 地面站 / Companion │
│ (QGroundControl, etc.) │
└──────────────┬───────────┘
│
MAVLink 消息
│
┌─────────────▼─────────────┐
│ MavlinkReceiver::run() │
│ (解析/分发线程) │
├───────────────────────────┤
│ handle_message() │
│ mission_manager.handle() │
│ parameter_manager.handle()│
│ ftp/log/timesync.handle() │
└─────────────┬─────────────┘
│
PX4 内部 uORB 系统
详细代码解读如下:
// 负责接收并解析来自地面站或机载计算机的MAVLink消息
void
MavlinkReceiver::run()
{
/* set thread name */
{
char thread_name[17];
snprintf(thread_name, sizeof(thread_name), "mavlink_rcv_if%d", _mavlink->get_instance_id());
px4_prctl(PR_SET_NAME, thread_name, px4_getpid());
}
// poll timeout in ms. Also defines the max update frequency of the mission & param manager, etc.
const int timeout = 10;
#if defined(__PX4_POSIX)
/* 1500 is the Wifi MTU, so we make sure to fit a full packet */
uint8_t buf[1600 * 5];
#elif defined(CONFIG_NET)
/* 1500 is the Wifi MTU, so we make sure to fit a full packet */
uint8_t buf[1000];
#else
/* the serial port buffers internally as well, we just need to fit a small chunk */
uint8_t buf[64];
#endif
mavlink_message_t msg;
struct pollfd fds[1] = {};
if (_mavlink->get_protocol() == Protocol::SERIAL) {
fds[0].fd = _mavlink->get_uart_fd();
fds[0].events = POLLIN;
}
#if defined(MAVLINK_UDP)
struct sockaddr_in srcaddr = {};
socklen_t addrlen = sizeof(srcaddr);
if (_mavlink->get_protocol() == Protocol::UDP) {
fds[0].fd = _mavlink->get_socket_fd();
fds[0].events = POLLIN;
}
#endif // MAVLINK_UDP
ssize_t nread = 0;
hrt_abstime last_send_update = 0;
// 主循环开始
while (!_mavlink->should_exit()) {
// check for parameter updates 参数更新检查
if (_parameter_update_sub.updated()) {
// clear update
parameter_update_s pupdate;
_parameter_update_sub.copy(&pupdate);
// update parameters from storage 一旦参数有变化,调用 updateParams() 更新内部配置(例如波特率、通道等)
updateParams();
}
// poll等待输入,等待10ms,看是否有数据可读
int ret = poll(&fds[0], 1, timeout);
// ret > 0 表示有输入事件,ret == -1 表示错误
if (ret > 0) {
if (_mavlink->get_protocol() == Protocol::SERIAL) {
/* non-blocking read. read may return negative values 串口读取数据*/
nread = ::read(fds[0].fd, buf, sizeof(buf));
// 若USB串口断开,延迟100ms再试
if (nread == -1 && errno == ENOTCONN) { // Not connected (can happen for USB)
usleep(100000);
}
}
#if defined(MAVLINK_UDP)
else if (_mavlink->get_protocol() == Protocol::UDP) {
if (fds[0].revents & POLLIN) {
// UDP 接收数据
nread = recvfrom(_mavlink->get_socket_fd(), buf, sizeof(buf), 0, (struct sockaddr *)&srcaddr, &addrlen);
}
struct sockaddr_in &srcaddr_last = _mavlink->get_client_source_address();
int localhost = (127 << 24) + 1;
if (!_mavlink->get_client_source_initialized()) {
// set the address either if localhost or if 3 seconds have passed
// this ensures that a GCS running on localhost can get a hold of
// the system within the first N seconds
hrt_abstime stime = _mavlink->get_start_time();
if ((stime != 0 && (hrt_elapsed_time(&stime) > 3_s))
|| (srcaddr_last.sin_addr.s_addr == htonl(localhost))) {
srcaddr_last.sin_addr.s_addr = srcaddr.sin_addr.s_addr;
srcaddr_last.sin_port = srcaddr.sin_port;
_mavlink->set_client_source_initialized();
PX4_INFO("partner IP: %s", inet_ntoa(srcaddr.sin_addr));
}
}
}
// only start accepting messages on UDP once we're sure who we talk to
if (_mavlink->get_protocol() != Protocol::UDP || _mavlink->get_client_source_initialized()) {
#endif // MAVLINK_UDP
/* if read failed, this loop won't execute 解析 MAVLink 数据流*/
for (ssize_t i = 0; i < nread; i++) {
// mavlink_parse_char() 完成协议解析,一旦解析出完整包,返回 true
if (mavlink_parse_char(_mavlink->get_channel(), buf[i], &msg, &_status)) {
/* check if we received version 2 and request a switch. */
if (!(_mavlink->get_status()->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1)) {
/* this will only switch to proto version 2 if allowed in settings */
_mavlink->set_proto_version(2);
}
// 处理解析出的消息,接收模块的核心就是解析数据
/* handle generic messages and commands 通用处理(心跳、状态、命令等)*/
handle_message(&msg);
/* handle packet with mission manager 航线任务相关数据解析*/
_mission_manager.handle_message(&msg);
/* handle packet with parameter component */
if (_mavlink->boot_complete()) {
// make sure mavlink app has booted before we start processing parameter sync
// 参数相关
_parameters_manager.handle_message(&msg);
} else {
if (hrt_elapsed_time(&_mavlink->get_first_start_time()) > 20_s) {
PX4_ERR("system boot did not complete in 20 seconds");
_mavlink->set_boot_complete();
}
}
if (_mavlink->ftp_enabled()) {
/* handle packet with ftp component 文件传输*/
_mavlink_ftp.handle_message(&msg);
}
/* handle packet with log component 日志请求(ULog下载*/
_mavlink_log_handler.handle_message(&msg);
/* handle packet with timesync component 时间同步相关*/
_mavlink_timesync.handle_message(&msg);
/* handle packet with parent object 主模块处理(转发、状态更新)*/
_mavlink->handle_message(&msg);
update_rx_stats(msg);
if (_message_statistics_enabled) {
update_message_statistics(msg);
}
}
}
/* count received bytes (nread will be -1 on read error) */
if (nread > 0) {
_mavlink->count_rxbytes(nread);
telemetry_status_s &tstatus = _mavlink->telemetry_status();
tstatus.rx_message_count = _total_received_counter;
tstatus.rx_message_lost_count = _total_lost_counter;
tstatus.rx_message_lost_rate = static_cast<float>(_total_lost_counter) / static_cast<float>(_total_received_counter);
if (_mavlink_status_last_buffer_overrun != _status.buffer_overrun) {
tstatus.rx_buffer_overruns++;
_mavlink_status_last_buffer_overrun = _status.buffer_overrun;
}
if (_mavlink_status_last_parse_error != _status.parse_error) {
tstatus.rx_parse_errors++;
_mavlink_status_last_parse_error = _status.parse_error;
}
if (_mavlink_status_last_packet_rx_drop_count != _status.packet_rx_drop_count) {
tstatus.rx_packet_drop_count++;
_mavlink_status_last_packet_rx_drop_count = _status.packet_rx_drop_count;
}
}
#if defined(MAVLINK_UDP)
}
#endif // MAVLINK_UDP
} else if (ret == -1) {
usleep(10000);
}
const hrt_abstime t = hrt_absolute_time();
CheckHeartbeats(t);
// 超时处理与周期性任务
if (t - last_send_update > timeout * 1000) {
_mission_manager.check_active_mission();
_mission_manager.send();
_parameters_manager.send();
if (_mavlink->ftp_enabled()) {
_mavlink_ftp.send();
}
_mavlink_log_handler.send();
last_send_update = t;
}
if (_tune_publisher != nullptr) {
_tune_publisher->publish_next_tune(t);
}
}
}
本模块主要完成了对输入数据的解析。
2.2.4 mavlink_mission(航线处理逻辑)
2.2.4.1 模块功能与定位
该文件实现了 PX4 与地面站之间的任务(Mission)同步管理逻辑,主要用于:
| 功能 | 说明 |
|---|---|
| 任务同步 | 处理 GCS 上传的航点任务(如 Mission Upload) |
| 任务下载 | 处理 GCS 请求的任务下载(Mission Download) |
| 任务执行状态 | 上报当前任务状态、进度、错误等 |
| 任务清除 | 支持清除当前存储的任务 |
| 任务验证 | 检查任务项是否合法(坐标、命令、frame 等) |
| 任务 ACK | 向地面站发送响应(ACK、Error、Reached、Current 等) |
一句话总结:
它是 PX4 飞控系统中处理地面站 “任务上传、同步与执行” 的核心通信模块,属于 MAVLink 层的 Mission 服务端实现。
2.2.4.2 主要类结构与核心函数
类:MavlinkMissionManager
成员变量
| 变量名 | 功能 |
|---|---|
_mavlink | MAVLink 通信实例指针 |
_transfer_in_progress | 标志任务是否在传输中 |
_transfer_partner_sysid / _transfer_partner_compid | 当前通信的 GCS 系统与组件 ID |
_mission_pub | 发布到 uORB 的 mission 数据 |
_mission_count | 当前任务总数 |
_transfer_seq | 当前接收的 mission item 序号 |
_transfer_start | 任务传输起始时间,用于超时检测 |
_work_item_type | 当前任务类型(mission / fence / rally) |
_transfer_result | 任务结果状态(accepted、error 等) |
核心函数(按流程分组)
| 函数 | 功能说明 |
|---|---|
handle_message(const mavlink_message_t *msg) | 入口函数,分发不同类型的 MAVLink Mission 消息 |
handle_mission_count() | 处理 GCS 发送的任务数量(上传开始) |
handle_mission_item() | 接收单个任务项,存储并发送 ACK 请求下一个 |
handle_mission_request() | 处理 GCS 请求任务项(下载阶段) |
handle_mission_request_list() | 处理任务列表请求(GCS 想下载任务) |
handle_mission_ack() | 处理地面站发来的 ACK(例如上传完成确认) |
handle_mission_clear_all() | 清除所有任务项 |
send() | 主循环周期性调用,检查超时并发送下一个数据包 |
send_mission_ack() | 向 GCS 回复 ACK |
send_mission_item() | 发送单个任务项到 GCS |
check_active_mission() | 检查当前任务是否仍然有效(周期调用) |
update_geofence_state() | 任务边界检查 |
check_timeout() | 检查任务传输是否超时(例如超过 3 秒未响应) |
2.2.4.3 MAVLink Mission 通信流程与状态机
📤 上传流程(GCS → PX4)
[1] Mission Count (GCS)
↓
PX4 初始化接收缓存、清空旧任务
↓
[2] Mission Item #0 (GCS)
↓
PX4 保存 → 回复 Mission Request #1
↓
[3] Mission Item #1 (GCS)
↓
...
↓
[4] Mission Item #N (GCS)
↓
PX4 回复 Mission ACK (Accepted)
📥 下载流程(PX4 → GCS)
[1] Mission Request List (GCS)
↓
PX4 回复 Mission Count
↓
[2] Mission Request #0 (GCS)
↓
PX4 发送 Mission Item #0
↓
...
↓
[3] Mission Request #N (GCS)
↓
PX4 发送 Mission Item #N
↓
[4] Mission ACK (GCS)
↓
PX4 结束传输
3 Mavlink模块实战相关
3.1 自定义Mavlink协议

3.2 Mavlink协议对外发送

3.2 修改对外发送频率

:PX4 Mavlink模块代码详解&spm=1001.2101.3001.5002&articleId=153697553&d=1&t=3&u=dd9f3aa8a8e14fe6b9cc6650f0223866)
47

被折叠的 条评论
为什么被折叠?



