移植mavlink到stm32详细教程,后面附快速移植方法

一:准备材料: mavlink源码 stm32串口程序

   1.mavlink源码:
            
            
           b.下拉到MAVLink Code and Generator点击MAVLink Generator (C/C++, Python)下载源码生成器          
                
 
             c.解压缩下载的文件,点击mavgenerate.py这个文件(前提是已经安装好了python软件)
                
             d.xml是生成的源文件,out是生成的目录 langguage是生成的代码语言。
                xml:mavlink-master/message_definitions/v1.0/common.xml
                out:D:/Backup/桌面/mav
                langguage:C
                protocol:1.0
                
                点击generate就能生成相应的文件到out目录里去
                
     2.stm32串口代码选用正点原子的串口代码,将生成的文件新建一个MAVLINK文件夹添加到工程里去(添加文件,添加头文件)
            
             
                     其中manlink_avoid_errors.h是我自己添加的用来解决报错的文件,尽量将更改添加到这个文件,方便以后移植
              
 二:准备移植
    将准备好的工程编译,会出现一堆错误("..\OBJ\USART.axf" - 30 Error(s), 17 Warning(s).),别急,一个一个解决就好了
 
    错误1:..\MAVLINK\common\../mavlink_types.h(53): error:  #20: identifier "pack" is undefined
    解决方法:这个错误是因为对齐方式的原因,因为gun编译跟mdk有些差异,具体我没有深究。
    屏蔽mavlink_types.h中的如下代码
  1. // Macro to define packed structures
  2. //#ifdef __GNUC__
  3. // #define MAVPACKED( __Declaration__ ) __Declaration__ __attribute__((packed))
  4. //#else
  5. // #define MAVPACKED( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) )
  6. //#endif
     在  mavlink_avoid_errors.h中加入如下代码(意思就是让MAVPACKED不起任何作用)
  1. #define MAVPACKED( __Declaration__ ) __Declaration__
    编译后:"..\OBJ\USART.axf" - 30 Error(s), 7 Warning(s).
 
 
    错误2:..\MAVLINK\common\../mavlink_types.h(53): error:  #3092: anonymous unions are only supported in --gnu mode, or when enabled with #pragma anon_unions
    解决方法:根据错误提示在mavlink_avoid_errors.h中添加如下代码
  1. #pragma anon_unions
    编译后:"..\OBJ\USART.axf" - 30 Error(s), 8 Warning(s).
 
 
 
    错误3:..\MAVLINK\common\../checksum.h(34): warning:  #260-D: explicit type is missing ("int" assumed)
    解决方法:包括后面很多错误都有共同点,指向有inline的行,这里是因为mdk中无法识别inline,重新定义inline就好
    在mavlink_avoid_errors.h中加入如下代码(因为mdk认识__INLINE)
  1. #defineinline __INLINE
    编译后:"..\OBJ\USART.axf" - 4 Error(s), 195 Warning(s).
 
 
 
   错误4:..\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. 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. 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).
 
    警告:..\MAVLINK\common\./mavlink_msg_heartbeat.h(261): warning:  #191-D: type qualifier is meaningless on cast type
    解决方法:按照提示跟踪错误到protocol.h,
    更改protocol.h的代码为(就是去掉了const)
  1. #define_MAV_RETURN_int8_t(msg, wire_offset)(int8_t)_MAV_PAYLOAD(msg)[wire_offset]
  2. #define_MAV_RETURN_uint8_t(msg, wire_offset)(uint8_t)_MAV_PAYLOAD(msg)[wire_offset]
    编译后:"..\OBJ\USART.axf" - 0 Error(s), 0 Warning(s).
   到此不代表移植好了,上面是本人边移植边写的教程,如下给大家做一个总结。可能很多东西跟上面重复的,如果大家想尽快的移植好可以参考下面的,如果你想了解为什么这么移植请参考上    面的移植过程。
 
三:不需要懂过程的快速移植,只需做好这几步就能快速移植了
    1.准备好工程变添加好生成的mavlink纯净文件(未经任何修改的文件)
    2.添加我写好的mavlink_avoid_errors.h文件,代码如下
  1. /** @file mavlink_avoid_errors.h
  2. * @简介:本文件是由624668529添加,用来统一解决mavlink报错信息
  3. * @see QQ624668529
  4. */
  5. #ifndef MAVLINK_AVOID_ERRORS_H
  6. #define MAVLINK_AVOID_ERRORS_H
  7. /*解决..\MAVLINK\common\../mavlink_types.h(53): error: #20: identifier "pack" is undefined*/
  8. #define MAVPACKED( __Declaration__ ) __Declaration__
  9. /*解决..\MAVLINK\common\../mavlink_types.h(53): error: #3092: anonymous unions are only supported in --gnu mode, or when enabled with #pragma anon_unions*/
  10. #pragma anon_unions
  11. #defineinline __INLINE
  12. #ifndef memset//由624668529添加 2018-08-24
  13. staticinlinevoid*memset(void*dest,int data,size_t length){
  14. uint32_t i;
  15. int*point = dest;
  16. for(i=0; i<length; i++) point[i]= data;
  17. return dest;
  18. }
  19. #endif
  20. #ifndef memcpy//由624668529添加 2018-08-24
  21. void*memcpy(void*dest,constvoid*src,size_t n)
  22. {
  23. unsignedchar*pout =(unsignedchar*)dest;
  24. unsignedchar*pin =(unsignedchar*)src;
  25. while(n-->0)*pout++=*pin++;
  26. return dest;
  27. }
  28. #include"mavlink_types.h"
  29. #define MAVLINK_USE_CONVENIENCE_FUNCTIONS
  30. #define MAVLINK_SEPARATE_HELPERS
  31. //mavlink_system_t mavlink_system = {0,0};
  32. mavlink_system_t mavlink_system ={
  33. 1,
  34. 1
  35. };// System ID, 1-255, Component/Subsystem ID, 1-255
  36. void comm_send_ch(mavlink_channel_t chan,uint8_t buf)
  37. {
  38. chan=chan;
  39. USART_SendData(USART1, buf);//向串口1发送数据
  40. while(USART_GetFlagStatus(USART1,USART_FLAG_TC)!=SET);//等待发送结束
  41. }
  42. #endif
  43. #include"mavlink.h"
  44. #include"mavlink_helpers.h"
  45. #endif//AVLINK_AVOID_ERRORS_H
    3.在main.c中更改成如下代码
  1. #include"sys.h"
  2. #include"delay.h"
  3. #include"usart.h"
  4. #include"led.h"
  5. #include"beep.h"
  6. #include"key.h"
  7. #include"mavlink_avoid_errors.h"
  8. //ALIENTEK 探索者STM32F407开发板 实验4
  9. //串口通信实验 -库函数版本
  10. //技术支持:www.openedv.com
  11. //淘宝店铺:http://eboard.taobao.com
  12. //广州市星翼电子科技有限公司
  13. //作者:正点原子 @ALIENTEK
  14. int main(void)
  15. {
  16. mavlink_heartbeat_t packet_in ={
  17. 963497464,17,84,151,218,3
  18. };
  19. mavlink_heartbeat_t packet1;
  20. memset(&packet1,0,sizeof(packet1));
  21. packet1.custom_mode = packet_in.custom_mode;
  22. packet1.type = packet_in.type;
  23. packet1.autopilot = packet_in.autopilot;
  24. packet1.base_mode = packet_in.base_mode;
  25. packet1.system_status = packet_in.system_status;
  26. packet1.mavlink_version = packet_in.mavlink_version;
  27. NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);//设置系统中断优先级分组2
  28. delay_init(168);//延时初始化
  29. uart_init(115200);//串口初始化波特率为115200
  30. LED_Init();//初始化与LED连接的硬件接口
  31. while(1)
  32. {
  33. mavlink_msg_heartbeat_send(MAVLINK_COMM_1 , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status );
  34. delay_ms(1000);
  35. }
  36. }
    4将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. }
    5.将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. }
    6.屏蔽mavlink_types.h中这一部分代码
  1. // Macro to define packed structures
  2. //#ifdef __GNUC__
  3. // #define MAVPACKED( __Declaration__ ) __Declaration__ __attribute__((packed))
  4. //#else
  5. // #define MAVPACKED( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) )
  6. //#endif
    7.更改protocol.h中的代码为(即去掉const)解决警告的方法
  1. #define_MAV_RETURN_int8_t(msg, wire_offset)(int8_t)_MAV_PAYLOAD(msg)[wire_offset]
  2. #define_MAV_RETURN_uint8_t(msg, wire_offset)(uint8_t)_MAV_PAYLOAD(msg)[wire_offset]
编译后:"..\OBJ\USART.axf" - 0 Error(s), 0 Warning(s).
 
 
四:下载到开发板打开串口调试助手
   成功接收到数据,如图,表示移植成功
    
 
 移植成功。
作者:恒久力行 QQ:624668529
 
本次进添加了串口发送函数,以后若有需要我会继续添加串口接收函数。
 
分享教程,只希望中国的科学技术突飞猛进过,望早日超越其他国家。加油中国人
 

 

 





posted @ 2016-08-26 11:30  恒久力行  阅读(10467)  评论(12编辑  收藏  举报