移植mavlink协议到STM32详细教程

1准备材料,

首先准备一个带串口的stm32程序(这里选用整点原子的官方串口例程这里自己去找不讲)作者:恒久力行 QQ:624668529,然后去mavlink官网下载mavlink源码,这里重点讲解这里
a.进入mavlink官网(http://qgroundcontrol.org/mavlink/start),下拉到MAVLink Code and Generator如下图,得到mavlink源码有多种途径,这里选取用python生成。即点击MAVLink Generator (C/C++, Python)
    
 b.然后进入如下界面,点击网址,下面是生成的方法和步骤都写有
c.然后点击clone and downed里面的download zip 即可下载
下载好后解压,然后直接运行mavlink-master里面的mavgenerate.py(python环境自己安装,这里不讲)
然后进入如下界面
 点击第一个browse选择message_definitions文件夹里面的v1.0里面的common.xml
然后自己选择输出路径我这里选的新建文件夹
language选择C
protocol选择1.0
然后直接点generate生成
 
到此材料准备完毕。
 
2开始真正的移植工作
a.在串口实验里新建一个MAVLINK文件夹,并将刚才生成的文件拷贝过来,如图
    
 打开工程新建分组,将所有拷贝过来的文件和头文件目录添加好,具体这里就不讲了,添加好后如图
    
 b.在main函数中添加#include "mavlink.h"如下
   
 然后编译
"..\OBJ\USART.axf" - 30 Error(s), 17 Warning(s).
一个一个解决。
 
错误一:
..\MAVLINK\common\../mavlink_types.h(53): error:  #20: identifier "pack" is undefined
解决方法:
将mavlink_types.h中
  1. #define MAVPACKED( __Declaration__ ) __pragma( pack(push,1)) __Declaration__ __pragma( pack(pop))
改为
  1. #define MAVPACKED( __Declaration__ ) __Declaration__
这里不使用对齐字节了,直接用也是一样的。
编译后:
"..\OBJ\USART.axf" - 30 Error(s), 7 Warning(s).
 
错误二:
..\MAVLINK\common\../mavlink_types.h(54): error:  #3092: anonymous unions are only supported in --gnu mode, or when enabled with #pragma anon_unions
解决方法:
根据提示信息在mavlink_types.h的前面加入#pragma anon_unions
编译后:
"..\OBJ\USART.axf" - 30 Error(s), 8 Warning(s).
 
错误三:
..\MAVLINK\common\../checksum.h(34): warning:  #260-D: explicit type is missing ("int" assumed)
包括后面很多错误都有共同点,指向有inline的行,这里是因为mdk中无法识别inline
解决方法:
在checksum.h加入一行代码定义inline
  1. #defineinline __INLINE
 
编译后:
"..\OBJ\USART.axf" - 4 Error(s), 195 Warning(s).
 
错误四:
..\MAVLINK\common\../mavlink_conversions.h(167): error:  #268: declaration may not appear after executable statement in block
解决方法:
指向定义的变量,将变量的定义放到函数的最前端(四个错误都是这种错误)
以前mavlink_conversions.h的代码
  1. MAVLINK_HELPER void mavlink_dcm_to_quaternion(constfloat dcm[3][3],float quaternion[4])
  2. {
  3. float tr = dcm[0][0]+ dcm[1][1]+ dcm[2][2];
  4. if(tr >0.0f){
  5. float s = sqrtf(tr +1.0f);
  6. quaternion[0]= s *0.5f;
  7. s =0.5f/ s;
  8. quaternion[1]=(dcm[2][1]- dcm[1][2])* s;
  9. quaternion[2]=(dcm[0][2]- dcm[2][0])* s;
  10. quaternion[3]=(dcm[1][0]- dcm[0][1])* s;
  11. }else{
  12. /* Find maximum diagonal element in dcm
  13. * store index in dcm_i */
  14. int dcm_i =0;
  15. int i;
  16. for(i =1; i <3; i++){
  17. if(dcm[i][i]> dcm[dcm_i][dcm_i]){
  18. dcm_i = i;
  19. }
  20. }
  21. int dcm_j =(dcm_i +1)%3;
  22. int dcm_k =(dcm_i +2)%3;
  23. float s = sqrtf((dcm[dcm_i][dcm_i]- dcm[dcm_j][dcm_j]-
  24. dcm[dcm_k][dcm_k])+1.0f);
  25. quaternion[dcm_i +1]= s *0.5f;
  26. s =0.5f/ s;
  27. quaternion[dcm_j +1]=(dcm[dcm_i][dcm_j]+ dcm[dcm_j][dcm_i])* s;
  28. quaternion[dcm_k +1]=(dcm[dcm_k][dcm_i]+ dcm[dcm_i][dcm_k])* s;
  29. quaternion[0]=(dcm[dcm_k][dcm_j]- dcm[dcm_j][dcm_k])* s;
  30. }
  31. }
更改后mavlink_conversions.h的代码
  1. MAVLINK_HELPER void mavlink_dcm_to_quaternion(constfloat dcm[3][3],float quaternion[4])
  2. {
  3. int dcm_j,dcm_k;
  4. float s;
  5. float tr = dcm[0][0]+ dcm[1][1]+ dcm[2][2];
  6. if(tr >0.0f){
  7. float s = sqrtf(tr +1.0f);
  8. quaternion[0]= s *0.5f;
  9. s =0.5f/ s;
  10. quaternion[1]=(dcm[2][1]- dcm[1][2])* s;
  11. quaternion[2]=(dcm[0][2]- dcm[2][0])* s;
  12. quaternion[3]=(dcm[1][0]- dcm[0][1])* s;
  13. }else{
  14. /* Find maximum diagonal element in dcm
  15. * store index in dcm_i */
  16. int dcm_i =0;
  17. int i;
  18. for(i =1; i <3; i++){
  19. if(dcm[i][i]> dcm[dcm_i][dcm_i]){
  20. dcm_i = i;
  21. }
  22. }
  23. dcm_j =(dcm_i +1)%3;
  24. dcm_k =(dcm_i +2)%3;
  25. s = sqrtf((dcm[dcm_i][dcm_i]- dcm[dcm_j][dcm_j]-
  26. dcm[dcm_k][dcm_k])+1.0f);
  27. quaternion[dcm_i +1]= s *0.5f;
  28. s =0.5f/ s;
  29. quaternion[dcm_j +1]=(dcm[dcm_i][dcm_j]+ dcm[dcm_j][dcm_i])* s;
  30. quaternion[dcm_k +1]=(dcm[dcm_k][dcm_i]+ dcm[dcm_i][dcm_k])* s;
  31. quaternion[0]=(dcm[dcm_k][dcm_j]- dcm[dcm_j][dcm_k])* s;
  32. }
  33. }
 
以前mavlink_helpers.h的代码
  1. MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t*buffer,constmavlink_message_t*msg)
  2. {
  3. memcpy(buffer,(constuint8_t*)&msg->magic, MAVLINK_NUM_HEADER_BYTES +(uint16_t)msg->len);
  4. uint8_t*ck = buffer +(MAVLINK_NUM_HEADER_BYTES +(uint16_t)msg->len);
  5. ck[0]=(uint8_t)(msg->checksum &0xFF);
  6. ck[1]=(uint8_t)(msg->checksum >>8);
  7. return MAVLINK_NUM_NON_PAYLOAD_BYTES +(uint16_t)msg->len;
  8. }
更改后mavlink_helpers.h的代码
  1. MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t*buffer,constmavlink_message_t*msg)
  2. {
  3. uint8_t*ck;
  4. memcpy(buffer,(constuint8_t*)&msg->magic, MAVLINK_NUM_HEADER_BYTES +(uint16_t)msg->len);
  5. ck = buffer +(MAVLINK_NUM_HEADER_BYTES +(uint16_t)msg->len);
  6. ck[0]=(uint8_t)(msg->checksum &0xFF);
  7. ck[1]=(uint8_t)(msg->checksum >>8);
  8. return MAVLINK_NUM_NON_PAYLOAD_BYTES +(uint16_t)msg->len;
  9. }
编译后:
"..\OBJ\USART.axf" - 0 Error(s), 195 Warning(s).
 
解决所有警告的方法:
将protocol.h里面的旧代码
  1. #define _MAV_RETURN_char(msg, wire_offset)(constchar)_MAV_PAYLOAD(msg)[wire_offset]
  2. #define_MAV_RETURN_int8_t(msg, wire_offset)(constint8_t)_MAV_PAYLOAD(msg)[wire_offset]
  3. #define_MAV_RETURN_uint8_t(msg, wire_offset)(constuint8_t)_MAV_PAYLOAD(msg)[wire_offset]
去掉const,改为
  1. #define _MAV_RETURN_char(msg, wire_offset)(constchar)_MAV_PAYLOAD(msg)[wire_offset]
  2. #define_MAV_RETURN_int8_t(msg, wire_offset)(int8_t)_MAV_PAYLOAD(msg)[wire_offset]
  3. #define_MAV_RETURN_uint8_t(msg, wire_offset)(uint8_t)_MAV_PAYLOAD(msg)[wire_offset]
编译后:
"..\OBJ\USART.axf" - 0 Error(s), 0 Warning(s).
 
3开始更改底层串口代码
待续。。。
作者:恒久力行 QQ:624668529
这里有移植的完整教程,两个教程参考着看吧附上网址http://www.cnblogs.com/lovechen/p/5809709.html
 

 





posted @ 2016-08-24 09:47  恒久力行  阅读(14420)  评论(0编辑  收藏  举报