MAVLink通讯
MAVLink是一种非常轻量级的消息传递协议,专为无人机生态系统而设计。
PX4使用“MAVLink”与地面站以及MAVLink软件开发工具包(SDK)进行通信,例如“QGroundControl”和MAVSDK,并将其作为连接到飞行控制器外部无人机组件(如伴随计算机、支持MAVLink的相机等)的集成机制。
本主题简要概述了MAVLink的基本概念,例如消息、命令和微服务。 它还提供了教程说明,指导如何为PX4添加以下支持:
- 流式传输MAVLink消息
- 处理传入的MAVLink消息并写入uORB主题。
INFO
本主题不涉及“命令”的处理和发送,也不涉及如何实现自己的微服务。
MAVLink概述
MAVLink是一种轻量级协议,旨在通过不可靠的低带宽无线电链路高效地发送消息。
“消息”是MAVLink中最简单、最“基本”的定义,由名称(例如ATTITUDE)、ID和包含相关数据的字段组成。 它们特意设计得很轻量,大小受到限制,并且没有重发和确认的语义。 独立消息通常用于流式传输遥测数据或状态信息,以及发送不需要确认的命令,例如高速率发送的设定点命令。
命令协议是一种更高级别的协议,用于发送可能需要确认的命令。 特定命令被定义为MAV_CMD枚举的值,例如起飞命令MAV_CMD_NAV_TAKEOFF,并最多包含7个数值“参数”值。 该协议通过将参数值打包在COMMAND_INT
或COMMAND_LONG
消息中来发送命令,并等待在COMMAND_ACK
中带有结果的确认。 如果未收到确认,则会自动重发命令。 请注意,MAV_CMD定义也用于定义任务动作,并且并非所有定义都在PX4上的命令/任务中受支持。
微服务是构建在MAVLink消息之上的其他高级协议。 它们用于传达无法在单个消息中发送的信息,并提供诸如可靠通信之类的功能。 上述命令协议就是这样一种服务。 其他还包括文件传输协议、相机协议和任务协议。
MAVLink消息、命令和枚举在XML定义文件中定义。 MAVLink工具链包括代码生成器,这些生成器根据这些定义创建特定编程语言的库,用于发送和接收消息。 请注意,大多数生成的库不会创建用于实现微服务的代码。
MAVLink项目对一些消息、命令、枚举和微服务进行了标准化,以便使用以下定义文件交换数据(请注意,更高级别的文件“包含”其下方文件的定义):
- development.xml — 被提议作为标准一部分的定义。 如果经过测试后被接受,这些定义将移至
common.xml
。 - common.xml — 满足许多常见无人机用例的定义“库”。 许多飞行栈、地面站和MAVLink外设都支持这些定义。 使用这些定义的飞行栈更有可能实现互操作。
- standard.xml — 实际的标准定义。 它们存在于绝大多数飞行栈中,并且以相同的方式实现。
- minimal.xml — 最小MAVLink实现所需的定义。
该项目还托管了方言XML定义,其中包含特定于某个飞行栈或其他相关方的MAVLink定义。
该协议依赖于通信的每一端对正在发送的消息有一个共享的定义。 这意味着,为了进行通信,通信的两端必须使用从相同XML定义生成的库。
PX4和MAVLink
PX4版本默认构建common.xml
MAVLink定义,以与MAVLink地面站、库以及外部组件(如MAVLink相机)实现最大的兼容性。 在main
分支中,在软件在环仿真(SITL)中,这些定义包含自development.xml
,对于其他板卡则包含自common.xml
。
INFO
要成为PX4版本的一部分,您使用的任何MAVLink定义都必须在common.xml
中(或包含的文件,如standard.xml
和minimal.xml
)。 在开发期间,您可以使用development.xml
中的定义。 您将需要与MAVLink团队合作来定义和贡献这些定义。
PX4将mavlink/mavlink仓库作为子模块包含在/src/modules/mavlink下。 这在/mavlink/messages/1.0/中包含XML定义文件。
构建工具链在构建时生成MAVLink 2 C头文件。 生成头文件的XML文件可以在PX4 kconfig板卡配置中针对每个板卡进行定义,使用变量CONFIG_MAVLINK_DIALECT
:
- 对于SITL,
CONFIG_MAVLINK_DIALECT
在boards/px4/sitl/default.px4board中设置为development
。 您可以将其更改为任何其他定义文件,但该文件必须包含common.xml
。 - 对于其他板卡,
CONFIG_MAVLINK_DIALECT
默认未设置,并且PX4构建common.xml
中的定义(这些默认构建到mavlink模块中 — 在src/modules/mavlink/Kconfig中搜索menuconfig MAVLINK_DIALECT
)。
这些文件生成到构建目录:/build/<构建目标>/mavlink/
。
自定义MAVLink消息
自定义MAVLink消息是指不在PX4默认包含的定义中的消息。
INFO
如果您使用自定义定义,则需要在PX4、您的地面站以及与之通信的任何其他SDK中维护该定义。 一般来说,只要有可能,您应该使用(或添加到)标准定义,以减少维护负担。
可以在与标准XML定义相同的目录中的新方言文件中添加自定义定义。 例如,创建PX4-Autopilot/src/modules/mavlink/mavlink/message_definitions/v1.0/custom_messages.xml
,并设置CONFIG_MAVLINK_DIALECT
以便为SITL构建新文件。 此方言文件应包含development.xml
,以便也包含所有标准定义。
对于初始原型设计,或者如果您希望您的消息成为“标准”,您也可以将您的消息添加到common.xml
(或development.xml
)中。 这简化了构建过程,因为您不需要修改正在构建的方言。
MAVLink开发者指南在如何定义MAVLink消息和枚举中解释了如何定义新消息。
您可以通过检查在构建目录(/build/<构建目标>/mavlink/
)中生成的头文件来确认您的新消息是否已构建。 如果您的消息未构建,可能是格式不正确,或者使用了冲突的ID。 检查构建日志以获取相关信息。
一旦消息被构建,您就可以按照以下部分所述进行流式传输、接收或以其他方式使用它。
INFO
MAVLink开发者指南提供了有关使用MAVLink工具链的更多信息。
流式传输MAVLink消息
MAVLink消息是使用从MavlinkStream
派生的流式传输类进行流式传输的,该类已添加到PX4流列表中。 该类具有您要实现的框架方法,以便PX4可以从生成的MAVLink消息定义中获取所需的信息。 它还有一个send()
方法,每次需要发送消息时都会调用该方法 — 您可以重写此方法,将信息从uORB订阅复制到要发送的MAVLink消息对象中。
本教程演示了如何将uORB消息作为MAVLink消息进行流式传输,并且适用于标准消息和自定义消息。
操作前提
通常,您已经有一个uORB消息,其中包含您想要流式传输的信息,并且有一个您想要用于流式传输的MAVLink消息的定义。
在这个示例中,我们假设您想要将(现有的)BatteryStatus uORB消息流式传输到一个新的MAVLink电池状态消息,我们将其命名为BATTERY_STATUS_DEMO
。
将此BATTERY_STATUS_DEMO
消息复制到您的PX4源代码中development.xml
的消息部分,该文件位于:\src\modules\mavlink\mavlink\message_definitions\v1.0\development.xml
。
<message id="11514" name="BATTERY_STATUS_DEMO">
<description>Simple demo battery.</description>
<field type="uint8_t" name="id" instance="true">Battery ID</field>
<field type="int16_t" name="temperature" units="cdegC" invalid="INT16_MAX">Temperature of the whole battery pack (not internal electronics). INT16_MAX field not provided.</field>
<field type="uint8_t" name="percent_remaining" units="%" invalid="UINT8_MAX">Remaining battery energy. Values: [0-100], UINT8_MAX: field not provided.</field>
</message>
INFO
请注意,这是尚未实现的BATTERY_STATUS_V2消息的简化版本,使用了随机选择的未使用ID 11514
。 在这里,我们将消息放在了development.xml
中,如果该消息最终打算成为标准消息集的一部分,这对于测试来说是可以的,但您也可以将自定义消息放在其自己的方言文件中。
为SITL构建PX4,并确认在/build/px4_sitl_default/mavlink/development/mavlink_msg_battery_status_demo.h
中生成了相关消息。
因为BatteryStatus
已经存在,所以您无需进行任何操作来创建或构建它。
定义流式传输类
首先,在/src/modules/mavlink/streams目录中为您的流式传输类(以要流式传输的消息命名)创建一个名为BATTERY_STATUS_DEMO.hpp
的文件。
在文件顶部添加uORB消息的头文件(所需的MAVLink头文件应该已经可用):
#include <uORB/topics/battery_status.h>
INFO
uORB主题的蛇形命名头文件是在构建时从驼峰命名的uORB文件名生成的。
然后将以下流式传输类定义复制到文件中:
class MavlinkStreamBatteryStatusDemo : public MavlinkStream
{
public:
static MavlinkStream *new_instance(Mavlink *mavlink)
{
return new MavlinkStreamBatteryStatusDemo(mavlink);
}
const char *get_name() const
{
return MavlinkStreamBatteryStatusDemo::get_name_static();
}
static const char *get_name_static()
{
return "BATTERY_STATUS_DEMO";
}
static uint16_t get_id_static()
{
return MAVLINK_MSG_ID_BATTERY_STATUS_DEMO;
}
uint16_t get_id()
{
return get_id_static();
}
unsigned get_size()
{
return MAVLINK_MSG_ID_BATTERY_STATUS_DEMO_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
}
private:
//Subscription to array of uORB battery status instances
uORB::SubscriptionMultiArray<battery_status_s, battery_status_s::MAX_INSTANCES> _battery_status_subs{ORB_ID::battery_status};
// SubscriptionMultiArray subscription is needed because battery has multiple instances.
// uORB::Subscription is used to subscribe to a single-instance topic
/* do not allow top copying this class */
MavlinkStreamBatteryStatusDemo(MavlinkStreamBatteryStatusDemo &);
MavlinkStreamBatteryStatusDemo& operator = (const MavlinkStreamBatteryStatusDemo &);
protected:
explicit MavlinkStreamBatteryStatusDemo(Mavlink *mavlink) : MavlinkStream(mavlink)
{}
bool send() override
{
bool updated = false;
// Loop through _battery_status_subs (subscription to array of BatteryStatus instances)
for (auto &battery_sub : _battery_status_subs) {
// battery_status_s is a struct that can hold the battery object topic
battery_status_s battery_status;
// Update battery_status and publish only if the status has changed
if (battery_sub.update(&battery_status)) {
// mavlink_battery_status_demo_t is the MAVLink message object
mavlink_battery_status_demo_t bat_msg{};
bat_msg.id = battery_status.id - 1;
bat_msg.percent_remaining = (battery_status.connected) ? roundf(battery_status.remaining * 100.f) : -1;
// check if temperature valid
if (battery_status.connected && PX4_ISFINITE(battery_status.temperature)) {
bat_msg.temperature = battery_status.temperature * 100.f;
} else {
bat_msg.temperature = INT16_MAX;
}
//Send the message
mavlink_msg_battery_status_demo_send_struct(_mavlink->get_channel(), &bat_msg);
updated = true;
}
}
return updated;
}
};
大多数流式传输类都非常相似(请参阅/src/modules/mavlink/streams中的示例):
流式传输类派生自
MavlinkStream
,并使用MavlinkStream<CamelCaseMessageName>
的模式命名。public
定义几乎是“样板代码”,允许PX4获取类的实例(new_instance()
),然后使用它从MAVLink头文件中获取消息的名称、ID和大小(get_name()
、get_name_static()
、get_id_static()
、get_id()
、get_size()
)。 对于您自己的流式传输类,这些可以直接复制并修改,以匹配您的MAVLink消息的值。private
定义订阅需要发布的uORB主题。 在这种情况下,uORB主题有多个实例:每个电池一个。 我们使用uORB::SubscriptionMultiArray
来获取电池状态订阅的数组。在这里,我们还定义了构造函数以防止定义被复制。
protected
部分是进行重要工作的地方!在这里,我们重写
send()
方法,将值从订阅的uORB主题复制到MAVLink消息的适当字段中,然后发送消息。在这个特定的示例中,我们有一个