欢迎使用 MavLinkCom#

MavLinkCom 是一个跨平台的 C++ 库,用于连接基于 MavLink 的飞行器并进行通信。具体来说,此库旨在与基于 PX4 的无人机协同工作。

设计#

您可以在 Visual Studio 中查看和编辑 Design.dgml 图表。
Overview

以下是此库中最重要的类。

MavLinkNode#

这是所有 MavLinkNode 的基类(子类包括 MavLinkVehicle、MavLinkVideoClient 和 MavLinkVideoServer)。该节点通过 MavLinkConnection 连接到您的 MavLink 飞行器,并提供发送 MavLinkMessage 和 MavLinkCommand 以及订阅接收消息的方法。此基类还存储您的应用程序用于向远程飞行器标识自身的本地系统 ID 和组件 ID。您还可以调用 startHeartbeat 以发送定期心跳消息以保持连接。

MavLinkMessage#

这是编码的 MavLinkMessage。对于使用过 mavlink.h C API 的人来说,这类似于 mavlink_message_t。您不会手动创建这些消息,它们是从强类型的 MavLinkMessageBase 子类编码的。

强类型消息和命令类#

MavLinkComGenerator 解析 mavlink common.xml 消息定义并生成所有 MavLink* MavLinkMessageBase 子类,以及一堆方便的 mavlink 枚举和一堆强类型的 MavLinkCommand 子类。

MavLinkMessageBase#

这是一组强类型消息类的基类,由 MavLinkComGenerator 项目代码生成。这取代了 mavlink C API 中定义的 C 消息,并提供了一种稍微更面向对象的方式来通过 MavLinkNode 上的 sendMessage 发送和接收消息。这些类具有 encode/decode 方法,用于与 MavLinkMessage 类相互转换。

MavLinkCommand#

这是一组强类型命令类的基类,由 MavLinkComGenerator 项目代码生成。这取代了 mavlink C API 中定义的 C 定义,并提供了一种更面向对象的方式来通过 MavLinkNode 上的 sendCommand 方法发送命令。MavLinkNode 负责将这些命令转换为底层 mavlink COMMAND_LONG 消息。

MavLinkConnection#

此​​类提供静态辅助方法,用于通过串行端口以及 UDP 或 TCP 套接字创建与远程 MavLink 节点的连接。此类提供了一种以发布/订阅方式订阅接收来自该节点消息的方式,因此您可以在同一连接上拥有多个订阅者。MavLinkVehicle 使用此方法来跟踪定义整体飞行器状态的各种消息。

MavLinkVehicle#

MavLinkVehicle 是一个 MavLinkNode,它跟踪定义整体飞行器状态的各种消息,并提供一个 VehicleState 结构体,其中包含该状态的快照,包括返航点、当前姿态、本地位置、全局位置等等。此类还提供了一系列辅助方法,封装了常用命令,提供简单的方法调用来执行诸如布防、撤防、起飞、降落、飞到本地坐标以及通过位置或速度控制在外部控制下飞行等操作。

MavLinkTcpServer#

此辅助类提供了一种设置“服务器”的方法,该服务器接受来自远程节点的 MavLinkConnection。您可以使用此​​类获取一个连接,然后可以将其提供给 MavLinkVideoServer 以通过 MavLink 提供图像。

MavLinkFtpClient#

此辅助类接受给定的 MavLinkConnection,并为支持 FTP 功能的飞行器提供 MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL 的 FTP 客户端支持。此​​类提供简单的方法来列出目录内容,以及获取和放置文件。

MavLinkVideoClient#

此辅助类接受给定的 MavLinkConnection,并提供辅助方法,用于从远程节点请求视频,并将 MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE 和 MAVLINK_MSG_ID_ENCAPSULATED_DATA 消息打包成易于使用的 MavLinkVideoFrames。

MavLinkVideoServer#

此辅助类接受给定的 MavLinkConnection,并提供 MavLinkVideoClient 协议的服务器端,包括在有视频请求需要处理时(hasVideoRequest)进行通知的辅助方法,以及发送视频帧(sendFrame)的方法,该方法将生成正确的 MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE 和 MAVLINK_MSG_ID_ENCAPSULATED_DATA 序列。

示例#

以下来自 UnitTest 项目的代码展示了如何通过 USB 串口连接到 Pixhawk 飞行控制器,然后等待接收到第一个心跳消息。

auto connection = MavLinkConnection::connectSerial("drone", "/dev/ttyACM0", 115200, "sh /etc/init.d/rc.usb\n");
MavLinkHeartbeat heartbeat;
if (!waitForHeartbeat(10000, heartbeat)) {
    throw std::runtime_error("Received no heartbeat from PX4 after 10 seconds");
}

以下代码连接到串口,然后将所有与 QGroundControl 之间的消息转发到该无人机,使用另一个连接加入无人机数据流。

auto droneConnection = MavLinkConnection::connectSerial("drone", "/dev/ttyACM0", 115200, "sh /etc/init.d/rc.usb\n");
auto proxyConnection = MavLinkConnection::connectRemoteUdp("qgc", "127.0.0.1", "127.0.0.1", 14550);
droneConnection->join(proxyConnection);
以下代码然后使用该连接,打开心跳并开始使用本地系统 ID 166 和组件 ID 1 跟踪飞行器信息。
auto vehicle = std::make_shared<MavLinkVehicle>(166, 1);
vehicle->connect(connection);
vehicle->startHeartbeat();

std::this_thread::sleep_for(std::chrono::seconds(5));

VehicleState state = vehicle->getVehicleState();
printf("Home position is %s, %f,%f,%f\n", state.home.is_set ? "set" : "not set", 
    state.home.global_pos.lat, state.home.global_pos.lon, state.home.global_pos.alt);
以下代码使用飞行器对象布防无人机并起飞,然后等待达到起飞高度。
bool rc = false;
if (!vehicle->armDisarm(true).wait(3000, &rc) || !rc) {
    printf("arm command failed\n");
    return;
}
if (!vehicle->takeoff(targetAlt).wait(3000, &rc) || !rc) {
    printf("takeoff command failed\n");
    return;
}
int version = vehicle->getVehicleStateVersion();
while (true) {
    int newVersion = vehicle->getVehicleStateVersion();
    if (version != newVersion) {
        VehicleState state = vehicle->getVehicleState();
        float alt = state.local_est.pos.z;
        if (alt >= targetAlt - delta && alt <= targetAlt + delta)
        {           
            reached = true;
            printf("Target altitude reached\n");
            break;
        }
    } else {
        std::this_thread::sleep_for(std::chrono::milliseconds(10));
    }
}
以下代码使用外部控制使无人机以摄像头对准中心的方式绕圈飞行。这里我们使用 subscribe 方法检查每个新的本地位置消息,以便在接收到该新位置后立即计算新的速度矢量。我们使用 setMessageInterval 请求这些消息的高速率,以确保平滑的圆形轨道。
vehicle->setMessageInterval((int)MavLinkMessageIds::MAVLINK_MSG_ID_LOCAL_POSITION_NED, 30);
vehicle->requestControl();
int subscription = vehicle->getConnection()->subscribe(
    [&](std::shared_ptr<MavLinkConnection> connection, const MavLinkMessage& m) {
        if (m.msgid == (int)MavLinkMessageIds::MAVLINK_MSG_ID_LOCAL_POSITION_NED)
        {
            // convert generic msg to strongly typed message.
            MavLinkLocalPositionNed localPos;
            localPos.decode(msg); 
            float x = localPos.x;
            float y = localPos.y;
            float dx = x - cx;
            float dy = y - cy;
            float angle = atan2(dy, dx);
            if (angle < 0) angle += M_PI * 2;
            float tangent = angle + M_PI_2;
            double newvx = orbitSpeed * cos(tangent);
            double newvy = orbitSpeed * sin(tangent);
            float heading = angle + M_PI;
            vehicle->moveByLocalVelocityWithAltHold(newvx, newvy, altitude, true, heading);
        }
    });
以下代码停止在外部模式下飞行无人机,并告诉无人机在其当前位置悬停。此版本的代码展示了如何在不阻塞 wait 调用的情况下使用 AsyncResult。
    vehicle->releaseControl();
    if (vehicle->loiter().then([=](bool rc) {
        printf("loiter command %s\n", rc ? "succeeded" : "failed");
    }

以下代码从无人机获取所有可配置参数并打印它们。

    auto list = vehicle->getParamList();
    auto end = list.end();
    int count = 0;
    for (auto iter = list.begin(); iter < end; iter++)
    {
        count++;
        MavLinkParameter p = *iter;
        if (p.type == MAV_PARAM_TYPE_REAL32 || p.type == MAV_PARAM_TYPE_REAL64) {
            printf("%s=%f\n", p.name.c_str(), p.value);
        }
        else {
            printf("%s=%d\n", p.name.c_str(), static_cast<int>(p.value));
        }
    }
以下代码在 Pixhawk 上设置一个参数以禁用 USB 安全检查(如果您通过 USB 使用无人机上另一个机载计算机控制 Pixhawk,这将非常方便)。如果您通过 USB 将 PC 或笔记本电脑连接到无人机,则不应这样做。

    MavLinkParameter  p;
    p.name = "CBRK_USB_CHK";
    p.value = 197848;
    if (!vehicle->setParameter(p).wait(3000,&rc) || !rc) {
        printf("Setting the CBRK_USB_CHK failed");
    }

MavLinkVehicle 实际上有一个名为 allowFlightControlOverUsb 的辅助方法,所以现在您知道它是如何实现的了 :-)

高级连接#

您可以使用 MavLinkConnection 类的“join”方法连接不同配置的 mavlink 管道,如下所示。

示例 1,我们通过串口连接到 PX4,并将这些消息代理到侦听远程端口的 QGroundControl 和 LogViewer。

Serial to QGC

示例 2:仿真可以与 jMavSim 通信,jMavSim 连接到 PX4。jMavSim 还可以管理多个连接,因此它可以与虚幻模拟器通信。另一个 MavLinkConnection 可以加入 jMavSim 不支持的代理连接,例如 LogViewer 或远程摄像头节点。

Serial to QGC

示例 3:我们使用 MavLinkConnection 通过串口连接到 PX4,然后为所有远程节点(包括 jMavSim)加入额外的连接。

Serial to QGC

示例 4:我们还可以使用分布式系统远程控制无人机。

Serial to QGC