QGC MAVLink 通信核心开发技术文档


前言

QGroundControl(QGC)与无人机之间的全部交互都建立在 MAVLink 协议之上。通信核心位于 src/comm/src/Vehicle/,以 LinkManager → LinkInterface → MAVLinkProtocol → MultiVehicleManager → Vehicle 为主线,实现从物理字节流到业务指令的完整链路。

本文按以下四部分展开:

  1. MAVLink 报文解析与封装
  2. 串口、UDP、TCP 链路驱动开发
  3. 心跳、状态上报、指令下发逻辑
  4. 多无人机设备管理

一、MAVLink 报文解析与封装

1.1 MAVLink 库集成与配置

QGC 使用 MAVLink C 参考实现,头文件位于 libs/mavlink/include/mavlink/v2.0/,通过 QGCMAVLink.h 统一引入:

#define MAVLINK_USE_MESSAGE_INFO
#define MAVLINK_EXTERNAL_RX_STATUS  // Single m_mavlink_status instance is in QGCApplication.cc
#include <stddef.h>
// ...
#include <mavlink_types.h>
extern mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
#include <mavlink.h>

关键编译选项说明:

宏/配置 作用
MAVLINK_USE_MESSAGE_INFO 启用消息元信息(名称、字段描述)
MAVLINK_EXTERNAL_RX_STATUS 解析状态数组由应用全局管理,而非库内静态变量
MAVLINK_CONF(默认 ardupilotmega 方言选择,在 QGCExternalLibs.pri 中配置

全局解析状态数组在 QGCApplication.cc 中定义:

// Mavlink status structures for entire app
mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];

每条物理链路占用一个独立的 mavlinkChannel(1 ~ N),保证多链路并行解析时状态互不干扰。

1.2 MAVLink 通道分配机制

LinkManager 在添加链路时从通道池分配 ID:

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
}

设计要点:

  • 通道 0 保留给内部用途
  • 新链路默认以 MAVLink v1 出站启动,收到 v2 帧后自动升级
  • 链路断开时 _freeMavlinkChannel() 回收位掩码

1.3 接收方向:逐字节解析

MAVLinkProtocol::receiveBytes() 是解析入口,由 LinkInterface::bytesReceived 信号触发:

void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
{
    // Since receiveBytes signals cross threads we can end up with signals in the queue
    // that come through after the link is disconnected. For these we just drop the data
    // since the link is closed.
    if (!_linkMgr->containsLink(link)) {
        return;
    }

    uint8_t mavlinkChannel = link->mavlinkChannel();

    // ...
    for (int position = 0; position < b.size(); position++) {
        if (mavlink_parse_char(mavlinkChannel, static_cast<uint8_t>(b[position]), &_message, &_status)) {
            // Got a valid message

解析流程:

Link 线程收到原始字节

emit bytesReceived

MAVLinkProtocol::receiveBytes

mavlink_parse_char 逐字节

完整帧?

序列号丢包统计

遥测日志写入

HEARTBEAT?

emit vehicleHeartbeatInfo

继续

emit messageReceived

Vehicle / PlanManager 等订阅者处理

MAVLink v1/v2 自动协商:收到首个 v2 帧且出站仍为 v1 时,自动切换出站版本:

            if (!link->decodedFirstMavlinkPacket()) {
                link->setDecodedFirstMavlinkPacket(true);
                mavlink_status_t* mavlinkStatus = mavlink_get_channel_status(mavlinkChannel);
                if (!(mavlinkStatus->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) && (mavlinkStatus->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1)) {
                    qDebug() << "Switching outbound to mavlink 2.0 due to incoming mavlink 2.0 packet:" << mavlinkStatus << mavlinkChannel << mavlinkStatus->flags;
                    mavlinkStatus->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
                    // Set all links to v2
                    setVersion(200);
                }
            }

序列号丢包检测:按 (sysid, compid) 维护 lastIndex[][],比较 message.seq 与期望值,累计 totalLossCounter 并计算滑动平均丢包率,每 32 包通过 mavlinkMessageStatus 信号上报 UI。

非 MAVLink 数据保护:连续 1000 字节无法解析出有效帧时,尝试 requestReset() 一次;仍失败则自动断开链路,防止误连非 MAVLink 设备(如调制解调器)。

1.4 发送方向:报文封装

发送路径在 Vehicle::_sendMessageOnLink() 中完成:

    // Give the plugin a chance to adjust
    _firmwarePlugin->adjustOutgoingMavlinkMessage(this, link, &message);

    // Write message into buffer, prepending start sign
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    int len = mavlink_msg_to_send_buffer(buffer, &message);

    link->writeBytesSafe((const char*)buffer, len);
    _messagesSent++;
    emit messagesSentChanged();

封装步骤:

  1. 业务层构造 mavlink_message_t(通常先用 mavlink_msg_xxx_encode_chan() 编码)
  2. FirmwarePlugin::adjustOutgoingMavlinkMessage() 允许固件插件修改出站消息
  3. mavlink_msg_to_send_buffer() 序列化为字节流(含起始标志、CRC)
  4. LinkInterface::writeBytesSafe() 线程安全写入链路

带通道的编码函数必须使用链路的 mavlinkChannel,以保证 CRC Extra 和 v1/v2 标志正确:

mavlink_msg_command_long_encode_chan(
    _mavlink->getSystemId(),           // GCS system id (默认 255)
    _mavlink->getComponentId(),        // MAV_COMP_ID_MISSIONPLANNER
    priorityLink()->mavlinkChannel(),  // 链路通道号
    &msg,
    &cmd);

GCS 身份标识:

  • System ID:默认 255,可在设置中修改,持久化于 QSettingsQGC_MAVLINK_PROTOCOL
  • Component ID:固定为 MAV_COMP_ID_MISSIONPLANNER

1.5 消息解码模式

Vehicle 收到消息后按 msgid 分发,典型解码模式:

// 1. 解码 payload
mavlink_heartbeat_t heartbeat;
mavlink_msg_heartbeat_decode(&message, &heartbeat);

// 2. 更新内部状态
_base_mode   = heartbeat.base_mode;
_custom_mode = heartbeat.custom_mode;

// 3. 通过 Q_PROPERTY / 信号通知 UI
emit flightModeChanged(flightMode());

Vehicle 的 _mavlinkMessageReceived() 是一个大型 switch(message.msgid) 分发器,处理 40+ 种消息类型,包括 HEARTBEATSYS_STATUSGLOBAL_POSITION_INTBATTERY_STATUSCOMMAND_ACK 等。

消息过滤规则:

    if (message.sysid != _id && message.sysid != 0) {
        // We allow RADIO_STATUS messages which come from a link the vehicle is using to pass through and be handled
        if (!(message.msgid == MAVLINK_MSG_ID_RADIO_STATUS && _containsLink(link))) {
            return;
        }
    }

每个 Vehicle 只处理自己的 sysid,例外是同一链路上的 RADIO_STATUS(来自数传电台)。

插件拦截链(接收方向):

    // Give the plugin a change to adjust the message contents
    if (!_firmwarePlugin->adjustIncomingMavlinkMessage(this, &message)) {
        return;
    }

    // Give the Core Plugin access to all mavlink traffic
    if (!_toolbox->corePlugin()->mavlinkMessage(this, link, message)) {
        return;
    }

1.6 遥测日志

MAVLinkProtocol 内置遥测录制:收到 HEARTBEAT 时启动日志,每条消息前附加 8 字节 UTC 微秒时间戳,通过 mavlink_msg_to_send_buffer() 写入临时文件。发送方向由 logSentBytes() 同样记录。解武装或所有 Vehicle 移除时停止日志并提示保存。


二、串口、UDP、TCP 链路驱动开发

2.1 链路抽象层设计

所有物理链路继承 LinkInterface,它同时是 QThreadQObject

class LinkInterface : public QThread
{
    Q_OBJECT

核心约定:

  • LinkManager 可创建/连接/断开链路(友元 + 私有 _connect/_disconnect
  • 对外暴露 writeBytesSafe() 线程安全写接口
  • 通过 bytesReceived / bytesSent 信号与协议层通信
  • 每条链路持有独立 mavlinkChannel

配置与实现分离LinkConfiguration 存持久化参数(端口、波特率、IP 等),LinkInterface 子类负责 IO。支持的链路类型:

    enum LinkType {
#ifndef NO_SERIAL_LINK
        TypeSerial,     ///< Serial Link
#endif
        TypeUdp,        ///< UDP Link
        TypeTcp,        ///< TCP Link
#ifdef QGC_ENABLE_BLUETOOTH
        TypeBluetooth,  ///< Bluetooth Link
#endif
#ifdef QT_DEBUG
        TypeMock,       ///< Mock Link for Unitesting
#endif
        TypeLogReplay,
        TypeLast
    };

2.2 LinkManager 链路生命周期

mermaid
sequenceDiagram
    participant UI as QML/Settings
    participant LM as LinkManager
    participant Link as LinkInterface
    participant MP as MAVLinkProtocol

    UI->>LM: createConnectedLink(config)
    LM->>Link: new SerialLink/UDPLink/TCPLink
    LM->>LM: _reserveMavlinkChannel()
    LM->>Link: _setMavlinkChannel(ch)
    LM->>Link: connectLink() → _connect()
    Link->>Link: start() / exec() 事件循环
    Link-->>LM: emit connected
    LM->>Link: connect bytesReceived → MP::receiveBytes

_addLink() 中的信号绑定是通信核心的枢纽:

    connect(link, &LinkInterface::communicationError,   _app,               &QGCApplication::criticalMessageBoxOnMainThread);
    connect(link, &LinkInterface::bytesReceived,        _mavlinkProtocol,   &MAVLinkProtocol::receiveBytes);
    connect(link, &LinkInterface::bytesSent,            _mavlinkProtocol,   &MAVLinkProtocol::logSentBytes);
    // ...
    connect(link, &LinkInterface::connectionRemoved,    this, &LinkManager::_linkConnectionRemoved, Qt::QueuedConnection);

2.3 串口链路(SerialLink)

配置类 SerialConfiguration 管理:

  • 端口名、波特率(57600 / 115200 / 921600 等)
  • 数据位、停止位、校验位、流控
  • usbDirect 标志(直连飞控 USB,用于优先级链路选择)

连接流程SerialLink::_connect()):

  1. 检测是否处于 Bootloader 模式(_isBootloader()),若是则等待超时
  2. 创建 QSerialPort,设置参数并 open()
  3. 连接 readyRead → 读取字节 → emit bytesReceived
  4. Bootloader 场景最多重试 12 次,每次间隔 500ms

写入_writeBytes):

void SerialLink::_writeBytes(const QByteArray data)
{
    if(_port && _port->isOpen()) {
        emit bytesSent(this, data);
        _logOutputDataRate(data.size(), QDateTime::currentMSecsSinceEpoch());
        _port->write(data);
    } else {
        qWarning() << "Serial port not writeable";
        _emitLinkError(tr("Could not send data - link %1 is disconnected!").arg(getName()));
    }
}

自动连接LinkManager 定时扫描 QGCSerialPortInfo(基于 USB VID/PID 识别 PX4/APM 板卡),匹配 _autoconnectUpdateTimerMSecs 周期自动创建链路。

2.4 UDP 链路(UDPLink)

UDP 是 SITL 仿真和多机场景最常用的链路,默认端口 14550

配置类 UDPConfiguration

  • localPort:本地绑定端口
  • targetHosts:预设目标地址列表(如 192.168.1.1:14550
  • 支持 Zeroconf/mDNS 服务发现(可选编译)

线程模型

    moveToThread(this);
void UDPLink::run()
{
    if (_hardwareConnect()) {
        exec();
    }
    // cleanup...
}

_connect() 启动线程 → run()_hardwareConnect() 绑定 socket → exec() 进入事件循环。

硬件连接_hardwareConnect):

  • 绑定 QHostAddress::AnyIPv4 + localPort
  • 加入组播组 224.0.0.1
  • 设置 256KB/512KB 收发缓冲区
  • 连接 readyReadreadBytes()

动态目标学习:收到 datagram 时,将 (sender, port) 加入 _sessionTargets,回复时同时发往预设目标和会话目标。本地地址检测(_isIpLocal)避免 SITL 同机运行时双链路问题。

读取与批量发送

        if (databuffer.size() > 10 * 1024) {
            emit bytesReceived(this, databuffer);
            databuffer.clear();
        }
    // ...
    if (databuffer.size()) {
        emit bytesReceived(this, databuffer);
    }

超过 10KB 时分批上报,降低信号频率。

2.5 TCP 链路(TCPLink)

TCP 主要用于 SITL(默认端口 5760)和某些数传设备。

配置类 TCPConfigurationhost + port

连接流程

bool TCPLink::_connect(void)
{
    if (isRunning()) { quit(); wait(); }
    start(HighPriority);
    return true;
}
void TCPLink::run()
{
    _hardwareConnect();
    exec();
}

_hardwareConnect() 创建 QTcpSocketconnectToHost()waitForConnected(1000),超时则报错断开。

TCP 为点对点连接,无 UDP 的动态目标学习,读写逻辑更简单:readyReadreadBytes()emit bytesReceived

2.6 线程安全写机制

所有链路共享同一写安全模式:

    void writeBytesSafe(const char *bytes, int length)
    {
        emit _invokeWriteBytes(QByteArray(bytes, length));
    }
    QObject::connect(this, &LinkInterface::_invokeWriteBytes, this, &LinkInterface::_writeBytes);

任意线程调用 writeBytesSafe() 均安全:Qt 将 _invokeWriteBytes 投递到 Link 所在线程执行实际 IO。

2.7 开发新链路类型的步骤

  1. 继承 LinkConfiguration,实现 type()loadSettings()saveSettings()settingsURL()
  2. 继承 LinkInterface,实现 _connect()_disconnect()_writeBytes()getName()isConnected()
  3. readBytes 等价逻辑中 emit bytesReceived(this, data)
  4. LinkManager::createConnectedLink()switch(config->type()) 中注册
  5. LinkManager::linkTypeStrings() 中添加显示名称
  6. 创建对应 QML 设置页(如 SerialSettings.qml

三、心跳、状态上报、指令下发逻辑

3.1 GCS 心跳(地面站 → 飞行器)

MultiVehicleManager 维护 GCS 心跳定时器,默认启用:

    _gcsHeartbeatTimer.setInterval(_gcsHeartbeatRateMSecs);
    _gcsHeartbeatTimer.setSingleShot(false);
    connect(&_gcsHeartbeatTimer, &QTimer::timeout, this, &MultiVehicleManager::_sendGCSHeartbeat);
    if (_gcsHeartbeatEnabled) {
        _gcsHeartbeatTimer.start();
    }

_sendGCSHeartbeat() 向每条已连接的非高延迟链路广播:

void MultiVehicleManager::_sendGCSHeartbeat(void)
{
    LinkManager* linkMgr = _toolbox->linkManager();
    for (int i=0; i<linkMgr->links().count(); i++) {
        LinkInterface* link = linkMgr->links()[i];
        if (link->isConnected() && !link->highLatency()) {
            mavlink_message_t message;
            mavlink_msg_heartbeat_pack_chan(_mavlinkProtocol->getSystemId(),
                                            _mavlinkProtocol->getComponentId(),
                                            link->mavlinkChannel(),
                                            &message,
                                            MAV_TYPE_GCS,
                                            MAV_AUTOPILOT_INVALID,
                                            MAV_MODE_MANUAL_ARMED,
                                            0,
                                            MAV_STATE_ACTIVE);
            // ... writeBytesSafe
        }
    }
}

GCS 心跳的作用:告知飞控地面站已连接(PX4 据此决定是否接受任务上传等命令)。新 Vehicle 创建后立即调用一次 _sendGCSHeartbeat()

3.2 飞行器心跳处理(飞行器 → 地面站)

第一层:MAVLinkProtocol

收到 HEARTBEATHIGH_LATENCY2 时:

            if (_message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
                _startLogging();
                mavlink_heartbeat_t heartbeat;
                mavlink_msg_heartbeat_decode(&_message, &heartbeat);
                emit vehicleHeartbeatInfo(link, _message.sysid, _message.compid, heartbeat.autopilot, heartbeat.type);
            }

            if (_message.msgid == MAVLINK_MSG_ID_HIGH_LATENCY2) {
                _startLogging();
                // ...
                emit vehicleHeartbeatInfo(link, _message.sysid, _message.compid, highLatency2.autopilot, highLatency2.type);
            }

第二层:MultiVehicleManager — 决定是否创建 Vehicle(详见第四节)。

第三层:Vehicle::_handleHeartbeat() — 更新飞行状态:

void Vehicle::_handleHeartbeat(mavlink_message_t& message)
{
    if (message.compid != _defaultComponentId) {
        return;
    }
    mavlink_heartbeat_t heartbeat;
    mavlink_msg_heartbeat_decode(&message, &heartbeat);

    bool newArmed = heartbeat.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY;
    // ArduPilot ARMING_REQUIRE=0 特殊处理 ...
    _updateArmed(newArmed);

    if (heartbeat.base_mode != _base_mode || heartbeat.custom_mode != _custom_mode) {
        // ...
        _base_mode   = heartbeat.base_mode;
        _custom_mode = heartbeat.custom_mode;
        emit flightModeChanged(flightMode());
    }
}

从 Heartbeat 提取的核心状态:

字段 QGC 用途
base_mode 安全位 armed/disarmed 状态
custom_mode 通过 FirmwarePlugin 映射为飞行模式字符串
autopilot / type 创建 Vehicle 时选择插件

3.3 通信丢失检测

QGC 使用 MavlinkMessagesTimer 而非直接依赖 Heartbeat 间隔来判断链路活性:

    static const int    _messageReceivedTimeoutMSecs = 3500;  // Signal connection lost after 3.5 seconds of no messages

机制:

  1. LinkManager::_mavlinkMessageReceived() 收到任意 MAVLink 消息时调用 link->startMavlinkMessagesTimer(message.sysid)
  2. 定时器每 3.5 秒检查一次,超时则 emit activeChanged(false, vehicle_id)
  3. Vehicle::_linkActiveChanged() 响应,设置 _connectionLost = true
        } else if (!active && !_connectionLost) {
            _updatePriorityLink(false, false);
            if (link == _priorityLink) {
                _connectionLost = true;
                communicationLost = true;
                _heardFrom = false;
                emit connectionLostChanged(true);

注意:判定依据是 任意 MAVLink 消息(不仅是 Heartbeat),3.5 秒无消息即报通信丢失。高延迟链路(highLatency=true)跳过超时检测,始终视为 active。

QML 绑定:

property bool communicationLost: activeVehicle ? activeVehicle.connectionLost : false

3.4 状态上报处理

Vehicle 通过 _mavlinkMessageReceived() 的 switch 分发处理各类遥测消息,更新 FactGroup 或发出信号。

SYS_STATUS — 系统健康

void Vehicle::_handleSysStatus(mavlink_message_t& message)
{
    mavlink_sys_status_t sysStatus;
    mavlink_msg_sys_status_decode(&message, &sysStatus);
    // 传感器 present/enabled/health 位图
    emit sensorsPresentBitsChanged(...);
    emit sensorsEnabledBitsChanged(...);
    emit sensorsHealthBitsChanged(...);
    // ArduPilot ARMING_REQUIRE=0 时从 MOTOR_OUTPUTS 判断 armed
}

BATTERY_STATUS — 电池:更新 _battery1FactGroup / _battery2FactGroup

GLOBAL_POSITION_INT / ATTITUDE 等:通过对应 FactGroup(GPS、姿态)更新,FactGroup 内置 _updateRateMSecs 节流 UI 刷新。

STATUSTEXT — 文本消息:转发给 UASMessageHandler,在工具栏 MessageIndicator 显示。

RADIO_STATUS — 数传信号_handleRadioStatus() 解析 RSSI、噪声,支持 3DR SiK 特殊 dBm 转换。

状态到 UI 的路径:

MAVLink 消息 → Vehicle 处理函数 → Fact._containerSetRawValue()
    → emit valueChanged → QML 属性绑定自动刷新

3.5 指令下发:sendMavCommand 机制

QGC 的命令下发采用 队列 + 超时重试 + ACK 确认 模式。

入队

void Vehicle::sendMavCommand(int component, MAV_CMD command, bool showError, float param1, ...)
{
    MavCommandQueueEntry_t entry;
    entry.commandInt = false;
    entry.component = component;
    entry.command = command;
    // ... 填充参数
    _mavCommandQueue.append(entry);

    if (_mavCommandQueue.count() == 1) {
        _mavCommandRetryCount = 0;
        _sendMavCommandAgain();
    }
}

发送与重试_sendMavCommandAgain):

  1. 超过最大重试次数 → 报错,emit mavCommandResult(FAILED),处理下一条
  2. 构造 COMMAND_LONGCOMMAND_INT 消息
  3. 通过 priorityLink() 发送
  4. 启动 _mavCommandAckTimer 等待 COMMAND_ACK
        mavlink_msg_command_long_encode_chan(_mavlink->getSystemId(),
                                             _mavlink->getComponentId(),
                                             priorityLink()->mavlinkChannel(),
                                             &msg,
                                             &cmd);
    sendMessageOnLink(priorityLink(), msg);

ACK 处理

    if (_mavCommandQueue.count() && ack.command == _mavCommandQueue[0].command) {
        _mavCommandAckTimer.stop();
        showError = _mavCommandQueue[0].showError;
        _mavCommandQueue.removeFirst();
        _sendNextQueuedMavCommand();
    }

命令队列保证 同一时刻只有一个命令等待 ACK,避免飞控命令通道冲突。常用命令包括:

命令 用途
MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES 获取飞控能力位
MAV_CMD_REQUEST_PROTOCOL_VERSION 协商 MAVLink v2
MAV_CMD_COMPONENT_ARM_DISARM 解锁/上锁
MAV_CMD_NAV_TAKEOFF / MAV_CMD_NAV_LAND 起飞/降落
MAV_CMD_DO_SET_MODE 切换飞行模式
MAV_CMD_IMAGE_START_CAPTURE 相机控制

3.6 通用消息发送路径

非命令类消息(如任务项、参数设置)通过 sendMessageOnLink() 发送:

bool Vehicle::sendMessageOnLink(LinkInterface* link, mavlink_message_t message)
{
    if (!link || !_links.contains(link) || !link->isConnected()) {
        return false;
    }
    emit _sendMessageOnLinkOnThread(link, message);
    return true;
}

使用 Qt::QueuedConnection 确保跨线程安全:

    connect(this, &Vehicle::_sendMessageOnLinkOnThread, this, &Vehicle::_sendMessageOnLink, Qt::QueuedConnection);

四、多无人机设备管理

4.1 MultiVehicleManager 架构

MultiVehicleManager 是 QGC 多机管理的核心,职责包括:

  • 根据 Heartbeat 自动创建/销毁 Vehicle
  • 维护 Vehicle 列表(QmlObjectListModel* vehicles
  • 管理当前活动 Vehicle(activeVehicle
  • 广播 GCS Heartbeat
  • 协调 MAVLink 协议版本
    Q_PROPERTY(bool                 activeVehicleAvailable          READ activeVehicleAvailable                                         NOTIFY activeVehicleAvailableChanged)
    Q_PROPERTY(bool                 parameterReadyVehicleAvailable  READ parameterReadyVehicleAvailable                                 NOTIFY parameterReadyVehicleAvailableChanged)
    Q_PROPERTY(Vehicle*             activeVehicle                   READ activeVehicle                  WRITE setActiveVehicle          NOTIFY activeVehicleChanged)
    Q_PROPERTY(QmlObjectListModel*  vehicles                        READ vehicles                                                       CONSTANT)
    Q_PROPERTY(Vehicle*             offlineEditingVehicle           READ offlineEditingVehicle                                          CONSTANT)

4.2 Vehicle 自动发现与创建

_vehicleHeartbeatInfo() 是 Vehicle 创建的决策中心:

void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int componentId, int vehicleFirmwareType, int vehicleType)
{
    // 1. 只接受 AUTOPILOT1 组件(compid=1)的心跳
    if (componentId != MAV_COMP_ID_AUTOPILOT1) { /* 忽略 */ return; }

    // 2. 多机开关检查
    if (_vehicles.count() > 0 && !corePlugin->options()->multiVehicleEnabled()) { return; }

    // 3. 去重:已存在 / 忽略列表 / sysid=0
    if (_ignoreVehicleIds.contains(vehicleId) || getVehicleById(vehicleId) || vehicleId == 0) { return; }

    // 4. 排除非飞行器类型
    switch (vehicleType) {
    case MAV_TYPE_GCS:
    case MAV_TYPE_ONBOARD_CONTROLLER:
    case MAV_TYPE_GIMBAL:
    case MAV_TYPE_ADSB:
        return;
    default: break;
    }

    // 5. 创建 Vehicle
    Vehicle* vehicle = new Vehicle(link, vehicleId, componentId, ...);
    _vehicles.append(vehicle);
    emit vehicleAdded(vehicle);

    // 6. 首架自动设为 active
    if (_vehicles.count() > 1) {
        showMessage("Connected to Vehicle N");
    } else {
        setActiveVehicle(vehicle);
    }
}

创建过滤规则总结:

条件 行为
compid != 1 忽略(相机、云台等组件不建 Vehicle)
vehicleType == GCS/ADSB/... 忽略
sysid 已存在 忽略(同一飞行器不重复创建)
sysid == GCS system id 警告冲突但仍创建
多机未启用且已有 Vehicle 忽略新 Heartbeat

4.3 活动 Vehicle 切换

切换活动 Vehicle 需要 两阶段延迟,避免 QML 引用悬挂对象:

void MultiVehicleManager::setActiveVehicle(Vehicle* vehicle)
{
    if (vehicle != _activeVehicle) {
        if (_activeVehicle) {
            _activeVehicle->setActive(false);
            _activeVehicleAvailable = false;
            emit activeVehicleAvailableChanged(false);
        }
        _vehicleBeingSetActive = vehicle;
        QTimer::singleShot(20, this, &MultiVehicleManager::_setActiveVehiclePhase2);
    }
}

Phase 2 中设置新 _activeVehicleemit activeVehicleChanged。QML 的 activeVehicle 属性自动切换绑定目标。

工具栏 MultiVehicleSelector.qml 允许用户在多机间切换。

4.4 多链路支持

一架 Vehicle 可同时使用多条链路(如 USB + 数传电台)。Vehicle 维护 _links 列表和 _priorityLink

优先级选择策略(_updatePriorityLink):

  1. 活动的直连 USB 链路
  2. 任意活动的非高延迟链路
  3. 高延迟链路
  4. 任意链路

命令发送始终走 priorityLink(),遥测从所有链路接收。辅助链路丢失时提示但不触发通信丢失(除非 priority link 丢失)。

MultiVehicleManager::linkInUse() 检查链路是否被其他 Vehicle 占用,防止多机共享同一链路时的冲突。

4.5 Vehicle 销毁流程

当所有链路对某 Vehicle 不再 active 时,触发销毁:

MultiVehicleManager Vehicle MavlinkMessagesTimer MultiVehicleManager Vehicle MavlinkMessagesTimer QTimer 20ms 延迟 activeChanged(false) _connectionLost = true 所有链路 inactive emit allLinksInactive _deleteVehiclePhase1 从列表移除, emit vehicleRemoved _deleteVehiclePhase2 delete Vehicle

两阶段删除(20ms 延迟)确保 QML 有足够时间断开对 Vehicle 的引用。

4.6 离线编辑 Vehicle

offlineEditingVehicle 是一架未连接的虚拟 Vehicle,类型由 Settings 中的 offlineEditingFirmwareType / offlineEditingVehicleType 决定,用于 Plan View 离线任务编辑:

    _offlineEditingVehicle = new Vehicle(
        static_cast<MAV_AUTOPILOT>(...),
        static_cast<MAV_TYPE>(...),
        _firmwarePluginManager, this);

4.7 MAVLink 协议版本协调

多机场景下,GCS 出站协议版本取所有 Vehicle 中 _maxProtoVersion 的最大值:

void MultiVehicleManager::_requestProtocolVersion(unsigned version)
{
    unsigned maxversion = 0;
    for (int i=0; i<_vehicles.count(); i++) {
        Vehicle *v = qobject_cast<Vehicle*>(_vehicles[i]);
        if (v && v->maxProtoVersion() > maxversion) {
            maxversion = v->maxProtoVersion();
        }
    }
    if (_mavlinkProtocol->getCurrentVersion() != maxversion) {
        _mavlinkProtocol->setVersion(maxversion);
    }
}

保证所有链路统一使用 v1 或 v2,避免混用导致 CRC 错误。

4.8 多机 UI 集成

QML 全局属性:

property var activeVehicle: QGroundControl.multiVehicleManager.activeVehicle

工具栏指示器(GPS、电池、模式等)均绑定 activeVehicle 的属性。多机时 MultiVehicleSelector 显示 Vehicle ID 列表,切换后所有视图自动更新。

参数就绪状态:parameterReadyVehicleAvailable 确保 UI 在飞控参数加载完成前不启用依赖参数的功能。


五、端到端通信流程总结

以"用户点击 ARM 按钮"为例,完整数据流:

1. QML: activeVehicle.armed = true  (或调用 sendMavCommand)
2. Vehicle::sendMavCommand(MAV_COMP_ID_AUTOPILOT1, MAV_CMD_COMPONENT_ARM_DISARM, ...)
3. _mavCommandQueue 入队 → _sendMavCommandAgain()
4. mavlink_msg_command_long_encode_chan() 封装
5. sendMessageOnLink(priorityLink(), msg)
6. emit _sendMessageOnLinkOnThread → QueuedConnection
7. _sendMessageOnLink → mavlink_msg_to_send_buffer()
8. priorityLink()->writeBytesSafe(buffer, len)
9. emit _invokeWriteBytes → Link 线程 _writeBytes()
10. SerialLink: QSerialPort::write() / UDPLink: QUdpSocket::writeDatagram()
11. 飞控收到 COMMAND_LONG,回复 COMMAND_ACK
12. bytesReceived → MAVLinkProtocol::receiveBytes → messageReceived
13. Vehicle::_handleCommandAck → 停止重试定时器,处理下一命令
14. 飞控发送 HEARTBEAT (armed=true)
15. Vehicle::_handleHeartbeat → _updateArmed(true) → emit armedChanged
16. QML 绑定更新,按钮状态刷新

六、开发建议与注意事项

  1. 新增 MAVLink 消息处理:在 Vehicle::_mavlinkMessageReceived() 的 switch 中添加 case,必要时创建 FactGroup 字段。
  2. 自定义命令:优先使用 sendMavCommand(),不要直接构造消息,以享受队列和重试机制。
  3. 链路开发:务必在 Link 线程中执行 IO,通过 bytesReceived 信号上报,禁止在主线程阻塞读串口。
  4. 多机测试:使用 MockLink 或 UDP SITL,为每个实例分配不同 sysid
  5. MAVLink 方言:若仅支持 PX4,可在 user_config.pri 中设置 MAVLINK_CONF = common 减小编译体积。
  6. 线程安全:跨线程访问 Vehicle/Link 必须通过信号槽,参考 writeBytesSafeQueuedConnection 模式。
Logo

AtomGit 是由开放原子开源基金会联合 CSDN 等生态伙伴共同推出的新一代开源与人工智能协作平台。平台坚持“开放、中立、公益”的理念,把代码托管、模型共享、数据集托管、智能体开发体验和算力服务整合在一起,为开发者提供从开发、训练到部署的一站式体验。

更多推荐