最近地面站遇到一个多机连接的Bug,当载具连接超出15架后,地面站就无法创建连接,且无法断开连接。通过QGroundControl DeBUG版测试后发现,提示出错是:Ran out of mavlink channels。
于是开始分析代码!首先是连接函数触发的前端代码:LinkSettings.qml
QGCButton {
text: qsTr("Connect")
enabled: _currentSelection && !_currentSelection.link
onClicked: {
QGroundControl.linkManager.createConnectedLink(_currentSelection)
}
触发了linkManager类中的createConnectedLink函数

这里有一个函数重载,调用了另外一个 createConnectedLink函数

此次调用了_addLink()函数

此次可以看到提示错误的代码了。说明我们已经接近问题了,首先是mavlinkChannel=0,说明通道不够用了以后导致Bug出现的,所以我们打开_reserveMavlinkChannel()看一下,在读代码之前我们思考一下,_reserveMavlinkChannel()函数肯定是用于分配MavLink通道的,当通道值为0则表示没有通道可以用了。
int LinkManager::_reserveMavlinkChannel(void)
{
// Find a mavlink channel to use for this link, Channel 0 is reserved for internal use.
for (uint8_t mavlinkChannel = 1; mavlinkChannel < MAVLINK_COMM_NUM_BUFFERS; mavlinkChannel++) {
if (!(_mavlinkChannelsUsedBitMask & 1 << mavlinkChannel)) {
mavlink_reset_channel_status(mavlinkChannel);
// Start the channel on Mav 1 protocol
mavlink_status_t* mavlinkStatus = mavlink_get_channel_status(mavlinkChannel);
mavlinkStatus->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
_mavlinkChannelsUsedBitMask |= 1 << mavlinkChannel;
return mavlinkChannel;
}
}
return 0; // All channels reserved
}
这段代码需要一点点耐心去理解一下,首先直观感受,当mavlinkChannel大于MAVLINK_COMM_NUM_BUFFERS时,通道就会为0,所以我们查一查这个宏定义是多少。

在mavLink库下mavlink_types.h文件下宏定义 MAVLINK_COMM_NUM_BUFFERS为16,mavlinkChannel通道初始值为1,所以导致只能最多连接15架次载具,根据注释我们可以知道我们可以调大这个MAVLINK_COMM_NUM_BUFFERS值。但究竟可以调多大,我们需要读一读_reserveMavlinkChannel()函数。

首先将数值1左移mavlinkChannel位,然后与_mavlinkChannelsUsedBitMask值相与,即可将_mavlinkChannelsUsedBitMask二进制表示时第mavlinkChannel位的二进制选出来,当值位0,即通道为使用,可进入分配通道的代码,当通道分配完成,需要将_mavlinkChannelsUsedBitMask第mavlinkChannel位赋1,即下面这条代码:

所以可以理解一下,当使用3个通道时, _mavlinkChannelsUsedBitMask二进制值为111,当使用4个通道时, _mavlinkChannelsUsedBitMask二进制值为1111。
所以我们再看看 _mavlinkChannelsUsedBitMask的声明:

_mavlinkChannelsUsedBitMask是一个32位的int值,最多可以表示32个1,所以回到设置MAVLINK_COMM_NUM_BUFFERS值,目前我们能设置的最多值应该是32。

博客详细分析了一个地面站软件遇到的连接问题,当连接超过15架载具时,无法创建新的连接。问题源于 MAVLink 通道资源耗尽,通道最大值为16。通过对代码的深入解析,发现通道分配机制限制了连接数量。解决方案可能涉及增大 MAVLINK_COMM_NUM_BUFFERS 的宏定义值,但考虑到 _mavlinkChannelsUsedBitMask 是32位,最大可表示32个通道,因此理论上最大可连接32架载具。
1万+

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



