文章

MAVLink消息的打包和解包

以心跳包为例,消息格式定义在common.xml中。

1. 打包

心跳包的打包函数为mavlink_msg_heartbeat_encode,将heartbeat作为msgpayload,并计算MAVLink消息的其余域,即完成填充所有内容到msg中。

1
2
3
4
static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat) {
    return mavlink_msg_heartbeat_pack(system_id, component_id, msg, 
        heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status);
}

其他msgid消息类似,调用mavlink_msg_xxx_encode,并调用mavlink_msg_xxx_pack函数进行打包。其中mavlink_msg_heartbeat_pack函数首先将mavlink_heartbeat_t中的内容填充到msgpayload中,然后调用mavlink_finalize_message计算MAVLink消息的其余域,即完成填充所有内容到msg中。

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
                               uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN];
    _mav_put_uint32_t(buf, 0, custom_mode);
    _mav_put_uint8_t(buf, 4, type);
    _mav_put_uint8_t(buf, 5, autopilot);
    _mav_put_uint8_t(buf, 6, base_mode);
    _mav_put_uint8_t(buf, 7, system_status);
    _mav_put_uint8_t(buf, 8, 3);

        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HEARTBEAT_LEN);
#else
    mavlink_heartbeat_t packet;
    packet.custom_mode = custom_mode;
    packet.type = type;
    packet.autopilot = autopilot;
    packet.base_mode = base_mode;
    packet.system_status = system_status;
    packet.mavlink_version = 3;

        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HEARTBEAT_LEN);
#endif

    msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
}

其中,包序号seq存储在内部数组m_mavlink_status[]对应channel中,每次pack操作之后,该channel对应的seq自增1。获取通道函数为:

1
mavlink_status_t* mavlink_get_channel_status(uint8_t chan);

最终,mavlink_finalize_message完成填充msg结构体除payload之外的所有域,包括计算得到的crc

mavlink_finalize_message的调用子函数中,还有两个操作涉及到v1v2协议的处理:

  • v2版本中,payload末尾进行0填充,通过调用_mav_trim_payload函数实现。
  • v2版本中,如果需要进行signing操作,通过调用mavlink_sign_packet生成signature

1.1. 消息的发送

在封包完成之后,调用mavlink_msg_to_send_buffer函数将包转换为字节流,然后调用方就可以通过TCP/UDP等传输层发送了。

1
uint16_t mavlink_msg_to_send_buffer(uint8_t *buf, const mavlink_message_t *msg);

2. 解包

每接收到一个字节,就需要调用mavlink_frame_char解包,并更新对应channelmavlink_status_t结构体中的状态机(parse_state成员域),直到解析完最后一个字节(16位CRC的最后一个字节)。

1
2
3
4
5
6
7
8
uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
{
    return mavlink_frame_char_buffer(mavlink_get_channel_buffer(chan),
        mavlink_get_channel_status(chan),
        c,
        r_message,
        r_mavlink_status);
}

同样的,获取mavlink_status_t结构体的函数为mavlink_get_channel_status

mavlink_frame_char_buffer函数中,就是判断mavlink_status_t结构体中的状态(parse_state成员域)进行解析,并更细parse_state。在解析完一个完成的mavlink_message_t消息体之后,返回MAVLINK_FRAMING_OK表示完成一个数据包的解析,并填充外面给的参数r_message,以及r_mavlink_status

2.1. 状态机流转图

mavlink_frame_char_buffer state flow

3. channel 与 system id

MAVLink协议中,channelsystem id是两个不同的概念。关于channel概念,见官方文档Multiple Streams (“channels”)

  • channel是指MAVLink消息的传输通道,每新建一个TCP/UDP/串口连接,即创建一个channel。可以理解为建立一个UDP Address + port,或一个TCP Address + port,就会创建一个channel
  • system id是标示不同的设备,比如地面站、飞控设备、以及其他设备。
  • 一个channel可以对应多个system id,比如一个channel可以对应多个飞控设备。同时,一个system id也可以对应多个channel,比如一个地面站可以同时连接多个飞控设备。

QGC中,LinkInterface::_allocateMavlinkChannel用于给一个传输层连接分配一个channel,根据MAVLink中的宏定义,一般容量为4个或16个。

4. 参考及资料

本文由作者按照 CC BY 4.0 进行授权