文件目录
- 大致可以分为三类
- .xml文件
- 框架API文件(mavlink.h等)
- msg.h文件
- 因为MAVLink将生成的所有函数均以头文件形式产生,因此无需添加到MDK的工程目录下
- 仅需添加头文件路径和添加包含即可使用
XML文件
- MAVLink生成器的输入文件
- 在这里自定义msg的组成和结构等
- MAVLink生成器文件夹下存在范例xml文件可供参考
- 在enums中指定
- 会用到什么样的状态标签
- (可以用来定义msg中变量类型)
- 在message中指定
- 会用到什么样的消息,
- 消息中包含哪些变量并指定变量类型(或单位)
- 为消息添加含义注释
- 注意每一个message都会对应生成后的.h文件
- 文件中定义了仅针对该message的打包、拆包函数
框架文件
- 除xml、message对应的文件之外的文件
- 是MAVLink的主框架和实现
- 根据教程修改mavlink_types文件,其他无需变动
Message文件
- 在XML中每定义一个message类型,都会对应产生一个.h文件
- 封装了仅针对该message的打包、拆包函数
API举例-打包
/**
* @brief Pack a allinlast message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param allangle [degree] Angle data combined with magnetometer and gyroscope.
* @param allX [mm] get coordinate x data.
* @param allY [mm] get coordinate y data.
* @param allziangle [degree] get coordinate angle data.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_allinlast_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t allangle, uint32_t allX, uint32_t allY, uint32_t allziangle)
- 打包时需要指定目标的系统ID和器件ID
- message中所有的成员将作为函数的参数传入并打包
API举例-拆包
/**
* @brief Get field allangle from allinlast message
*
* @return [degree] Angle data combined with magnetometer and gyroscope.
*/
static inline uint32_t mavlink_msg_allinlast_get_allangle(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field allX from allinlast message
*
* @return [mm] get coordinate x data.
*/
static inline uint32_t mavlink_msg_allinlast_get_allX(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 4);
}
/**
* @brief Get field allY from allinlast message
*
* @return [mm] get coordinate y data.
*/
static inline uint32_t mavlink_msg_allinlast_get_allY(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 8);
}
/**
* @brief Get field allziangle from allinlast message
*
* @return [degree] get coordinate angle data.
*/
static inline uint32_t mavlink_msg_allinlast_get_allziangle(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 12);
}
- 可以看出,该message中每有一个成员,都会生成一个可以解析包的函数与之对应
- 从函数名中即可得到该函数返回值是message中哪一个变量
使用方法
发送message
static void SensorDeal_entry(void *parameter)
{
APP_SENSOR *Application = (APP_SENSOR *)parameter;
mavlink_message_t MAVLinkMsg;
uint8_t MAVLink_Buf[8 + 16]; //发送的缓存(注意大小, 16表示四个参数的大小)
uint16_t MAVLink_Len; //发送的长度
while (1)
{
MAVLink_Len = mavlink_msg_allinlast_pack(Application->dev_UartBsp.Property_MyID, 1, &MAVLinkMsg, 123, 456,1,2);
MAVLink_Len = mavlink_msg_to_send_buffer(MAVLink_Buf, &MAVLinkMsg);
if(MAVLink_Len == 0)
{
rt_kprintf("Error: MAVLink msg packed error!\n");
}
rt_device_write(Application->dev_UartBsp.Value_uart_dev , 0, &MAVLinkMsg, sizeof(MAVLinkMsg));
}
}
- 使用message文件中提供的函数
mavlink_msg_allinlast_pack
对消息打包 - 使用框架提供的函数
mavlink_msg_to_send_buffer
将消息填充在缓冲区内 - 使用RTT提供的串口发送接口
rt_device_write
,把缓存区的数据发送出去
接收message
static rt_err_t Module_UartMavlinkHandle(rt_device_t dev, rt_size_t size)
{
rt_sem_release(&uartMavlink_sem);
return RT_EOK;
}
RTT的串口设备接收中断回调函数,当每接收到一个字符,添加信号量
static void Module_UartMavlinkFeed(MODULE_UARTMAVLINK *module)
{
uint8_t data;
uint8_t ret;
while (rt_device_read(module->Value_uart_dev, -1, &data, 1) == 0)
{
rt_sem_control(&uartMavlink_sem, RT_IPC_CMD_RESET, RT_NULL);
rt_sem_take(&uartMavlink_sem, RT_WAITING_FOREVER);
}
ret = mavlink_parse_char(MAVLINK_COMM_3, data, &(module->Value_mavlinkgetmsg), &(module->Value_mavlinkstatus));
if(MAVLINK_FRAMING_OK == ret)
rt_mq_send(&(module->Value_mavlinkmsg_queue), &(module->Value_mavlinkgetmsg), sizeof(module->Value_mavlinkgetmsg));
}
未接收到信号量时,该线程阻塞
- 当接收到一个信号量,说明串口接收到一个字符
- 通过框架内的函数
mavlink_parse_char
,将拆分后字符重组为message - 判断返回值是否已经完整接收到了一个包
如果已经完整接收,将拼接好的信息添加到RTT的消息队列中
static void SensorDeal_entry(void *parameter)
{
while (1)
{
if( rt_mq_recv (&(Application->dev_UartBsp.Value_mavlinkmsg_queue),
&MAVLinkMsg,sizeof(MAVLinkMsg), 0)==RT_EOK)
{
if(MAVLinkMsg.sysid == Application->dev_UartBsp.Property_MyID)
{
switch(MAVLinkMsg.msgid)
{
case MAVLINK_MSG_ID_AllinLast:
Application->Value_DataSheet[allX] =
mavlink_msg_allinlast_get_allX(&MAVLinkMsg);
Application->Value_DataSheet[allziangle] =
mavlink_msg_allinlast_get_allziangle(&MAVLinkMsg);
break;
default:
break;
}
}
}
}
}
从消息队列中提取一个消息
- 如果成功提取一个
- 判断包中的 目标系统ID是不是自身
- 如果是发给自己的,判断消息的ID
- 根据消息ID调用不同的解析函数,提取自己关注的变量