前言
QGC连接无人机飞控时支持多种连接方式,并且可以自动连接,不由让人好奇它的实现原理,本文主要分析QGC的连接原理和连接过程,数据的收发过程。
提示:以下是本篇文章正文内容
一、连接原理
QGC使用QT框架,采用c++语言,能够通过多种方式连接无人机飞控(串口、UDP、TCP、蓝牙等)。连接的实现类有一个基类Linkinterface,继承于QThread类,基类提供统一接口,实现多态。子类有:SerialLink、UDPLink、TCPLink、BluetoothLink、MockLink,分别对应串口、UDP、TCP、蓝牙连接的具体实现。除SerialLink类外,其他的子类都重写了run函数,说明这些连接都运行在子线程里,通过信号槽的方式把接收到的数据送到主线程。
LinkInterface主要用于实现连接的通用接口,而连接的管理放在了LinkManager类。LinkManager继承于QGCTool类,QGCTool类是QGC工具类的基类,继承于QGCTool类的子类对象都是单例模式。连接管理包括了创建连接、建立连接、断开连接、数据收发等。
二、连接过程与数据收发
1.连接过程(以串口为例)
QGC的自动连接实际使用的是一个定时器,定时去触发连接检测函数,检测是否有需要连接的设备。定时器变量名_portListTimer,定时时间到后触发槽函数_updateAutoConnectLinks()
connect(&_portListTimer, &QTimer::timeout, this, &LinkManager::_updateAutoConnectLinks);//linkManager.c 90
整理了一下整个连接过程,贴个图
LinkInterface* LinkManager::createConnectedLink(SharedLinkConfigurationPointer& config, bool isPX4Flow)
{
if (!config) {
qWarning() << "LinkManager::createConnectedLink called with nullptr config";
return nullptr;
}
LinkInterface* pLink = nullptr;
switch(config->type()) {
#ifndef NO_SERIAL_LINK
case LinkConfiguration::TypeSerial:
{
auto* serialConfig = qobject_cast<SerialConfiguration*>(config.data());
if (serialConfig) {
pLink = new SerialLink(config, isPX4Flow);
if (serialConfig->usbDirect()) {
_activeLinkCheckList.append(qobject_cast<SerialLink*>(pLink));
if (!_activeLinkCheckTimer.isActive()) {
_activeLinkCheckTimer.start();
}
}
}
}
break;
#else
Q_UNUSED(isPX4Flow)
#endif
case LinkConfiguration::TypeUdp:
pLink = new UDPLink(config);
break;
case LinkConfiguration::TypeTcp:
pLink = new TCPLink(config);
break;
#ifdef QGC_ENABLE_BLUETOOTH
case LinkConfiguration::TypeBluetooth:
pLink = new BluetoothLink(config);
break;
#endif
case LinkConfiguration::TypeLogReplay:
pLink = new LogReplayLink(config);
break;
#ifdef QT_DEBUG
case LinkConfiguration::TypeMock:
pLink = new MockLink(config);
break;
#endif
case LinkConfiguration::TypeLast:
break;
}
if (pLink) {
_addLink(pLink);
connectLink(pLink);
}
return pLink;
}
然后分别执行_addLink()、connectLink()函数。connectLink()中主要操作是link->_connect(),根据基类指针指向的不同子类,调用不同的连接函数。_addLink()主要把连接对象指针添加到连接列表,连接数据收发的信号槽,数据接收槽函数位于MavlinkProtocol类(图片中写错了,笔误),该类同样继承于QGCTool类,单例模式,只有一个对象。
void LinkManager::_addLink(LinkInterface* link)
{
if (thread() != QThread::currentThread()) {
qWarning() << "_addLink called from incorrect thread";
return;
}
if (!link) {
return;
}
if (!containsLink(link)) {
int mavlinkChannel = _reserveMavlinkChannel();
if (mavlinkChannel != 0) {
link->_setMavlinkChannel(mavlinkChannel);
} else {
qWarning() << "Ran out of mavlink channels";
return;
}
_sharedLinks.append(SharedLinkInterfacePointer(link));
emit newLink(link);
}
connect(link, &LinkInterface::communicationError, _app, &QGCApplication::criticalMessageBoxOnMainThread);
connect(link, &LinkInterface::bytesReceived, _mavlinkProtocol, &MAVLinkProtocol::receiveBytes);// receive data.
connect(link, &LinkInterface::bytesSent, _mavlinkProtocol, &MAVLinkProtocol::logSentBytes);// send data.
_mavlinkProtocol->resetMetadataForLink(link);
_mavlinkProtocol->setVersion(_mavlinkProtocol->getCurrentVersion());
connect(link, &LinkInterface::connected, this, &LinkManager::_linkConnected);
connect(link, &LinkInterface::disconnected, this, &LinkManager::_linkDisconnected);
// This connection is queued since it will cloe the link. So we want the link emitter to return otherwise we would
// close the link our from under itself.
connect(link, &LinkInterface::connectionRemoved, this, &LinkManager::_linkConnectionRemoved, Qt::QueuedConnection);
}
mavlinkprotocol收到数据后根据mavlink协议进行一系列操作,最后消息会通过信号槽的方式传到vehicle类,根据不同的mavlink消息执行具体的操作(_mavlinkMessageReceived()函数)。
写到这不得不说一下QGC的多机连接,多机管理类MultiVehicleManager,在mavlinkprotocol收到无人机广播的heartbeat消息后,会发送vehicleHeartbeatInfo信号,MultiVehicleManager类的槽函数_vehicleHeartbeatInfo()接收这个信号,根据消息包中的无人机类型创建不同的vehicle对象,实现多机的一个连接。
connect(_mavlinkProtocol, &MAVLinkProtocol::vehicleHeartbeatInfo, this, &MultiVehicleManager::_vehicleHeartbeatInfo);
2.数据发送
上面的过程图只写了数据的接收,数据发送也整理了一下,贴个图,详细过程就不叙述了,用到的话可以根据过程图追一下代码。
总结
QGC的连接结构设计的还是挺棒的,过程简洁,结构合理。除了串口没搞明白是否开线程外,其他方式的连接都是每个连接都是一个线程,收到数据后再通过信号槽的方式传递到主线程。另外连接还有通道的概念,每个连接对应一个mavlink通道,通道数目会显示限制连接数量,通过修改MAVLINK_COMM_NUM_BUFFERS(位置:mavlink_types.h)宏可以修改通道数目。还需要修改一个变量_mavlinkChannelsUsedBitMask,该变量用于计算存储每个通道。
宏:MAVLINK_COMM_NUM_BUFFERS
位置:mav_link_types.c
通道控制函数:int LinkManager::_reserveMavlinkChannel(void)
void LinkManager::_freeMavlinkChannel(int channel)
位置:LinkManager.c