文件目录

  • 大致可以分为三类
    • .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举例-打包

  1. /**
  2. * @brief Pack a allinlast message
  3. * @param system_id ID of this system
  4. * @param component_id ID of this component (e.g. 200 for IMU)
  5. * @param msg The MAVLink message to compress the data into
  6. *
  7. * @param allangle [degree] Angle data combined with magnetometer and gyroscope.
  8. * @param allX [mm] get coordinate x data.
  9. * @param allY [mm] get coordinate y data.
  10. * @param allziangle [degree] get coordinate angle data.
  11. * @return length of the message in bytes (excluding serial stream start sign)
  12. */
  13. static inline uint16_t mavlink_msg_allinlast_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  14. uint32_t allangle, uint32_t allX, uint32_t allY, uint32_t allziangle)
  • 打包时需要指定目标的系统ID和器件ID
  • message中所有的成员将作为函数的参数传入并打包

API举例-拆包

  1. /**
  2. * @brief Get field allangle from allinlast message
  3. *
  4. * @return [degree] Angle data combined with magnetometer and gyroscope.
  5. */
  6. static inline uint32_t mavlink_msg_allinlast_get_allangle(const mavlink_message_t* msg)
  7. {
  8. return _MAV_RETURN_uint32_t(msg, 0);
  9. }
  10. /**
  11. * @brief Get field allX from allinlast message
  12. *
  13. * @return [mm] get coordinate x data.
  14. */
  15. static inline uint32_t mavlink_msg_allinlast_get_allX(const mavlink_message_t* msg)
  16. {
  17. return _MAV_RETURN_uint32_t(msg, 4);
  18. }
  19. /**
  20. * @brief Get field allY from allinlast message
  21. *
  22. * @return [mm] get coordinate y data.
  23. */
  24. static inline uint32_t mavlink_msg_allinlast_get_allY(const mavlink_message_t* msg)
  25. {
  26. return _MAV_RETURN_uint32_t(msg, 8);
  27. }
  28. /**
  29. * @brief Get field allziangle from allinlast message
  30. *
  31. * @return [degree] get coordinate angle data.
  32. */
  33. static inline uint32_t mavlink_msg_allinlast_get_allziangle(const mavlink_message_t* msg)
  34. {
  35. return _MAV_RETURN_uint32_t(msg, 12);
  36. }
  • 可以看出,该message中每有一个成员,都会生成一个可以解析包的函数与之对应
  • 从函数名中即可得到该函数返回值是message中哪一个变量

使用方法

发送message

  1. static void SensorDeal_entry(void *parameter)
  2. {
  3. APP_SENSOR *Application = (APP_SENSOR *)parameter;
  4. mavlink_message_t MAVLinkMsg;
  5. uint8_t MAVLink_Buf[8 + 16]; //发送的缓存(注意大小, 16表示四个参数的大小)
  6. uint16_t MAVLink_Len; //发送的长度
  7. while (1)
  8. {
  9. MAVLink_Len = mavlink_msg_allinlast_pack(Application->dev_UartBsp.Property_MyID, 1, &MAVLinkMsg, 123, 456,1,2);
  10. MAVLink_Len = mavlink_msg_to_send_buffer(MAVLink_Buf, &MAVLinkMsg);
  11. if(MAVLink_Len == 0)
  12. {
  13. rt_kprintf("Error: MAVLink msg packed error!\n");
  14. }
  15. rt_device_write(Application->dev_UartBsp.Value_uart_dev , 0, &MAVLinkMsg, sizeof(MAVLinkMsg));
  16. }
  17. }
  • 使用message文件中提供的函数 mavlink_msg_allinlast_pack 对消息打包
  • 使用框架提供的函数 mavlink_msg_to_send_buffer 将消息填充在缓冲区内
  • 使用RTT提供的串口发送接口 rt_device_write ,把缓存区的数据发送出去

接收message

  1. static rt_err_t Module_UartMavlinkHandle(rt_device_t dev, rt_size_t size)
  2. {
  3. rt_sem_release(&uartMavlink_sem);
  4. return RT_EOK;
  5. }
  • RTT的串口设备接收中断回调函数,当每接收到一个字符,添加信号量

    1. static void Module_UartMavlinkFeed(MODULE_UARTMAVLINK *module)
    2. {
    3. uint8_t data;
    4. uint8_t ret;
    5. while (rt_device_read(module->Value_uart_dev, -1, &data, 1) == 0)
    6. {
    7. rt_sem_control(&uartMavlink_sem, RT_IPC_CMD_RESET, RT_NULL);
    8. rt_sem_take(&uartMavlink_sem, RT_WAITING_FOREVER);
    9. }
    10. ret = mavlink_parse_char(MAVLINK_COMM_3, data, &(module->Value_mavlinkgetmsg), &(module->Value_mavlinkstatus));
    11. if(MAVLINK_FRAMING_OK == ret)
    12. rt_mq_send(&(module->Value_mavlinkmsg_queue), &(module->Value_mavlinkgetmsg), sizeof(module->Value_mavlinkgetmsg));
    13. }
  • 未接收到信号量时,该线程阻塞

  • 当接收到一个信号量,说明串口接收到一个字符
  • 通过框架内的函数 mavlink_parse_char ,将拆分后字符重组为message
  • 判断返回值是否已经完整接收到了一个包
  • 如果已经完整接收,将拼接好的信息添加到RTT的消息队列中

    1. static void SensorDeal_entry(void *parameter)
    2. {
    3. while (1)
    4. {
    5. if( rt_mq_recv (&(Application->dev_UartBsp.Value_mavlinkmsg_queue),
    6. &MAVLinkMsg,sizeof(MAVLinkMsg), 0)==RT_EOK)
    7. {
    8. if(MAVLinkMsg.sysid == Application->dev_UartBsp.Property_MyID)
    9. {
    10. switch(MAVLinkMsg.msgid)
    11. {
    12. case MAVLINK_MSG_ID_AllinLast:
    13. Application->Value_DataSheet[allX] =
    14. mavlink_msg_allinlast_get_allX(&MAVLinkMsg);
    15. Application->Value_DataSheet[allziangle] =
    16. mavlink_msg_allinlast_get_allziangle(&MAVLinkMsg);
    17. break;
    18. default:
    19. break;
    20. }
    21. }
    22. }
    23. }
    24. }
  • 从消息队列中提取一个消息

    • 如果成功提取一个
    • 判断包中的 目标系统ID是不是自身
    • 如果是发给自己的,判断消息的ID
      • 根据消息ID调用不同的解析函数,提取自己关注的变量