移植mavlink協議到STM32詳細教程

1準備材料,html

首先準備一個帶串口的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
 

 



相關文章
相關標籤/搜索