1. 库文件接口使用
1.1. 原理
发送方发送数据,需要经历组包->格式转换->发包(根据链路类型调用相关发送接口)的过程;
接收方接收数据,需要经历解包->msgId解析->具体消息处理的过程;
1.2. 接口
需要关注的重点是发送数据,接收数据的流程。Mavlink提供了几类接口,简化了应用层收发数据的操作。主要使用的接口如下:
发送相关接口 | 说明 |
---|---|
mavlink_msg_xxx_pack | 组包接口,按照协议封装数据,以mavlink_message_t结构对外提供,默认使用通道MAVLINK_COMM_0 |
mavlink_msg_to_send_bufffer | 将mavlink_message_t结构体转换为buf |
mavlink_finalize_message | 内部组包接口,组除payload之外的其他数据,默认使用通道MAVLINK_COMM_0 |
mavlink_finalize_message_chan | 内部组包接口,组除payload之外的其他数据,可指定通道 |
mavlink_msg_xxx_encode | 组包接口,按照协议封装数据,以mavlink_message_t结构对外提供。源参数都过mavlink_xxx_t结构体提供 |
mavlink_msg_xxx_encode_chan | 组包接口,同mavlink_msg_xxx_encode,但可以指定通道 |
mavlink_msg_xxx_pack_chan | 组包接口,同mavlink_msg_xxx_pack,但可以指定通道 |
接收相关接口 | 说明 |
---|---|
mavlink_parse_char | 解析接收数据,按字节解析 |
mavlink_msg_xxx_decode | 解包接口,将mavlink_message_t转换为mavlink_xxx_t结构体 |
mavlink_msg_xxx_get_yyy | 获取结构体xxx的yyy字段数据 |
1.3. 结构体
1.3.1. mavlink_message_t
MAVPACKED(
typedef struct __mavlink_message {
uint16_t checksum; ///< sent at end of packet
uint8_t magic; ///< protocol magic marker
uint8_t len; ///< Length of payload
uint8_t incompat_flags; ///< flags that must be understood
uint8_t compat_flags; ///< flags that can be ignored if not understood
uint8_t seq; ///< Sequence of packet
uint8_t sysid; ///< ID of message sender system/aircraft
uint8_t compid; ///< ID of the message sender component
uint32_t msgid:24; ///< ID of message in payload
uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];
uint8_t ck[2]; ///< incoming checksum bytes
uint8_t signature[MAVLINK_SIGNATURE_BLOCK_LEN];
}) mavlink_message_t;
mavlink_message_t结构体参与组包和解包的过程,作为中间过程参数使用,也是mavlink数据帧格式的体现。结构体成员magic~signature的完全对应帧格式的字段,而checksum成员则作为中间参数,参与解包过程的校验和的计算过程。实际接收和发送的数据帧的校验和,存储在ck中。
1.3.2. mavlink_status_t
typedef struct __mavlink_status {
uint8_t msg_received; ///< Number of received messages
uint8_t buffer_overrun; ///< Number of buffer overruns
uint8_t parse_error; ///< Number of parse errors
mavlink_parse_state_t parse_state; ///< Parsing state machine
uint8_t packet_idx; ///< Index in current packet
uint8_t current_rx_seq; ///< Sequence number of last packet received
uint8_t current_tx_seq; ///< Sequence number of last packet sent
uint16_t packet_rx_success_count; ///< Received packets
uint16_t packet_rx_drop_count; ///< Number of packet drops
uint8_t flags; ///< MAVLINK_STATUS_FLAG_*
uint8_t signature_wait; ///< number of signature bytes left to receive
struct __mavlink_signing *signing; ///< optional signing state
struct __mavlink_signing_streams *signing_streams; ///< global record of stream timestamps
} mavlink_status_t;
mavlink_status_t结构体存储和记录了组包和解包的过程状态量,以及解包成功失败的统计信息。
各字段含义如下:
Element | 说明 |
---|---|
msg_received | 接收状态量,取值为mavlink_framing_t枚举值,可为incomplete/ok/bad_crc/bad_signature |
buffer_overrun | payload长度溢出的包统计 |
parse_error | 解包错误的包统计 |
parse_state | 解包状态量,控制解包的状态机跳转,取值为mavlink_parse_state_t的枚举值 |
packet_idx | Payload字段的数组下标,解析payload的时候每解析一字节则加1 |
current_rx_seq | 解包时,当前包的seq字段 |
current_tx_seq | 组包时,当前包的seq字段,每次递增1 |
packet_rx_success_count | 解包成功统计值 |
packet_rx_drop_count | 解析失败的包统计(当前1.0.12版本貌似没用上) |
flags | 标志位,用于标识版本信息,取值为MAVLINK_STATUS_FLAG_*宏 |
signature_wait | 用于记录待接收的签名字段的字节数,初始为13,每收到一个签名字节减1 |
signing | 用于数据签名 |
signing_streams | 用于数据签名 |
1.4. 程序示例
发送数据帧:
/*Send Heartbeat */
mavlink_msg_heartbeat_pack(1, 200, &msg, MAV_TYPE_HELICOPTER, MAV_AUTOPILOT_GENERIC, MAV_MODE_GUIDED_ARMED, 0, MAV_STATE_ACTIVE);
len = mavlink_msg_to_send_buffer(buf, &msg);
bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in));
/* Send Status */
mavlink_msg_sys_status_pack(1, 200, &msg, 0, 0, 0, 500, 11000, -1, -1, 0, 0, 0, 0, 0, 0);
len = mavlink_msg_to_send_buffer(buf, &msg);
bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof (struct sockaddr_in));
/* Send Local Position */
mavlink_msg_local_position_ned_pack(1, 200, &msg, microsSinceEpoch(),
position[0], position[1], position[2],
position[3], position[4], position[5]);
len = mavlink_msg_to_send_buffer(buf, &msg);
bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in));
/* Send attitude */
mavlink_msg_attitude_pack(1, 200, &msg, microsSinceEpoch(), 1.2, 1.7, 3.14, 0.01, 0.02, 0.03);
len = mavlink_msg_to_send_buffer(buf, &msg);
bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in));
也可以如下:
// heartbeat为mavlink_heartbeat_t类型,外部已经从其他途径获取到该结构体内容,或者自行填充好了该结构体
mavlink_msg_heartbeat_encode(1, 200, &msg, &heartbeat);
len = mavlink_msg_to_send_buffer(buf, &msg);
bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in));
接收数据帧:
memset(buf, 0, BUFFER_LENGTH);
recsize = recvfrom(sockS, (void *)buf, BUFFER_LENGTH, 0, (struct sockaddr *)&locAddr, &fromlen);
if (recsize > 0)
{
// Something received - print out all bytes and parse packet
mavlink_message_t msg;
mavlink_status_t status;
printf("Bytes Received: %d\nDatagram: ", (int)recsize);
for (i = 0; i < recsize; ++i)
{
temp = buf[i];
printf("%02x ", (unsigned char)temp);
if (mavlink_parse_char(MAVLINK_COMM_0, buf[i], &msg, &status))
{
// Packet received
printf("\nReceived packet: SYS: %d, COMP: %d, LEN: %d, MSG ID: %d\n", msg.sysid, msg.compid, msg.len, msg.msgid);
switch(msg.msgid)
{
case MAVLINK_MSG_ID_HEARTBEAT:
{
mavlink_heartbeat_t heartbeat;
mavlink_msg_heartbeat_decode(&msg, &heartbeat);
// HanldeHeartbeatMsg(heartbeat);
break;
}
default:
break;
}
}
}
printf("\n");
}