移植MAVLINK到STM32详细教程之三
在前面教程的基础上继续移植优化,之前的没有加缓冲区,没有接收函数功能,这里进行统一的讲解 作者:恒久力行 qq:624668529
缓冲区对于接受来说很有必要,为了数据的稳定性和实时性必须要加上缓冲。没有缓冲很容易造成数据丢失
一:利用之前移植好的工程,在其基础上进行改动
1.将两个文件mavlink_usart_fifo.h mavlink_usart_fifo.c添加到工程里(都是关于缓冲区的底层串口加缓冲区函数)
mavlink_usart_fifo.h
#ifndef _USART_FIFO_H_//作者:恒久力行 qq:624668529#define _USART_FIFO_H_#include"stdint.h"#definetrue1#definefalse0typedefstruct _fifo {uint8_t* buf;uint16_t length;uint16_t head;uint16_t tail;}fifo_t;uint8_t fifo_read_ch(fifo_t* fifo,uint8_t* ch);uint8_t fifo_write_ch(fifo_t* fifo,uint8_t ch);uint16_t fifo_free(fifo_t* fifo);uint16_t fifo_used(fifo_t* fifo);void fifo_init(fifo_t* fifo,uint8_t* buf,uint16_t length);uint8_t serial_write_buf(uint8_t* buf,uint16_t length);uint8_t serial_read_ch(void);uint16_t serial_free(void);uint16_t serial_available(void);#endif/*_USART_FIFO_H_*/
mavlink_usart_fifo.c
#include"sys.h"//作者:恒久力行 qq:624668529#include"mavlink_usart_fifo.h"#define UART_TX_BUFFER_SIZE 255#define UART_RX_BUFFER_SIZE 255fifo_t uart_rx_fifo, uart_tx_fifo;uint8_t uart_tx_buf[UART_TX_BUFFER_SIZE], uart_rx_buf[UART_RX_BUFFER_SIZE];/** @brief 读FIFO* @param fifo 待读缓冲区* *ch 读到的数据* @return* 正确读取,1; 无数据,0*/uint8_t fifo_read_ch(fifo_t* fifo,uint8_t* ch){if(fifo->tail == fifo->head)returnfalse;*ch = fifo->buf[fifo->tail];if(++fifo->tail >= fifo->length) fifo->tail =0;returntrue;}/** @brief 写一字节数据到FIFO* @param fifo 待写入缓冲区* ch 待写入的数据* @return* 正确,1; 缓冲区满,0*/uint8_t fifo_write_ch(fifo_t* fifo,uint8_t ch){uint16_t h = fifo->head;if(++h >= fifo->length) h =0;if(h == fifo->tail)returnfalse;fifo->buf[fifo->head]= ch;fifo->head = h;returntrue;}/** @brief 返回缓冲区剩余字节长度* @param fifo* @return* 剩余空间** @note 剩余字节长度大于等于2时,才可写入数据*/uint16_t fifo_free(fifo_t* fifo){uint16_t free;if(fifo->head >= fifo->tail) free = fifo->tail +(fifo->length - fifo->head);else free = fifo->tail - fifo->head;return free;}uint16_t fifo_used(fifo_t* fifo){uint16_t used;if(fifo->head >= fifo->tail) used = fifo->head - fifo->tail;else used = fifo->head +(fifo->length - fifo->tail);return used;}/** @brief 初始化缓冲区* @param *fifo* *buf* length*/void fifo_init(fifo_t* fifo,uint8_t* buf,uint16_t length){uint16_t i;fifo->buf = buf;fifo->length = length;fifo->head =0;fifo->tail =0;for(i=0; i<length; i++) fifo->buf[i]=0;}/** @brief 写数据到串口,启动发射** @note 数据写入发射缓冲区后,启动发射中断,在中断程序,数据自动发出*/uint8_t serial_write_buf(uint8_t* buf,uint16_t length){uint16_t i;if(length ==0)returnfalse;for(i =0; length >0; length--, i++){fifo_write_ch(&uart_tx_fifo, buf[i]);}USART_ITConfig(USART1, USART_IT_TXE, ENABLE);returntrue;}/** @brief 自串口读数据* @return 一字节数据*/uint8_t serial_read_ch(void){uint8_t ch;fifo_read_ch(&uart_rx_fifo,&ch);return ch;}/** @breif 检测发射缓冲区剩余字节长度* @return 剩余字节长度*/uint16_t serial_free(void){return fifo_free(&uart_tx_fifo);}uint16_t serial_available(void){return fifo_used(&uart_rx_fifo);}void USART1_IRQHandler(void){uint8_t c;if(USART_GetITStatus(USART1, USART_IT_RXNE)!= RESET)//数据接收终端{c = USART_ReceiveData(USART1);fifo_write_ch(&uart_rx_fifo, c);//USART_ITConfig(USART1, USART_IT_RXNE, DISABLE);}if(USART_GetITStatus(USART1, USART_IT_TXE)!= RESET)//数据发送中断{if(fifo_read_ch(&uart_tx_fifo,&c))USART_SendData(USART1, c);elseUSART_SendData(USART1,0x55);if(fifo_used(&uart_tx_fifo)==0)// Check if all data is transmitted . if yes disable transmitter UDRE interrupt{// Disable the EVAL_COM1 Transmit interruptUSART_ITConfig(USART1, USART_IT_TXE, DISABLE);}}}
2.在usart.c中屏蔽USART1_IRQHandler函数
usart.c全代码
#include"sys.h"//作者:恒久力行 qq:624668529#include"usart.h"////////////////////////////////////////////////////////////////////////////////////如果使用ucos,则包括下面的头文件即可.#if SYSTEM_SUPPORT_OS#include"includes.h"//ucos 使用#endif////////////////////////////////////////////////////////////////////////////////////本程序只供学习使用,未经作者许可,不得用于其它任何用途//ALIENTEK STM32F4探索者开发板//串口1初始化//正点原子@ALIENTEK//技术论坛:www.openedv.com//修改日期:2014/6/10//版本:V1.5//版权所有,盗版必究。//Copyright(C) 广州市星翼电子科技有限公司 2009-2019//All rights reserved//********************************************************************************//V1.3修改说明//支持适应不同频率下的串口波特率设置.//加入了对printf的支持//增加了串口接收命令功能.//修正了printf第一个字符丢失的bug//V1.4修改说明//1,修改串口初始化IO的bug//2,修改了USART_RX_STA,使得串口最大接收字节数为2的14次方//3,增加了USART_REC_LEN,用于定义串口最大允许接收的字节数(不大于2的14次方)//4,修改了EN_USART1_RX的使能方式//V1.5修改说明//1,增加了对UCOSII的支持//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////加入以下代码,支持printf函数,而不需要选择use MicroLIB#if 1#pragmaimport(__use_no_semihosting)//标准库需要的支持函数struct __FILE{int handle;};FILE __stdout;//定义_sys_exit()以避免使用半主机模式_sys_exit(int x){x = x;}//重定义fputc函数int fputc(int ch,FILE*f){while((USART1->SR&0X40)==0);//循环发送,直到发送完毕USART1->DR =(u8) ch;return ch;}#endif#if EN_USART1_RX //如果使能了接收//串口1中断服务程序//注意,读取USARTx->SR能避免莫名其妙的错误u8 USART_RX_BUF[USART_REC_LEN];//接收缓冲,最大USART_REC_LEN个字节.//接收状态//bit15, 接收完成标志//bit14, 接收到0x0d//bit13~0, 接收到的有效字节数目u16 USART_RX_STA=0;//接收状态标记//初始化IO 串口1//bound:波特率void uart_init(u32 bound){//GPIO端口设置GPIO_InitTypeDef GPIO_InitStructure;USART_InitTypeDef USART_InitStructure;NVIC_InitTypeDef NVIC_InitStructure;RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOA,ENABLE);//使能GPIOA时钟RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1,ENABLE);//使能USART1时钟//串口1对应引脚复用映射GPIO_PinAFConfig(GPIOA,GPIO_PinSource9,GPIO_AF_USART1);//GPIOA9复用为USART1GPIO_PinAFConfig(GPIOA,GPIO_PinSource10,GPIO_AF_USART1);//GPIOA10复用为USART1//USART1端口配置GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9 | GPIO_Pin_10;//GPIOA9与GPIOA10GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;//复用功能GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;//速度50MHzGPIO_InitStructure.GPIO_OType = GPIO_OType_PP;//推挽复用输出GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;//上拉GPIO_Init(GPIOA,&GPIO_InitStructure);//初始化PA9,PA10//USART1 初始化设置USART_InitStructure.USART_BaudRate = bound;//波特率设置USART_InitStructure.USART_WordLength = USART_WordLength_8b;//字长为8位数据格式USART_InitStructure.USART_StopBits = USART_StopBits_1;//一个停止位USART_InitStructure.USART_Parity = USART_Parity_No;//无奇偶校验位USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;//无硬件数据流控制USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;//收发模式USART_Init(USART1,&USART_InitStructure);//初始化串口1USART_Cmd(USART1, ENABLE);//使能串口1//USART_ClearFlag(USART1, USART_FLAG_TC);#if EN_USART1_RXUSART_ITConfig(USART1, USART_IT_RXNE, ENABLE);//开启相关中断//Usart1 NVIC 配置NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQn;//串口1中断通道NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority=3;//抢占优先级3NVIC_InitStructure.NVIC_IRQChannelSubPriority =3;//子优先级3NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;//IRQ通道使能NVIC_Init(&NVIC_InitStructure);//根据指定的参数初始化VIC寄存器、#endif}//void USART1_IRQHandler(void) //串口1中断服务程序//{// u8 Res;//#if SYSTEM_SUPPORT_OS //如果SYSTEM_SUPPORT_OS为真,则需要支持OS.// OSIntEnter();//#endif// if(USART_GetITStatus(USART1, USART_IT_RXNE) != RESET) //接收中断(接收到的数据必须是0x0d 0x0a结尾)// {// Res =USART_ReceiveData(USART1);//(USART1->DR); //读取接收到的数据//// if((USART_RX_STA&0x8000)==0)//接收未完成// {// if(USART_RX_STA&0x4000)//接收到了0x0d// {// if(Res!=0x0a)USART_RX_STA=0;//接收错误,重新开始// else USART_RX_STA|=0x8000; //接收完成了// }// else //还没收到0X0D// {// if(Res==0x0d)USART_RX_STA|=0x4000;// else// {// USART_RX_BUF[USART_RX_STA&0X3FFF]=Res ;// USART_RX_STA++;// if(USART_RX_STA>(USART_REC_LEN-1))USART_RX_STA=0;//接收数据错误,重新开始接收// }// }// }// }//#if SYSTEM_SUPPORT_OS //如果SYSTEM_SUPPORT_OS为真,则需要支持OS.// OSIntExit();//#endif//}#endif
3.添加mavlink_avoid_errors.h里面的代码如下,这个代码是用来避免错误的,跟mdk编译器相关的
/** @file mavlink_avoid_errors.h//作者:恒久力行 qq:624668529* @简介:本文件是由624668529添加,用来统一解决mavlink报错信息* @see QQ624668529*/#ifndef MAVLINK_AVOID_ERRORS_H#define MAVLINK_AVOID_ERRORS_H#include"stdio.h"#include"stdint.h"/*解决..\MAVLINK\common\../mavlink_types.h(53): error: #20: identifier "pack" is undefined*/#define MAVPACKED( __Declaration__ ) __Declaration__/*解决..\MAVLINK\common\../mavlink_types.h(53): error: #3092: anonymous unions are only supported in --gnu mode, or when enabled with #pragma anon_unions*/#pragma anon_unions#defineinline __inline//#ifndef memset//由624668529添加 2018-08-24//void *memset(void *dest, int data, size_t length) {// uint32_t i;// int *point = dest;// for(i=0; i<length; i++) point[i] = data;// return dest;//}//#endif//#ifndef memcpy//由624668529添加 2018-08-24//void *memcpy(void *dest, const void *src, size_t n)//{// unsigned char *pout = (unsigned char*)dest;// unsigned char *pin = (unsigned char*)src;// while (n-- > 0) *pout++ = *pin++;// return dest;//}//#endif#include"mavlink_types.h"#define MAVLINK_USE_CONVENIENCE_FUNCTIONS//#define MAVLINK_SEPARATE_HELPERS//mavlink_system_t mavlink_system = {0,0};//mavlink_system_t mavlink_system = {// 1,// 1//}; // System ID, 1-255, Component/Subsystem ID, 1-255//void comm_send_ch(mavlink_channel_t chan, uint8_t buf)//{// chan=chan;// USART_SendData(USART1, buf); //向串口1发送数据// while(USART_GetFlagStatus(USART1,USART_FLAG_TC)!=SET);//等待发送结束//}#include"mavlink.h"#include"mavlink_helpers.h"#endif//AVLINK_AVOID_ERRORS_H
4.添加open_tel_mavlink.h 和open_tel_mavlink.c 这两个函数是测试mavlink通信的上层代码
open_tel_mavlink.h
#ifndef __OPEN_TEL_MAVLINK_H//作者:恒久力行 qq:624668529#define __OPEN_TEL_MAVLINK_H//#include "./minimal/minimal/minimal.h"#include"define.h"#include"mavlink_avoid_errors.h"#include"stdint.h"void mavlink_send_message(mavlink_channel_t chan,enum ap_message id,uint16_t packet_drops);void update(void);void handleMessage(mavlink_message_t* msg);#endif/*__OPENTEL_MAVLINK_H*/
open_tel_mavlink.c
#include"open_tel_mavlink.h"//作者:恒久力行 qq:624668529////#include "mavlink_usart_fifo.h"//#include "mavlink_avoid_errors.h"//#include "mavlink_types.h"//#include "mavlink_avoid_errors.h"#include"define.h"#include"stdint.h"////Add By BigWtypedefuint8_tbool;//typedef struct {// char c;//} prog_char_t;//// This is the state of the flight control system// There are multiple states defined such as STABILIZE, ACRO,staticint8_t control_mode = STABILIZE;mavlink_channel_t chan;//uint16_t packet_drops;mavlink_heartbeat_t heartbeat;mavlink_attitude_t attitude;mavlink_global_position_int_t position;//mavlink_ahrs_t ahrs;uint8_t buf[100];////End Add By BigW//// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-// this costs us 51 bytes, but means that low priority// messages don't block the CPUstaticmavlink_statustext_t pending_status;// true when we have received at least 1 MAVLink packetstaticbool mavlink_active;// check if a message will fit in the payload space available#define CHECK_PAYLOAD_SIZE(id)if(payload_space < MAVLINK_MSG_ID_ ## id ## _LEN) return falsevoid handleMessage(mavlink_message_t* msg);/** !!NOTE!!** the use of NOINLINE separate functions for each message type avoids* a compiler bug in gcc that would cause it to use far more stack* space than is needed. Without the NOINLINE we use the sum of the* stack needed for each message type. Please be careful to follow the* pattern below when adding any new messages*/static NOINLINE void send_heartbeat(mavlink_channel_t chan){uint8_t base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;uint8_t system_status = MAV_STATE_ACTIVE;uint32_t custom_mode = control_mode;// work out the base_mode. This value is not very useful// for APM, but we calculate it as best we can so a generic// MAVLink enabled ground station can work out something about// what the MAV is up to. The actual bit values are highly// ambiguous for most of the APM flight modes. In practice, you// only get useful information from the custom_mode, which maps to// the APM flight mode and has a well defined meaning in the// ArduPlane documentationbase_mode = MAV_MODE_FLAG_STABILIZE_ENABLED;switch(control_mode){case AUTO:case RTL:case LOITER:case GUIDED:case CIRCLE:base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED;// note that MAV_MODE_FLAG_AUTO_ENABLED does not match what// APM does in any mode, as that is defined as "system finds its own goal// positions", which APM does not currently dobreak;}// all modes except INITIALISING have some form of manual// override if stick mixing is enabledbase_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;#if HIL_MODE != HIL_MODE_DISABLEDbase_mode |= MAV_MODE_FLAG_HIL_ENABLED;#endif// we are armed if we are not initialisingif(0){//motors.armed()) {base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;}// indicate we have set a custom modebase_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;mavlink_msg_heartbeat_send(chan,MAV_TYPE_QUADROTOR,MAV_AUTOPILOT_ARDUPILOTMEGA,base_mode,custom_mode,system_status);}static NOINLINE void send_attitude(mavlink_channel_t chan){mavlink_msg_attitude_send(chan,++buf[1],//millis(),++buf[2],//ahrs.roll,++buf[3],//ahrs.pitch,++buf[4],//ahrs.yaw,++buf[5],//omega.x,++buf[6],//omega.y,++buf[7]);//omega.z);}staticvoid NOINLINE send_location(mavlink_channel_t chan){//Matrix3f rot = ahrs.get_dcm_matrix(); // neglecting angle of attack for nowmavlink_msg_global_position_int_send(chan,1,//millis(),2,//current_loc.lat, // in 1E7 degrees3,//current_loc.lng, // in 1E7 degrees4,//g_gps->altitude * 10, // millimeters above sea level5,//(current_loc.alt - home.alt) * 10, // millimeters above ground6,//g_gps->ground_speed * rot.a.x, // X speed cm/s7,//g_gps->ground_speed * rot.b.x, // Y speed cm/s8,//g_gps->ground_speed * rot.c.x,9);//g_gps->ground_course); // course in 1/100 degree}//static void NOINLINE send_ahrs(mavlink_channel_t chan)//{// //Vector3f omega_I = ahrs.get_gyro_drift();// mavlink_msg_ahrs_send(// chan,// ++buf[8],//omega_I.x,// ++buf[9],//omega_I.y,// ++buf[10],//omega_I.z,// 1,// 0,// ++buf[11],//ahrs.get_error_rp(),// ++buf[12]);//ahrs.get_error_yaw());//}staticvoid NOINLINE send_statustext(mavlink_channel_t chan){}// are we still delaying telemetry to try to avoid Xbee bricking?staticbool telemetry_delayed(mavlink_channel_t chan){returnfalse;}// try to send a message, return false if it won't fit in the serial tx bufferstaticbool mavlink_try_send_message(mavlink_channel_t chan,enum ap_message id,uint16_t packet_drops){int16_t payload_space = serial_free();if(telemetry_delayed(chan)){returnfalse;}switch(id){case MSG_HEARTBEAT:CHECK_PAYLOAD_SIZE(HEARTBEAT);send_heartbeat(chan);break;case MSG_ATTITUDE:CHECK_PAYLOAD_SIZE(ATTITUDE);send_attitude(chan);break;case MSG_LOCATION:CHECK_PAYLOAD_SIZE(GLOBAL_POSITION_INT);send_location(chan);break;// case MSG_AHRS:// CHECK_PAYLOAD_SIZE(AHRS);// send_ahrs(chan);// break;case MSG_STATUSTEXT:CHECK_PAYLOAD_SIZE(STATUSTEXT);send_statustext(chan);break;default:break;}returntrue;}#define MAX_DEFERRED_MESSAGES MSG_RETRY_DEFERREDstaticstruct mavlink_queue {enum ap_message deferred_messages[MAX_DEFERRED_MESSAGES];uint8_t next_deferred_message;uint8_t num_deferred_messages;} mavlink_queue[2];// send a message using mavlinkvoid mavlink_send_message(mavlink_channel_t chan,enum ap_message id,uint16_t packet_drops){uint8_t i, nextid;struct mavlink_queue *q =&mavlink_queue[(uint8_t)chan];// see if we can send the deferred messages, if anywhile(q->num_deferred_messages !=0){if(!mavlink_try_send_message(chan,q->deferred_messages[q->next_deferred_message],packet_drops)){break;}q->next_deferred_message++;if(q->next_deferred_message == MAX_DEFERRED_MESSAGES){q->next_deferred_message =0;}q->num_deferred_messages--;}if(id == MSG_RETRY_DEFERRED){return;}// this message id might already be deferredfor(i=0, nextid = q->next_deferred_message; i < q->num_deferred_messages; i++){if(q->deferred_messages[nextid]== id){// its already deferred, discardreturn;}nextid++;if(nextid == MAX_DEFERRED_MESSAGES){nextid =0;}}if(q->num_deferred_messages !=0||!mavlink_try_send_message(chan, id, packet_drops)){// can't send it now, so defer itif(q->num_deferred_messages == MAX_DEFERRED_MESSAGES){// the defer buffer is full, discardreturn;}nextid = q->next_deferred_message + q->num_deferred_messages;if(nextid >= MAX_DEFERRED_MESSAGES){nextid -= MAX_DEFERRED_MESSAGES;}q->deferred_messages[nextid]= id;q->num_deferred_messages++;}}void mavlink_send_text(mavlink_channel_t chan,enum gcs_severity severity,char*str){if(telemetry_delayed(chan)){return;}if(severity == SEVERITY_LOW){// send via the deferred queuing systempending_status.severity =(uint8_t)severity;mav_array_memcpy((char*)pending_status.text, str,sizeof(pending_status.text));mavlink_send_message(chan, MSG_STATUSTEXT,0);}else{// send immediatelymavlink_msg_statustext_send(chan,severity,str);}}void update(void){// receive new packetsmavlink_message_t msg;mavlink_status_t status;status.packet_rx_drop_count =0;// process received byteswhile(serial_available()){uint8_t c = serial_read_ch();// Try to get a new messageif(mavlink_parse_char(chan, c,&msg,&status)){mavlink_active =true;//printf("%c",c);printf("Received message with ID %d, sequence: %d from component %d of system %d",\msg.msgid, msg.seq, msg.compid, msg.sysid);handleMessage(&msg);}}}void handleMessage(mavlink_message_t* msg){//struct Location tell_command = {}; // command for telemetryswitch(msg->msgid){case MAVLINK_MSG_ID_HEARTBEAT:{mavlink_msg_heartbeat_decode(msg,&heartbeat);break;}case MAVLINK_MSG_ID_ATTITUDE:{mavlink_msg_attitude_decode(msg,&attitude);break;}case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:{mavlink_msg_global_position_int_decode(msg,&position);break;}//// case MAVLINK_MSG_ID_AHRS: {// mavlink_msg_ahrs_decode(msg, &ahrs);// break;// }default:break;}// end switch}// end handle mavlink
5.添加define.h函数,这里是上层函数的一些结构类型定义,为避免上层报错就添加上(有兴趣的可以自己精简)
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-#ifndef _DEFINES_H//作者:恒久力行 qq:624668529#define _DEFINES_H// this avoids a very common config error#define ENABLE ENABLED#define DISABLE DISABLED// Flight modes// ------------#define YAW_HOLD 0#define YAW_ACRO 1#define YAW_AUTO 2#define YAW_LOOK_AT_HOME 3#define YAW_TOY 4// THOR This is the Yaw mode#define ROLL_PITCH_STABLE 0#define ROLL_PITCH_ACRO 1#define ROLL_PITCH_AUTO 2#define ROLL_PITCH_STABLE_OF 3#define ROLL_PITCH_TOY 4// THOR This is the Roll and Pitch// mode#define THROTTLE_MANUAL 0#define THROTTLE_HOLD 1#define THROTTLE_AUTO 2// active altitude sensor// ----------------------#define SONAR 0#define BARO 1#define SONAR_SOURCE_ADC 1#define SONAR_SOURCE_ANALOG_PIN 2// CH 7 control#define CH7_DO_NOTHING 0#define CH7_SET_HOVER 1#define CH7_FLIP 2#define CH7_SIMPLE_MODE 3#define CH7_RTL 4#define CH7_AUTO_TRIM 5#define CH7_ADC_FILTER 6#define CH7_SAVE_WP 7#define CH7_MULTI_MODE 8// Frame types#define QUAD_FRAME 0#define TRI_FRAME 1#define HEXA_FRAME 2#define Y6_FRAME 3#define OCTA_FRAME 4#define HELI_FRAME 5#define OCTA_QUAD_FRAME 6#define PLUS_FRAME 0#define X_FRAME 1#define V_FRAME 2// LED output#define NORMAL_LEDS 0#define AUTO_TRIM_LEDS 1#define CH_7_PWM_TRIGGER 1800#define CH_6_PWM_TRIGGER_HIGH 1800#define CH_6_PWM_TRIGGER 1500#define CH_6_PWM_TRIGGER_LOW 1200// Internal defines, don't edit and expect things to work// -------------------------------------------------------#define TRUE 1#define FALSE 0#defineToRad(x)(x*0.01745329252)// *pi/180#defineToDeg(x)(x*57.2957795131)// *180/pi#define DEBUG 0#define LOITER_RANGE 60// for calculating power outside of loiter radius#define T6 1000000#define T7 10000000// GPS type codes - use the names, not the numbers#define GPS_PROTOCOL_NONE -1#define GPS_PROTOCOL_NMEA 0#define GPS_PROTOCOL_SIRF 1#define GPS_PROTOCOL_UBLOX 2#define GPS_PROTOCOL_IMU 3#define GPS_PROTOCOL_MTK 4#define GPS_PROTOCOL_HIL 5#define GPS_PROTOCOL_MTK16 6#define GPS_PROTOCOL_AUTO 7#define CH_ROLL CH_1#define CH_PITCH CH_2#define CH_THROTTLE CH_3#define CH_RUDDER CH_4#define CH_YAW CH_4#define RC_CHANNEL_ANGLE 0#define RC_CHANNEL_RANGE 1#define RC_CHANNEL_ANGLE_RAW 2// HIL enumerations#define HIL_MODE_DISABLED 0#define HIL_MODE_ATTITUDE 1#define HIL_MODE_SENSORS 2#define ASCENDING 1#define DESCENDING -1#define REACHED_ALT 0// Auto Pilot modes// ----------------#define STABILIZE 0// hold level position#define ACRO 1// rate control#define ALT_HOLD 2// AUTO control#define AUTO 3// AUTO control#define GUIDED 4// AUTO control#define LOITER 5// Hold a single location#define RTL 6// AUTO control#define CIRCLE 7// AUTO control#define POSITION 8// AUTO control#define LAND 9// AUTO control#define OF_LOITER 10// Hold a single location using optical flow// sensor#define TOY_A 11// THOR Enum for Toy mode#define TOY_M 12// THOR Enum for Toy mode#define NUM_MODES 13#define SIMPLE_1 1#define SIMPLE_2 2#define SIMPLE_3 4#define SIMPLE_4 8#define SIMPLE_5 16#define SIMPLE_6 32// CH_6 Tuning// -----------#define CH6_NONE 0// Attitude#define CH6_STABILIZE_KP 1#define CH6_STABILIZE_KI 2#define CH6_STABILIZE_KD 29// duplicate with CH6_DAMP#define CH6_YAW_KP 3#define CH6_YAW_KI 24// Rate#define CH6_ACRO_KP 25#define CH6_RATE_KP 4#define CH6_RATE_KI 5#define CH6_RATE_KD 21#define CH6_YAW_RATE_KP 6#define CH6_YAW_RATE_KD 26// Altitude rate controller#define CH6_THROTTLE_KP 7// Extras#define CH6_TOP_BOTTOM_RATIO 8#define CH6_RELAY 9// Navigation#define CH6_TRAVERSE_SPEED 10// maximum speed to next way point#define CH6_NAV_KP 11#define CH6_LOITER_KP 12#define CH6_LOITER_KI 27// Trad Heli specific#define CH6_HELI_EXTERNAL_GYRO 13// altitude controller#define CH6_THR_HOLD_KP 14#define CH6_Z_GAIN 15#define CH6_DAMP 16// duplicate with CH6_YAW_RATE_KD// optical flow controller#define CH6_OPTFLOW_KP 17#define CH6_OPTFLOW_KI 18#define CH6_OPTFLOW_KD 19#define CH6_NAV_I 20#define CH6_LOITER_RATE_KP 22#define CH6_LOITER_RATE_KI 28#define CH6_LOITER_RATE_KD 23#define CH6_AHRS_YAW_KP 30#define CH6_AHRS_KP 31// nav byte mask// -------------#define NAV_LOCATION 1#define NAV_ALTITUDE 2#define NAV_DELAY 4// Commands - Note that APM now uses a subset of the MAVLink protocol// commands. See enum MAV_CMD in the GCS_Mavlink library#define CMD_BLANK 0// there is no command stored in the mem location// requested#define NO_COMMAND 0#define LOITER_MODE 1#define WP_MODE 2#define CIRCLE_MODE 3#define NO_NAV_MODE 4#define TOY_MODE 5// THOR This mode defines the Virtual// WP following mode// TOY mixing options#define TOY_LOOKUP_TABLE 0#define TOY_LINEAR_MIXER 1#define TOY_EXTERNAL_MIXER 2// Waypoint options#define MASK_OPTIONS_RELATIVE_ALT 1#define WP_OPTION_ALT_CHANGE 2#define WP_OPTION_YAW 4#define WP_OPTION_ALT_REQUIRED 8#define WP_OPTION_RELATIVE 16//#define WP_OPTION_ 32//#define WP_OPTION_ 64#define WP_OPTION_NEXT_CMD 128//repeating events#define NO_REPEAT 0#define CH_5_TOGGLE 1#define CH_6_TOGGLE 2#define CH_7_TOGGLE 3#define CH_8_TOGGLE 4#define RELAY_TOGGLE 5#define STOP_REPEAT 10// GCS Message ID's/// NOTE: to ensure we never block on sending MAVLink messages/// please keep each MSG_ to a single MAVLink message. If need be/// create new MSG_ IDs for additional messages on the same/// streamenum ap_message {MSG_HEARTBEAT,MSG_ATTITUDE,MSG_LOCATION,MSG_EXTENDED_STATUS1,MSG_EXTENDED_STATUS2,MSG_NAV_CONTROLLER_OUTPUT,MSG_CURRENT_WAYPOINT,MSG_VFR_HUD,MSG_RADIO_OUT,MSG_RADIO_IN,MSG_RAW_IMU1,MSG_RAW_IMU2,MSG_RAW_IMU3,MSG_GPS_STATUS,MSG_GPS_RAW,MSG_SERVO_OUT,MSG_NEXT_WAYPOINT,MSG_NEXT_PARAM,MSG_STATUSTEXT,MSG_LIMITS_STATUS,MSG_AHRS,MSG_SIMSTATE,MSG_HWSTATUS,MSG_RETRY_DEFERRED // this must be last};enum gcs_severity {SEVERITY_LOW=1,SEVERITY_MEDIUM,SEVERITY_HIGH,SEVERITY_CRITICAL};// Logging parameters#define TYPE_AIRSTART_MSG 0x00#define TYPE_GROUNDSTART_MSG 0x01#define LOG_ATTITUDE_MSG 0x01#define LOG_GPS_MSG 0x02#define LOG_MODE_MSG 0x03#define LOG_CONTROL_TUNING_MSG 0x04#define LOG_NAV_TUNING_MSG 0x05#define LOG_PERFORMANCE_MSG 0x06#define LOG_RAW_MSG 0x07#define LOG_CMD_MSG 0x08#define LOG_CURRENT_MSG 0x09#define LOG_STARTUP_MSG 0x0A#define LOG_MOTORS_MSG 0x0B#define LOG_OPTFLOW_MSG 0x0C#define LOG_DATA_MSG 0x0D#define LOG_PID_MSG 0x0E#define LOG_ITERM_MSG 0x0F#define LOG_DMP_MSG 0x10#define LOG_INDEX_MSG 0xF0#define MAX_NUM_LOGS 50#define MASK_LOG_ATTITUDE_FAST (1<<0)#define MASK_LOG_ATTITUDE_MED (1<<1)#define MASK_LOG_GPS (1<<2)#define MASK_LOG_PM (1<<3)#define MASK_LOG_CTUN (1<<4)#define MASK_LOG_NTUN (1<<5)#define MASK_LOG_MODE (1<<6)#define MASK_LOG_RAW (1<<7)#define MASK_LOG_CMD (1<<8)#define MASK_LOG_CUR (1<<9)#define MASK_LOG_MOTORS (1<<10)#define MASK_LOG_OPTFLOW (1<<11)#define MASK_LOG_PID (1<<12)#define MASK_LOG_ITERM (1<<13)// Waypoint Modes// ----------------#define ABS_WP 0#define REL_WP 1// Command Queues// ---------------#define COMMAND_MUST 0#define COMMAND_MAY 1#define COMMAND_NOW 2// Events// ------#define EVENT_WILL_REACH_WAYPOINT 1#define EVENT_SET_NEW_WAYPOINT_INDEX 2#define EVENT_LOADED_WAYPOINT 3#define EVENT_LOOP 4// Climb rate calculations#define ALTITUDE_HISTORY_LENGTH 8//Number of (time,altitude) points to// regress a climb rate from#define BATTERY_VOLTAGE(x)(x*(g.input_voltage/1024.0))*g.volt_div_ratio#define CURRENT_AMPS(x)((x*(g.input_voltage/1024.0))-CURR_AMPS_OFFSET)*g.curr_amp_per_volt//#define BARO_FILTER_SIZE 8/* ************************************************************** *//* Expansion PIN's that people can use for various things. */// AN0 - 7 are located at edge of IMU PCB "above" pressure sensor and// Expansion port// AN0 - 5 are also located next to voltage dividers and sliding SW2 switch// AN0 - 3 has 10kOhm resistor in serial, include 3.9kOhm to make it as// voltage divider// AN4 - 5 are direct GPIO pins from atmega1280 and they are the latest pins// next to SW2 switch// Look more ArduCopter Wiki for voltage dividers and other ports#define AN0 54// resistor, vdiv use, divider 1 closest to relay#define AN1 55// resistor, vdiv use, divider 2#define AN2 56// resistor, vdiv use, divider 3#define AN3 57// resistor, vdiv use, divider 4 closest to SW2#define AN4 58// direct GPIO pin, default as analog input, next to SW2// switch#define AN5 59// direct GPIO pin, default as analog input, next to SW2// switch#define AN6 60// direct GPIO pin, default as analog input, close to// Pressure sensor, Expansion Ports#define AN7 61// direct GPIO pin, default as analog input, close to// Pressure sensor, Expansion Ports// AN8 - 15 are located at edge of IMU PCB "above" pressure sensor and// Expansion port// AN8 - 15 PINs are not connected anywhere, they are located as last 8 pins// on edge of the board above Expansion Ports// even pins (8,10,12,14) are at edge of board, Odd pins (9,11,13,15) are on// inner row#define AN8 62// NC#define AN9 63// NC#define AN10 64// NC#define AN11 65// NC#define AN12 66// NC#define AN13 67// NC#define AN14 68// NC#define AN15 69// NC#define RELAY_PIN 47#define PIEZO_PIN AN5 //Last pin on the back ADC connector// sonar//#define SonarToCm(x) (x*1.26) // Sonar raw value to centimeters// RADIANS#define RADX100 0.000174532925#define DEGX100 5729.57795// EEPROM addresses#define EEPROM_MAX_ADDR 4096// parameters get the first 1536 bytes of EEPROM, remainder is for waypoints#define WP_START_BYTE 0x600// where in memory home WP is stored + all other// WP#define WP_SIZE 15#define ONBOARD_PARAM_NAME_LENGTH 15// fence points are stored at the end of the EEPROM#define MAX_FENCEPOINTS 6#define FENCE_WP_SIZE sizeof(Vector2l)#define FENCE_START_BYTE (EEPROM_MAX_ADDR-(MAX_FENCEPOINTS*FENCE_WP_SIZE))#define MAX_WAYPOINTS ((FENCE_START_BYTE - WP_START_BYTE)/ WP_SIZE)-1// -// 1// to// be// safe// mark a function as not to be inlined#define NOINLINE __attribute__((noinline))// IMU selection#define CONFIG_IMU_OILPAN 1#define CONFIG_IMU_MPU6000 2// APM Hardware selection#define APM_HARDWARE_APM1 1#define APM_HARDWARE_APM2 2#define AP_BARO_BMP085 1#define AP_BARO_MS5611 2#define LOGGING_SIMPLE 1#define LOGGING_VERBOSE 2// Channel Config selection#define CHANNEL_CONFIG_DEFAULT 1#define CHANNEL_CONFIG_CUSTOM 2#endif// _DEFINES_H//作者:恒久力行 qq:624668529
6.主函数也有更改这里是主函数代码
main.c
#include"sys.h"//作者:恒久力行 qq:624668529#include"delay.h"#include"usart.h"#include"led.h"#include"beep.h"#include"key.h"#include"mavlink_avoid_errors.h"#include"mavlink_usart_fifo.h"#include"open_tel_mavlink.h"//ALIENTEK 探索者STM32F407开发板 实验4//串口通信实验 -库函数版本//技术支持:www.openedv.com//淘宝店铺:http://eboard.taobao.com//广州市星翼电子科技有限公司//作者:正点原子 @ALIENTEKmavlink_system_t mavlink_system;#define UART_TX_BUFFER_SIZE 255#define UART_RX_BUFFER_SIZE 255externfifo_t uart_rx_fifo, uart_tx_fifo;externuint8_t uart_tx_buf[UART_TX_BUFFER_SIZE], uart_rx_buf[UART_RX_BUFFER_SIZE];int main(void){NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);//设置系统中断优先级分组2delay_init(168);//延时初始化uart_init(115200);//串口初始化波特率为115200LED_Init();//初始化与LED连接的硬件接口fifo_init(&uart_tx_fifo, uart_tx_buf, UART_TX_BUFFER_SIZE);fifo_init(&uart_rx_fifo, uart_rx_buf, UART_RX_BUFFER_SIZE);mavlink_system.sysid = MAV_TYPE_GENERIC;mavlink_system.compid = MAV_AUTOPILOT_GENERIC;while(1){mavlink_send_message(0, MSG_HEARTBEAT,0);mavlink_send_message(0, MSG_LOCATION,0);while(1){// if(tranlTimer > 100)// {// tranlTimer = 0;// mavlink_send_message(0, MSG_HEARTBEAT, 0);// mavlink_send_message(0, MSG_ATTITUDE, 0);// mavlink_send_message(0, MSG_AHRS, 0);// }update();}}}
7.mavlink_helpers.h在以前基础上增加如下代码(如有重复函数,请屏蔽以前的函数)
跟原来官方不同的还有MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t*buffer,constmavlink_message_t*msg)
这个函数参数定义到函数最前面了。全代码是修改后的,有兴趣的可以去比较。不修改的话会报错。
#include"mavlink_usart_fifo.h"externmavlink_system_t mavlink_system;MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan,constchar*buf,uint16_t len){serial_write_buf((uint8_t*)buf, len);}
mavlink_helpers.h全代码
#ifndef _MAVLINK_HELPERS_H_//作者:恒久力行 qq:624668529#define _MAVLINK_HELPERS_H_#include"string.h"#include"checksum.h"#include"mavlink_types.h"#include"mavlink_conversions.h"#ifndef MAVLINK_HELPER#define MAVLINK_HELPER#endifexternmavlink_system_t mavlink_system;/** Internal function to give access to the channel status for each channel*/#ifndef MAVLINK_GET_CHANNEL_STATUSMAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan){#ifdef MAVLINK_EXTERNAL_RX_STATUS// No m_mavlink_status array defined in function,// has to be defined externally#elsestaticmavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];#endifreturn&m_mavlink_status[chan];}#endif/** Internal function to give access to the channel buffer for each channel*/#ifndef MAVLINK_GET_CHANNEL_BUFFERMAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan){#ifdef MAVLINK_EXTERNAL_RX_BUFFER// No m_mavlink_buffer array defined in function,// has to be defined externally#elsestaticmavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];#endifreturn&m_mavlink_buffer[chan];}#endif/*** @brief Reset the status of a channel.*/MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan){mavlink_status_t*status = mavlink_get_channel_status(chan);status->parse_state = MAVLINK_PARSE_STATE_IDLE;}/*** @brief Finalize a MAVLink message with channel assignment** This function calculates the checksum and sets length and aircraft id correctly.* It assumes that the message id and the payload are already correctly set. This function* can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack* instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead.** @param msg Message to finalize* @param system_id Id of the sending (this) system, 1-127* @param length Message length*/#if MAVLINK_CRC_EXTRAMAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg,uint8_t system_id,uint8_t component_id,uint8_t chan,uint8_t min_length,uint8_t length,uint8_t crc_extra)#elseMAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg,uint8_t system_id,uint8_t component_id,uint8_t chan,uint8_t length)#endif{// This is only used for the v2 protocol and we silence it here(void)min_length;// This code part is the same for all messages;msg->magic = MAVLINK_STX;msg->len = length;msg->sysid = system_id;msg->compid = component_id;// One sequence number per channelmsg->seq = mavlink_get_channel_status(chan)->current_tx_seq;mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1;msg->checksum = crc_calculate(((constuint8_t*)(msg))+3, MAVLINK_CORE_HEADER_LEN);crc_accumulate_buffer(&msg->checksum, _MAV_PAYLOAD(msg), msg->len);#if MAVLINK_CRC_EXTRAcrc_accumulate(crc_extra,&msg->checksum);#endifmavlink_ck_a(msg)=(uint8_t)(msg->checksum &0xFF);mavlink_ck_b(msg)=(uint8_t)(msg->checksum >>8);return length + MAVLINK_NUM_NON_PAYLOAD_BYTES;}/*** @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel*/#if MAVLINK_CRC_EXTRAMAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg,uint8_t system_id,uint8_t component_id,uint8_t min_length,uint8_t length,uint8_t crc_extra){return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, min_length, length, crc_extra);}#elseMAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg,uint8_t system_id,uint8_t component_id,uint8_t length){return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length);}#endif#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONSMAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan,constchar*buf,uint16_t len);/*** @brief Finalize a MAVLink message with channel assignment and send*/#if MAVLINK_CRC_EXTRAMAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan,uint8_t msgid,constchar*packet,uint8_t min_length,uint8_t length,uint8_t crc_extra)#elseMAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan,uint8_t msgid,constchar*packet,uint8_t length)#endif{uint16_t checksum;uint8_t buf[MAVLINK_NUM_HEADER_BYTES];uint8_t ck[2];mavlink_status_t*status = mavlink_get_channel_status(chan);buf[0]= MAVLINK_STX;buf[1]= length;buf[2]= status->current_tx_seq;buf[3]= mavlink_system.sysid;buf[4]= mavlink_system.compid;buf[5]= msgid;status->current_tx_seq++;checksum = crc_calculate((constuint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN);crc_accumulate_buffer(&checksum, packet, length);#if MAVLINK_CRC_EXTRAcrc_accumulate(crc_extra,&checksum);#endifck[0]=(uint8_t)(checksum &0xFF);ck[1]=(uint8_t)(checksum >>8);MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES +(uint16_t)length);_mavlink_send_uart(chan,(constchar*)buf, MAVLINK_NUM_HEADER_BYTES);_mavlink_send_uart(chan, packet, length);_mavlink_send_uart(chan,(constchar*)ck,2);MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES +(uint16_t)length);}/*** @brief re-send a message over a uart channel* this is more stack efficient than re-marshalling the message*/MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan,constmavlink_message_t*msg){uint8_t ck[2];ck[0]=(uint8_t)(msg->checksum &0xFF);ck[1]=(uint8_t)(msg->checksum >>8);// XXX use the right sequence hereMAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len);_mavlink_send_uart(chan,(constchar*)&msg->magic, MAVLINK_NUM_HEADER_BYTES);_mavlink_send_uart(chan, _MAV_PAYLOAD(msg), msg->len);_mavlink_send_uart(chan,(constchar*)ck,2);MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len);}#endif// MAVLINK_USE_CONVENIENCE_FUNCTIONS/*** @brief Pack a message to send it over a serial byte stream*/MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t*buffer,constmavlink_message_t*msg){uint8_t*ck;memcpy(buffer,(constuint8_t*)&msg->magic, MAVLINK_NUM_HEADER_BYTES +(uint16_t)msg->len);ck = buffer +(MAVLINK_NUM_HEADER_BYTES +(uint16_t)msg->len);ck[0]=(uint8_t)(msg->checksum &0xFF);ck[1]=(uint8_t)(msg->checksum >>8);return MAVLINK_NUM_NON_PAYLOAD_BYTES +(uint16_t)msg->len;}union __mavlink_bitfield {uint8_tuint8;int8_tint8;uint16_tuint16;int16_tint16;uint32_tuint32;int32_tint32;};MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg){crc_init(&msg->checksum);}MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg,uint8_t c){crc_accumulate(c,&msg->checksum);}/*** This is a varient of mavlink_frame_char() but with caller supplied* parsing buffers. It is useful when you want to create a MAVLink* parser in a library that doesn't use any global variables** @param rxmsg parsing message buffer* @param status parsing starus buffer* @param c The char to parse** @param returnMsg NULL if no message could be decoded, the message data else* @param returnStats if a message was decoded, this is filled with the channel's stats* @return 0 if no message could be decoded, 1 on good message and CRC, 2 on bad CRC** A typical use scenario of this function call is:** @code* #include <mavlink.h>** mavlink_message_t msg;* int chan = 0;*** while(serial.bytesAvailable > 0)* {* uint8_t byte = serial.getNextByte();* if (mavlink_frame_char(chan, byte, &msg) != MAVLINK_FRAMING_INCOMPLETE)* {* printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid);* }* }*** @endcode*/MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg,mavlink_status_t* status,uint8_t c,mavlink_message_t* r_message,mavlink_status_t* r_mavlink_status){/*default message crc function. You can override this per-system toput this data in a different memory segment*/#if MAVLINK_CRC_EXTRA#ifndef MAVLINK_MESSAGE_CRCstaticconstuint8_t mavlink_message_crcs[256]= MAVLINK_MESSAGE_CRCS;#define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid]#endif#endif/* Enable this option to check the length of each message.This allows invalid messages to be caught much sooner. Use if the transmissionmedium is prone to missing (or extra) characters (e.g. a radio that fades inand out). Only use if the channel will only contain messages types listed inthe headers.*/#ifdef MAVLINK_CHECK_MESSAGE_LENGTH#ifndef MAVLINK_MESSAGE_LENGTHstaticconstuint8_t mavlink_message_lengths[256]= MAVLINK_MESSAGE_LENGTHS;#define MAVLINK_MESSAGE_LENGTH(msgid) mavlink_message_lengths[msgid]#endif#endifint bufferIndex =0;status->msg_received = MAVLINK_FRAMING_INCOMPLETE;switch(status->parse_state){case MAVLINK_PARSE_STATE_UNINIT:case MAVLINK_PARSE_STATE_IDLE:if(c == MAVLINK_STX){status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;rxmsg->len =0;rxmsg->magic = c;mavlink_start_checksum(rxmsg);}break;case MAVLINK_PARSE_STATE_GOT_STX:if(status->msg_received/* Support shorter buffers than thedefault maximum packet size */#if (MAVLINK_MAX_PAYLOAD_LEN < 255)|| c > MAVLINK_MAX_PAYLOAD_LEN#endif){status->buffer_overrun++;status->parse_error++;status->msg_received =0;status->parse_state = MAVLINK_PARSE_STATE_IDLE;}else{// NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2rxmsg->len = c;status->packet_idx =0;mavlink_update_checksum(rxmsg, c);status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH;}break;case MAVLINK_PARSE_STATE_GOT_LENGTH:rxmsg->seq = c;mavlink_update_checksum(rxmsg, c);status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ;break;case MAVLINK_PARSE_STATE_GOT_SEQ:rxmsg->sysid = c;mavlink_update_checksum(rxmsg, c);status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID;break;case MAVLINK_PARSE_STATE_GOT_SYSID:rxmsg->compid = c;mavlink_update_checksum(rxmsg, c);status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID;break;case MAVLINK_PARSE_STATE_GOT_COMPID:#ifdef MAVLINK_CHECK_MESSAGE_LENGTHif(rxmsg->len != MAVLINK_MESSAGE_LENGTH(c)){status->parse_error++;status->parse_state = MAVLINK_PARSE_STATE_IDLE;break;}#endifrxmsg->msgid = c;mavlink_update_checksum(rxmsg, c);if(rxmsg->len ==0){status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;}else{status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID;}break;case MAVLINK_PARSE_STATE_GOT_MSGID:_MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++]=(char)c;mavlink_update_checksum(rxmsg, c);if(status->packet_idx == rxmsg->len){status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;}break;case MAVLINK_PARSE_STATE_GOT_PAYLOAD:#if MAVLINK_CRC_EXTRAmavlink_update_checksum(rxmsg, MAVLINK_MESSAGE_CRC(rxmsg->msgid));#endifif(c !=(rxmsg->checksum &0xFF)){status->parse_state = MAVLINK_PARSE_STATE_GOT_BAD_CRC1;}else{status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1;}_MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx]=(char)c;break;case MAVLINK_PARSE_STATE_GOT_CRC1:case MAVLINK_PARSE_STATE_GOT_BAD_CRC1:if(status->parse_state == MAVLINK_PARSE_STATE_GOT_BAD_CRC1 || c !=(rxmsg->checksum >>8)){// got a bad CRC messagestatus->msg_received = MAVLINK_FRAMING_BAD_CRC;}else{// Successfully got messagestatus->msg_received = MAVLINK_FRAMING_OK;}status->parse_state = MAVLINK_PARSE_STATE_IDLE;_MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx+1]=(char)c;memcpy(r_message, rxmsg,sizeof(mavlink_message_t));break;}bufferIndex++;// If a message has been sucessfully decoded, check indexif(status->msg_received == MAVLINK_FRAMING_OK){//while(status->current_seq != rxmsg->seq)//{// status->packet_rx_drop_count++;// status->current_seq++;//}status->current_rx_seq = rxmsg->seq;// Initial condition: If no packet has been received so far, drop count is undefinedif(status->packet_rx_success_count ==0) status->packet_rx_drop_count =0;// Count this packet as receivedstatus->packet_rx_success_count++;}r_message->len = rxmsg->len;// Provide visibility on how far we are into current msgr_mavlink_status->parse_state = status->parse_state;r_mavlink_status->packet_idx = status->packet_idx;r_mavlink_status->current_rx_seq = status->current_rx_seq+1;r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count;r_mavlink_status->packet_rx_drop_count = status->parse_error;status->parse_error =0;if(status->msg_received == MAVLINK_FRAMING_BAD_CRC){/*the CRC came out wrong. We now need to overwrite themsg CRC with the one on the wire so that if thecaller decides to forward the message anyway thatmavlink_msg_to_send_buffer() won't overwrite thechecksum*/r_message->checksum = _MAV_PAYLOAD(rxmsg)[status->packet_idx]|(_MAV_PAYLOAD(rxmsg)[status->packet_idx+1]<<8);}return status->msg_received;}/*** This is a convenience function which handles the complete MAVLink parsing.* the function will parse one byte at a time and return the complete packet once* it could be successfully decoded. This function will return 0, 1 or* 2 (MAVLINK_FRAMING_INCOMPLETE, MAVLINK_FRAMING_OK or MAVLINK_FRAMING_BAD_CRC)** Messages are parsed into an internal buffer (one for each channel). When a complete* message is received it is copies into *returnMsg and the channel's status is* copied into *returnStats.** @param chan ID of the current channel. This allows to parse different channels with this function.* a channel is not a physical message channel like a serial port, but a logic partition of* the communication streams in this case. COMM_NB is the limit for the number of channels* on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows* @param c The char to parse** @param returnMsg NULL if no message could be decoded, the message data else* @param returnStats if a message was decoded, this is filled with the channel's stats* @return 0 if no message could be decoded, 1 on good message and CRC, 2 on bad CRC** A typical use scenario of this function call is:** @code* #include <mavlink.h>** mavlink_message_t msg;* int chan = 0;*** while(serial.bytesAvailable > 0)* {* uint8_t byte = serial.getNextByte();* if (mavlink_frame_char(chan, byte, &msg) != MAVLINK_FRAMING_INCOMPLETE)* {* printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid);* }* }*** @endcode*/MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan,uint8_t c,mavlink_message_t* r_message,mavlink_status_t* r_mavlink_status){return mavlink_frame_char_buffer(mavlink_get_channel_buffer(chan),mavlink_get_channel_status(chan),c,r_message,r_mavlink_status);}/*** This is a convenience function which handles the complete MAVLink parsing.* the function will parse one byte at a time and return the complete packet once* it could be successfully decoded. This function will return 0 or 1.** Messages are parsed into an internal buffer (one for each channel). When a complete* message is received it is copies into *returnMsg and the channel's status is* copied into *returnStats.** @param chan ID of the current channel. This allows to parse different channels with this function.* a channel is not a physical message channel like a serial port, but a logic partition of* the communication streams in this case. COMM_NB is the limit for the number of channels* on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows* @param c The char to parse** @param returnMsg NULL if no message could be decoded, the message data else* @param returnStats if a message was decoded, this is filled with the channel's stats* @return 0 if no message could be decoded or bad CRC, 1 on good message and CRC** A typical use scenario of this function call is:** @code* #include <mavlink.h>** mavlink_message_t msg;* int chan = 0;*** while(serial.bytesAvailable > 0)* {* uint8_t byte = serial.getNextByte();* if (mavlink_parse_char(chan, byte, &msg))* {* printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid);* }* }*** @endcode*/MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan,uint8_t c,mavlink_message_t* r_message,mavlink_status_t* r_mavlink_status){uint8_t msg_received = mavlink_frame_char(chan, c, r_message, r_mavlink_status);if(msg_received == MAVLINK_FRAMING_BAD_CRC){// we got a bad CRC. Treat as a parse failuremavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan);mavlink_status_t* status = mavlink_get_channel_status(chan);status->parse_error++;status->msg_received = MAVLINK_FRAMING_INCOMPLETE;status->parse_state = MAVLINK_PARSE_STATE_IDLE;if(c == MAVLINK_STX){status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;rxmsg->len =0;mavlink_start_checksum(rxmsg);}return0;}return msg_received;}/*** @brief Put a bitfield of length 1-32 bit into the buffer** @param b the value to add, will be encoded in the bitfield* @param bits number of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc.* @param packet_index the position in the packet (the index of the first byte to use)* @param bit_index the position in the byte (the index of the first bit to use)* @param buffer packet buffer to write into* @return new position of the last used byte in the buffer*/MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b,uint8_t bits,uint8_t packet_index,uint8_t bit_index,uint8_t* r_bit_index,uint8_t* buffer){uint16_t bits_remain = bits;// Transform number into network orderint32_t v;uint8_t i_bit_index, i_byte_index, curr_bits_n;#if MAVLINK_NEED_BYTE_SWAPunion{int32_t i;uint8_t b[4];} bin, bout;bin.i = b;bout.b[0]= bin.b[3];bout.b[1]= bin.b[2];bout.b[2]= bin.b[1];bout.b[3]= bin.b[0];v = bout.i;#elsev = b;#endif// buffer in// 01100000 01000000 00000000 11110001// buffer out// 11110001 00000000 01000000 01100000// Existing partly filled byte (four free slots)// 0111xxxx// Mask n free bits// 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1// = ((uint32_t)(1 << n)) - 1; // = 2^n - 1// Shift n bits into the right position// out = in >> n;// Mask and shift bytesi_bit_index = bit_index;i_byte_index = packet_index;if(bit_index >0){// If bits were available at start, they were available// in the byte before the current indexi_byte_index--;}// While bits have not been packed yetwhile(bits_remain >0){// Bits still have to be packed// there can be more than 8 bits, so// we might have to pack them into more than one byte// First pack everything we can into the current 'open' byte//curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8//FIXMEif(bits_remain <=(uint8_t)(8- i_bit_index)){// Enough spacecurr_bits_n =(uint8_t)bits_remain;}else{curr_bits_n =(8- i_bit_index);}// Pack these n bits into the current byte// Mask out whatever was at that position with ones (xxx11111)buffer[i_byte_index]&=(0xFF>>(8- curr_bits_n));// Put content to this position, by masking out the non-used partbuffer[i_byte_index]|=((0x00<< curr_bits_n)& v);// Increment the bit indexi_bit_index += curr_bits_n;// Now proceed to the next byte, if necessarybits_remain -= curr_bits_n;if(bits_remain >0){// Offer another 8 bits / one bytei_byte_index++;i_bit_index =0;}}*r_bit_index = i_bit_index;// If a partly filled byte is present, mark this as consumedif(i_bit_index !=7) i_byte_index++;return i_byte_index - packet_index;}#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS// To make MAVLink work on your MCU, define comm_send_ch() if you wish// to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a// whole packet at a time/*#include "mavlink_types.h"void comm_send_ch(mavlink_channel_t chan, uint8_t ch){if (chan == MAVLINK_COMM_0){uart0_transmit(ch);}if (chan == MAVLINK_COMM_1){uart1_transmit(ch);}}*/#include"mavlink_usart_fifo.h"MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan,constchar*buf,uint16_t len){serial_write_buf((uint8_t*)buf, len);}//MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len)//{//#ifdef MAVLINK_SEND_UART_BYTES// /* this is the more efficient approach, if the platform// defines it */// MAVLINK_SEND_UART_BYTES(chan, (const uint8_t *)buf, len);//#else// /* fallback to one byte at a time */// uint16_t i;// for (i = 0; i < len; i++) {// comm_send_ch(chan, (uint8_t)buf[i]);// }//#endif//}#endif// MAVLINK_USE_CONVENIENCE_FUNCTIONS#endif/* _MAVLINK_HELPERS_H_ */
8.checksum未经任何修改(为了大家方便看附上全代码)
checksum.h
#ifdef __cplusplus//作者:恒久力行 qq:624668529extern"C"{#endif#ifndef _CHECKSUM_H_#define _CHECKSUM_H_// Visual Studio versions before 2010 don't have stdint.h, so we just error out.#if (defined _MSC_VER) && (_MSC_VER < 1600)#error"The C-MAVLink implementation requires Visual Studio 2010 or greater"#endif#include<stdint.h>/**** CALCULATE THE CHECKSUM**/#define X25_INIT_CRC 0xffff#define X25_VALIDATE_CRC 0xf0b8#ifndef HAVE_CRC_ACCUMULATE/*** @brief Accumulate the X.25 CRC by adding one char at a time.** The checksum function adds the hash of one char at a time to the* 16 bit checksum (uint16_t).** @param data new char to hash* @param crcAccum the already accumulated checksum**/staticinlinevoid crc_accumulate(uint8_t data,uint16_t*crcAccum){/*Accumulate one byte of data into the CRC*/uint8_t tmp;tmp = data ^(uint8_t)(*crcAccum &0xff);tmp ^=(tmp<<4);*crcAccum =(*crcAccum>>8)^(tmp<<8)^(tmp <<3)^(tmp>>4);}#endif/*** @brief Initiliaze the buffer for the X.25 CRC** @param crcAccum the 16 bit X.25 CRC*/staticinlinevoid crc_init(uint16_t* crcAccum){*crcAccum = X25_INIT_CRC;}/*** @brief Calculates the X.25 checksum on a byte buffer** @param pBuffer buffer containing the byte array to hash* @param length length of the byte array* @return the checksum over the buffer bytes**/staticinlineuint16_t crc_calculate(constuint8_t* pBuffer,uint16_t length){uint16_t crcTmp;crc_init(&crcTmp);while(length--){crc_accumulate(*pBuffer++,&crcTmp);}return crcTmp;}/*** @brief Accumulate the X.25 CRC by adding an array of bytes** The checksum function adds the hash of one char at a time to the* 16 bit checksum (uint16_t).** @param data new bytes to hash* @param crcAccum the already accumulated checksum**/staticinlinevoid crc_accumulate_buffer(uint16_t*crcAccum,constchar*pBuffer,uint16_t length){constuint8_t*p =(constuint8_t*)pBuffer;while(length--){crc_accumulate(*p++, crcAccum);}}#endif/* _CHECKSUM_H_ */#ifdef __cplusplus}#endif
9.mavlink_conversions.h修改了一个地方就是将参数定义提到前面了
(就是这个函数MAVLINK_HELPER void mavlink_dcm_to_quaternion(constfloat dcm[3][3],float quaternion[4])
mavlink_conversions.h全代码
#ifndef _MAVLINK_CONVERSIONS_H_//作者:恒久力行 qq:624668529#define _MAVLINK_CONVERSIONS_H_/* enable math defines on Windows */#ifdef _MSC_VER#ifndef _USE_MATH_DEFINES#define _USE_MATH_DEFINES#endif#endif#include<math.h>#ifndef M_PI_2#define M_PI_2 ((float)asin(1))#endif/*** @file mavlink_conversions.h** These conversion functions follow the NASA rotation standards definition file* available online.** Their intent is to lower the barrier for MAVLink adopters to use gimbal-lock free* (both rotation matrices, sometimes called DCM, and quaternions are gimbal-lock free)* rotation representations. Euler angles (roll, pitch, yaw) will be phased out of the* protocol as widely as possible.** @author James Goppert* @author Thomas Gubler <thomasgubler@gmail.com>*//*** Converts a quaternion to a rotation matrix** @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)* @param dcm a 3x3 rotation matrix*/MAVLINK_HELPER void mavlink_quaternion_to_dcm(constfloat quaternion[4],float dcm[3][3]){double a = quaternion[0];double b = quaternion[1];double c = quaternion[2];double d = quaternion[3];double aSq = a * a;double bSq = b * b;double cSq = c * c;double dSq = d * d;dcm[0][0]= aSq + bSq - cSq - dSq;dcm[0][1]=2*(b * c - a * d);dcm[0][2]=2*(a * c + b * d);dcm[1][0]=2*(b * c + a * d);dcm[1][1]= aSq - bSq + cSq - dSq;dcm[1][2]=2*(c * d - a * b);dcm[2][0]=2*(b * d - a * c);dcm[2][1]=2*(a * b + c * d);dcm[2][2]= aSq - bSq - cSq + dSq;}/*** Converts a rotation matrix to euler angles** @param dcm a 3x3 rotation matrix* @param roll the roll angle in radians* @param pitch the pitch angle in radians* @param yaw the yaw angle in radians*/MAVLINK_HELPER void mavlink_dcm_to_euler(constfloat dcm[3][3],float* roll,float* pitch,float* yaw){float phi, theta, psi;theta = asin(-dcm[2][0]);if(fabsf(theta -(float)M_PI_2)<1.0e-3f){phi =0.0f;psi =(atan2f(dcm[1][2]- dcm[0][1],dcm[0][2]+ dcm[1][1])+ phi);}elseif(fabsf(theta +(float)M_PI_2)<1.0e-3f){phi =0.0f;psi = atan2f(dcm[1][2]- dcm[0][1],dcm[0][2]+ dcm[1][1]- phi);}else{phi = atan2f(dcm[2][1], dcm[2][2]);psi = atan2f(dcm[1][0], dcm[0][0]);}*roll = phi;*pitch = theta;*yaw = psi;}/*** Converts a quaternion to euler angles** @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)* @param roll the roll angle in radians* @param pitch the pitch angle in radians* @param yaw the yaw angle in radians*/MAVLINK_HELPER void mavlink_quaternion_to_euler(constfloat quaternion[4],float* roll,float* pitch,float* yaw){float dcm[3][3];mavlink_quaternion_to_dcm(quaternion, dcm);mavlink_dcm_to_euler((constfloat(*)[3])dcm, roll, pitch, yaw);}/*** Converts euler angles to a quaternion** @param roll the roll angle in radians* @param pitch the pitch angle in radians* @param yaw the yaw angle in radians* @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)*/MAVLINK_HELPER void mavlink_euler_to_quaternion(float roll,float pitch,float yaw,float quaternion[4]){float cosPhi_2 = cosf(roll /2);float sinPhi_2 = sinf(roll /2);float cosTheta_2 = cosf(pitch /2);float sinTheta_2 = sinf(pitch /2);float cosPsi_2 = cosf(yaw /2);float sinPsi_2 = sinf(yaw /2);quaternion[0]=(cosPhi_2 * cosTheta_2 * cosPsi_2 +sinPhi_2 * sinTheta_2 * sinPsi_2);quaternion[1]=(sinPhi_2 * cosTheta_2 * cosPsi_2 -cosPhi_2 * sinTheta_2 * sinPsi_2);quaternion[2]=(cosPhi_2 * sinTheta_2 * cosPsi_2 +sinPhi_2 * cosTheta_2 * sinPsi_2);quaternion[3]=(cosPhi_2 * cosTheta_2 * sinPsi_2 -sinPhi_2 * sinTheta_2 * cosPsi_2);}/*** Converts a rotation matrix to a quaternion* Reference:* - Shoemake, Quaternions,* http://www.cs.ucr.edu/~vbz/resources/quatut.pdf** @param dcm a 3x3 rotation matrix* @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)*/MAVLINK_HELPER void mavlink_dcm_to_quaternion(constfloat dcm[3][3],float quaternion[4]){int dcm_j,dcm_k;float s;float tr = dcm[0][0]+ dcm[1][1]+ dcm[2][2];if(tr >0.0f){float s = sqrtf(tr +1.0f);quaternion[0]= s *0.5f;s =0.5f/ s;quaternion[1]=(dcm[2][1]- dcm[1][2])* s;quaternion[2]=(dcm[0][2]- dcm[2][0])* s;quaternion[3]=(dcm[1][0]- dcm[0][1])* s;}else{/* Find maximum diagonal element in dcm* store index in dcm_i */int dcm_i =0;int i;for(i =1; i <3; i++){if(dcm[i][i]> dcm[dcm_i][dcm_i]){dcm_i = i;}}dcm_j =(dcm_i +1)%3;dcm_k =(dcm_i +2)%3;s = sqrtf((dcm[dcm_i][dcm_i]- dcm[dcm_j][dcm_j]-dcm[dcm_k][dcm_k])+1.0f);quaternion[dcm_i +1]= s *0.5f;s =0.5f/ s;quaternion[dcm_j +1]=(dcm[dcm_i][dcm_j]+ dcm[dcm_j][dcm_i])* s;quaternion[dcm_k +1]=(dcm[dcm_k][dcm_i]+ dcm[dcm_i][dcm_k])* s;quaternion[0]=(dcm[dcm_k][dcm_j]- dcm[dcm_j][dcm_k])* s;}}/*** Converts euler angles to a rotation matrix** @param roll the roll angle in radians* @param pitch the pitch angle in radians* @param yaw the yaw angle in radians* @param dcm a 3x3 rotation matrix*/MAVLINK_HELPER void mavlink_euler_to_dcm(float roll,float pitch,float yaw,float dcm[3][3]){float cosPhi = cosf(roll);float sinPhi = sinf(roll);float cosThe = cosf(pitch);float sinThe = sinf(pitch);float cosPsi = cosf(yaw);float sinPsi = sinf(yaw);dcm[0][0]= cosThe * cosPsi;dcm[0][1]=-cosPhi * sinPsi + sinPhi * sinThe * cosPsi;dcm[0][2]= sinPhi * sinPsi + cosPhi * sinThe * cosPsi;dcm[1][0]= cosThe * sinPsi;dcm[1][1]= cosPhi * cosPsi + sinPhi * sinThe * sinPsi;dcm[1][2]=-sinPhi * cosPsi + cosPhi * sinThe * sinPsi;dcm[2][0]=-sinThe;dcm[2][1]= sinPhi * cosThe;dcm[2][2]= cosPhi * cosThe;}#endif
10.mavlink_types.h跟源代码相比较屏蔽了下面这段代码
(关于MAVPACKED相关定义在mavlink_avoid_errors.h中)
// Macro to define packed structures//#ifdef __GNUC__// #define MAVPACKED( __Declaration__ ) __Declaration__ __attribute__((packed))//#else// #define MAVPACKED( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) )//#endif
mavlink_types.h全代码
#ifndef MAVLINK_TYPES_H_#define MAVLINK_TYPES_H_// Visual Studio versions before 2010 don't have stdint.h, so we just error out.#if (defined _MSC_VER) && (_MSC_VER < 1600)#error"The C-MAVLink implementation requires Visual Studio 2010 or greater"#endif#include<stdint.h>// Macro to define packed structures//#ifdef __GNUC__// #define MAVPACKED( __Declaration__ ) __Declaration__ __attribute__((packed))//#else// #define MAVPACKED( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) )//#endif#ifndef MAVLINK_MAX_PAYLOAD_LEN// it is possible to override this, but be careful!#define MAVLINK_MAX_PAYLOAD_LEN 255///< Maximum payload length#endif#define MAVLINK_CORE_HEADER_LEN 5///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte)#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN +1)///< Length of all header bytes, including core and checksum#define MAVLINK_NUM_CHECKSUM_BYTES 2#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES)#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES)///< Maximum packet length#define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255#define MAVLINK_EXTENDED_HEADER_LEN 14#if (defined _MSC_VER) || ((defined __APPLE__) && (defined __MACH__)) || (defined __linux__)/* full fledged 32bit++ OS */#define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507#else/* small microcontrollers */#define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048#endif#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES)/*** Old-style 4 byte param union** This struct is the data format to be used when sending* parameters. The parameter should be copied to the native* type (without type conversion)* and re-instanted on the receiving side using the* native type as well.*/MAVPACKED(typedefstruct param_union {union{float param_float;int32_t param_int32;uint32_t param_uint32;int16_t param_int16;uint16_t param_uint16;int8_t param_int8;uint8_t param_uint8;uint8_t bytes[4];};uint8_t type;})mavlink_param_union_t;/*** New-style 8 byte param union* mavlink_param_union_double_t will be 8 bytes long, and treated as needing 8 byte alignment for the purposes of MAVLink 1.0 field ordering.* The mavlink_param_union_double_t will be treated as a little-endian structure.** If is_double is 1 then the type is a double, and the remaining 63 bits are the double, with the lowest bit of the mantissa zero.* The intention is that by replacing the is_double bit with 0 the type can be directly used as a double (as the is_double bit corresponds to the* lowest mantissa bit of a double). If is_double is 0 then mavlink_type gives the type in the union.* The mavlink_types.h header will also need to have shifts/masks to define the bit boundaries in the above,* as bitfield ordering isn’t consistent between platforms. The above is intended to be for gcc on x86,* which should be the same as gcc on little-endian arm. When using shifts/masks the value will be treated as a 64 bit unsigned number,* and the bits pulled out using the shifts/masks.*/MAVPACKED(typedefstruct param_union_extended {union{struct{uint8_t is_double:1;uint8_t mavlink_type:7;union{char c;uint8_tuint8;int8_tint8;uint16_tuint16;int16_tint16;uint32_tuint32;int32_tint32;float f;uint8_t align[7];};};uint8_t data[8];};})mavlink_param_union_double_t;/*** This structure is required to make the mavlink_send_xxx convenience functions* work, as it tells the library what the current system and component ID are.*/MAVPACKED(typedefstruct __mavlink_system {uint8_t sysid;///< Used by the MAVLink message_xx_send() convenience functionuint8_t compid;///< Used by the MAVLink message_xx_send() convenience function})mavlink_system_t;MAVPACKED(typedefstruct __mavlink_message {uint16_t checksum;///< sent at end of packetuint8_t magic;///< protocol magic markeruint8_t len;///< Length of payloaduint8_t seq;///< Sequence of packetuint8_t sysid;///< ID of message sender system/aircraftuint8_t compid;///< ID of the message sender componentuint8_t msgid;///< ID of message in payloaduint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];})mavlink_message_t;MAVPACKED(typedefstruct __mavlink_extended_message {mavlink_message_t base_msg;int32_t extended_payload_len;///< Length of extended payload if anyuint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN];})mavlink_extended_message_t;typedefenum{MAVLINK_TYPE_CHAR =0,MAVLINK_TYPE_UINT8_T =1,MAVLINK_TYPE_INT8_T =2,MAVLINK_TYPE_UINT16_T =3,MAVLINK_TYPE_INT16_T =4,MAVLINK_TYPE_UINT32_T =5,MAVLINK_TYPE_INT32_T =6,MAVLINK_TYPE_UINT64_T =7,MAVLINK_TYPE_INT64_T =8,MAVLINK_TYPE_FLOAT =9,MAVLINK_TYPE_DOUBLE =10}mavlink_message_type_t;#define MAVLINK_MAX_FIELDS 64typedefstruct __mavlink_field_info {constchar*name;// name of this fieldconstchar*print_format;// printing format hint, or NULLmavlink_message_type_t type;// type of this fieldunsignedint array_length;// if non-zero, field is an arrayunsignedint wire_offset;// offset of each field in the payloadunsignedint structure_offset;// offset in a C structure}mavlink_field_info_t;// note that in this structure the order of fields is the order// in the XML file, not necessary the wire ordertypedefstruct __mavlink_message_info {constchar*name;// name of the messageunsigned num_fields;// how many fields in this messagemavlink_field_info_t fields[MAVLINK_MAX_FIELDS];// field information}mavlink_message_info_t;#define _MAV_PAYLOAD(msg)((constchar*)(&((msg)->payload64[0])))#define _MAV_PAYLOAD_NON_CONST(msg)((char*)(&((msg)->payload64[0])))// checksum is immediately after the payload bytes#define mavlink_ck_a(msg)*((msg)->len +(uint8_t*)_MAV_PAYLOAD_NON_CONST(msg))#define mavlink_ck_b(msg)*(((msg)->len+(uint16_t)1)+(uint8_t*)_MAV_PAYLOAD_NON_CONST(msg))typedefenum{MAVLINK_COMM_0,MAVLINK_COMM_1,MAVLINK_COMM_2,MAVLINK_COMM_3}mavlink_channel_t;/** applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number* of buffers they will use. If more are used, then the result will be* a stack overrun*/#ifndef MAVLINK_COMM_NUM_BUFFERS#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32)# define MAVLINK_COMM_NUM_BUFFERS 16#else# define MAVLINK_COMM_NUM_BUFFERS 4#endif#endiftypedefenum{MAVLINK_PARSE_STATE_UNINIT=0,MAVLINK_PARSE_STATE_IDLE,MAVLINK_PARSE_STATE_GOT_STX,MAVLINK_PARSE_STATE_GOT_SEQ,MAVLINK_PARSE_STATE_GOT_LENGTH,MAVLINK_PARSE_STATE_GOT_SYSID,MAVLINK_PARSE_STATE_GOT_COMPID,MAVLINK_PARSE_STATE_GOT_MSGID,MAVLINK_PARSE_STATE_GOT_PAYLOAD,MAVLINK_PARSE_STATE_GOT_CRC1,MAVLINK_PARSE_STATE_GOT_BAD_CRC1}mavlink_parse_state_t;///< The state machine for the comm parsertypedefenum{MAVLINK_FRAMING_INCOMPLETE=0,MAVLINK_FRAMING_OK=1,MAVLINK_FRAMING_BAD_CRC=2}mavlink_framing_t;typedefstruct __mavlink_status {uint8_t msg_received;///< Number of received messagesuint8_t buffer_overrun;///< Number of buffer overrunsuint8_t parse_error;///< Number of parse errorsmavlink_parse_state_t parse_state;///< Parsing state machineuint8_t packet_idx;///< Index in current packetuint8_t current_rx_seq;///< Sequence number of last packet receiveduint8_t current_tx_seq;///< Sequence number of last packet sentuint16_t packet_rx_success_count;///< Received packetsuint16_t packet_rx_drop_count;///< Number of packet drops}mavlink_status_t;#define MAVLINK_BIG_ENDIAN 0#define MAVLINK_LITTLE_ENDIAN 1#endif/* MAVLINK_TYPES_H_ */
11.protocol.h未做任何修改,附上全代码
protocol.h全代码
#ifndef _MAVLINK_PROTOCOL_H_//作者:恒久力行 qq:624668529#define _MAVLINK_PROTOCOL_H_#include"string.h"#include"mavlink_types.h"/*If you want MAVLink on a system that is native big-endian,you need to define NATIVE_BIG_ENDIAN*/#ifdef NATIVE_BIG_ENDIAN# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN)#else# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN)#endif#ifndef MAVLINK_STACK_BUFFER#define MAVLINK_STACK_BUFFER 0#endif#ifndef MAVLINK_AVOID_GCC_STACK_BUG# define MAVLINK_AVOID_GCC_STACK_BUG defined(__GNUC__)#endif#ifndef MAVLINK_ASSERT#define MAVLINK_ASSERT(x)#endif#ifndef MAVLINK_START_UART_SEND#define MAVLINK_START_UART_SEND(chan, length)#endif#ifndef MAVLINK_END_UART_SEND#define MAVLINK_END_UART_SEND(chan, length)#endif/* option to provide alternative implementation of mavlink_helpers.h */#ifdef MAVLINK_SEPARATE_HELPERS#define MAVLINK_HELPER/* decls in sync with those in mavlink_helpers.h */#ifndef MAVLINK_GET_CHANNEL_STATUSMAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan);#endifMAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan);#if MAVLINK_CRC_EXTRAMAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg,uint8_t system_id,uint8_t component_id,uint8_t chan,uint8_t min_length,uint8_t length,uint8_t crc_extra);MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg,uint8_t system_id,uint8_t component_id,uint8_t min_length,uint8_t length,uint8_t crc_extra);#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONSMAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan,uint8_t msgid,constchar*packet,uint8_t min_length,uint8_t length,uint8_t crc_extra);#endif#elseMAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg,uint8_t system_id,uint8_t component_id,uint8_t chan,uint8_t length);MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg,uint8_t system_id,uint8_t component_id,uint8_t length);#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONSMAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan,uint8_t msgid,constchar*packet,uint8_t length);#endif#endif// MAVLINK_CRC_EXTRAMAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t*buffer,constmavlink_message_t*msg);MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg);MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg,uint8_t c);MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg,mavlink_status_t* status,uint8_t c,mavlink_message_t* r_message,mavlink_status_t* r_mavlink_status);MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan,uint8_t c,mavlink_message_t* r_message,mavlink_status_t* r_mavlink_status);MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan,uint8_t c,mavlink_message_t* r_message,mavlink_status_t* r_mavlink_status);MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b,uint8_t bits,uint8_t packet_index,uint8_t bit_index,uint8_t* r_bit_index,uint8_t* buffer);#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONSMAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan,constchar*buf,uint16_t len);MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan,constmavlink_message_t*msg);#endif#else#define MAVLINK_HELPER staticinline#include"mavlink_helpers.h"#endif// MAVLINK_SEPARATE_HELPERS/*** @brief Get the required buffer size for this message*/staticinlineuint16_t mavlink_msg_get_send_buffer_length(constmavlink_message_t* msg){return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES;}#if MAVLINK_NEED_BYTE_SWAPstaticinlinevoid byte_swap_2(char*dst,constchar*src){dst[0]= src[1];dst[1]= src[0];}staticinlinevoid byte_swap_4(char*dst,constchar*src){dst[0]= src[3];dst[1]= src[2];dst[2]= src[1];dst[3]= src[0];}staticinlinevoid byte_swap_8(char*dst,constchar*src){dst[0]= src[7];dst[1]= src[6];dst[2]= src[5];dst[3]= src[4];dst[4]= src[3];dst[5]= src[2];dst[6]= src[1];dst[7]= src[0];}#elif!MAVLINK_ALIGNED_FIELDSstaticinlinevoid byte_copy_2(char*dst,constchar*src){dst[0]= src[0];dst[1]= src[1];}staticinlinevoid byte_copy_4(char*dst,constchar*src){dst[0]= src[0];dst[1]= src[1];dst[2]= src[2];dst[3]= src[3];}staticinlinevoid byte_copy_8(char*dst,constchar*src){memcpy(dst, src,8);}#endif#define_mav_put_uint8_t(buf, wire_offset, b) buf[wire_offset]=(uint8_t)b#define_mav_put_int8_t(buf, wire_offset, b) buf[wire_offset]=(int8_t)b#define _mav_put_char(buf, wire_offset, b) buf[wire_offset]= b#if MAVLINK_NEED_BYTE_SWAP#define_mav_put_uint16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset],(constchar*)&b)#define_mav_put_int16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset],(constchar*)&b)#define_mav_put_uint32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset],(constchar*)&b)#define_mav_put_int32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset],(constchar*)&b)#define_mav_put_uint64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset],(constchar*)&b)#define_mav_put_int64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset],(constchar*)&b)#define _mav_put_float(buf, wire_offset, b) byte_swap_4(&buf[wire_offset],(constchar*)&b)#define _mav_put_double(buf, wire_offset, b) byte_swap_8(&buf[wire_offset],(constchar*)&b)#elif!MAVLINK_ALIGNED_FIELDS#define_mav_put_uint16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset],(constchar*)&b)#define_mav_put_int16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset],(constchar*)&b)#define_mav_put_uint32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset],(constchar*)&b)#define_mav_put_int32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset],(constchar*)&b)#define_mav_put_uint64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset],(constchar*)&b)#define_mav_put_int64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset],(constchar*)&b)#define _mav_put_float(buf, wire_offset, b) byte_copy_4(&buf[wire_offset],(constchar*)&b)#define _mav_put_double(buf, wire_offset, b) byte_copy_8(&buf[wire_offset],(constchar*)&b)#else#define_mav_put_uint16_t(buf, wire_offset, b)*(uint16_t*)&buf[wire_offset]= b#define_mav_put_int16_t(buf, wire_offset, b)*(int16_t*)&buf[wire_offset]= b#define_mav_put_uint32_t(buf, wire_offset, b)*(uint32_t*)&buf[wire_offset]= b#define_mav_put_int32_t(buf, wire_offset, b)*(int32_t*)&buf[wire_offset]= b#define_mav_put_uint64_t(buf, wire_offset, b)*(uint64_t*)&buf[wire_offset]= b#define_mav_put_int64_t(buf, wire_offset, b)*(int64_t*)&buf[wire_offset]= b#define _mav_put_float(buf, wire_offset, b)*(float*)&buf[wire_offset]= b#define _mav_put_double(buf, wire_offset, b)*(double*)&buf[wire_offset]= b#endif/*like memcpy(), but if src is NULL, do a memset to zero*/staticinlinevoid mav_array_memcpy(void*dest,constvoid*src,size_t n){if(src == NULL){memset(dest,0, n);}else{memcpy(dest, src, n);}}/** Place a char array into a buffer*/staticinlinevoid _mav_put_char_array(char*buf,uint8_t wire_offset,constchar*b,uint8_t array_length){mav_array_memcpy(&buf[wire_offset], b, array_length);}/** Place a uint8_t array into a buffer*/staticinlinevoid _mav_put_uint8_t_array(char*buf,uint8_t wire_offset,constuint8_t*b,uint8_t array_length){mav_array_memcpy(&buf[wire_offset], b, array_length);}/** Place a int8_t array into a buffer*/staticinlinevoid _mav_put_int8_t_array(char*buf,uint8_t wire_offset,constint8_t*b,uint8_t array_length){mav_array_memcpy(&buf[wire_offset], b, array_length);}#if MAVLINK_NEED_BYTE_SWAP#define _MAV_PUT_ARRAY(TYPE, V) \staticinlinevoid _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \{ \if(b == NULL){ \memset(&buf[wire_offset],0, array_length*sizeof(TYPE)); \}else{ \uint16_t i; \for(i=0; i<array_length; i++){ \_mav_put_## TYPE (buf, wire_offset+(i*sizeof(TYPE)), b[i]); \} \} \}#else#define _MAV_PUT_ARRAY(TYPE, V) \staticinlinevoid _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \{ \mav_array_memcpy(&buf[wire_offset], b, array_length*sizeof(TYPE)); \}#endif_MAV_PUT_ARRAY(uint16_t, u16)_MAV_PUT_ARRAY(uint32_t, u32)_MAV_PUT_ARRAY(uint64_t, u64)_MAV_PUT_ARRAY(int16_t, i16)_MAV_PUT_ARRAY(int32_t, i32)_MAV_PUT_ARRAY(int64_t, i64)_MAV_PUT_ARRAY(float, f)_MAV_PUT_ARRAY(double, d)#define _MAV_RETURN_char(msg, wire_offset)(constchar)_MAV_PAYLOAD(msg)[wire_offset]#define_MAV_RETURN_int8_t(msg, wire_offset)(int8_t)_MAV_PAYLOAD(msg)[wire_offset]#define_MAV_RETURN_uint8_t(msg, wire_offset)(uint8_t)_MAV_PAYLOAD(msg)[wire_offset]#if MAVLINK_NEED_BYTE_SWAP#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \staticinline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \{ TYPE r; byte_swap_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; }_MAV_MSG_RETURN_TYPE(uint16_t,2)_MAV_MSG_RETURN_TYPE(int16_t,2)_MAV_MSG_RETURN_TYPE(uint32_t,4)_MAV_MSG_RETURN_TYPE(int32_t,4)_MAV_MSG_RETURN_TYPE(uint64_t,8)_MAV_MSG_RETURN_TYPE(int64_t,8)_MAV_MSG_RETURN_TYPE(float,4)_MAV_MSG_RETURN_TYPE(double,8)#elif!MAVLINK_ALIGNED_FIELDS#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \staticinline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \{ TYPE r; byte_copy_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; }_MAV_MSG_RETURN_TYPE(uint16_t,2)_MAV_MSG_RETURN_TYPE(int16_t,2)_MAV_MSG_RETURN_TYPE(uint32_t,4)_MAV_MSG_RETURN_TYPE(int32_t,4)_MAV_MSG_RETURN_TYPE(uint64_t,8)_MAV_MSG_RETURN_TYPE(int64_t,8)_MAV_MSG_RETURN_TYPE(float,4)_MAV_MSG_RETURN_TYPE(double,8)#else// nicely aligned, no swap#define _MAV_MSG_RETURN_TYPE(TYPE) \staticinline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \{return*(const TYPE *)(&_MAV_PAYLOAD(msg)[ofs]);}_MAV_MSG_RETURN_TYPE(uint16_t)_MAV_MSG_RETURN_TYPE(int16_t)_MAV_MSG_RETURN_TYPE(uint32_t)_MAV_MSG_RETURN_TYPE(int32_t)_MAV_MSG_RETURN_TYPE(uint64_t)_MAV_MSG_RETURN_TYPE(int64_t)_MAV_MSG_RETURN_TYPE(float)_MAV_MSG_RETURN_TYPE(double)#endif// MAVLINK_NEED_BYTE_SWAPstaticinlineuint16_t _MAV_RETURN_char_array(constmavlink_message_t*msg,char*value,uint8_t array_length,uint8_t wire_offset){memcpy(value,&_MAV_PAYLOAD(msg)[wire_offset], array_length);return array_length;}staticinlineuint16_t _MAV_RETURN_uint8_t_array(constmavlink_message_t*msg,uint8_t*value,uint8_t array_length,uint8_t wire_offset){memcpy(value,&_MAV_PAYLOAD(msg)[wire_offset], array_length);return array_length;}staticinlineuint16_t _MAV_RETURN_int8_t_array(constmavlink_message_t*msg,int8_t*value,uint8_t array_length,uint8_t wire_offset){memcpy(value,&_MAV_PAYLOAD(msg)[wire_offset], array_length);return array_length;}#if MAVLINK_NEED_BYTE_SWAP#define _MAV_RETURN_ARRAY(TYPE, V) \staticinlineuint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \uint8_t array_length,uint8_t wire_offset) \{ \uint16_t i; \for(i=0; i<array_length; i++){ \value[i]= _MAV_RETURN_## TYPE (msg, wire_offset+(i*sizeof(value[0]))); \} \return array_length*sizeof(value[0]); \}#else#define _MAV_RETURN_ARRAY(TYPE, V) \staticinlineuint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \uint8_t array_length,uint8_t wire_offset) \{ \memcpy(value,&_MAV_PAYLOAD(msg)[wire_offset], array_length*sizeof(TYPE)); \return array_length*sizeof(TYPE); \}#endif_MAV_RETURN_ARRAY(uint16_t, u16)_MAV_RETURN_ARRAY(uint32_t, u32)_MAV_RETURN_ARRAY(uint64_t, u64)_MAV_RETURN_ARRAY(int16_t, i16)_MAV_RETURN_ARRAY(int32_t, i32)_MAV_RETURN_ARRAY(int64_t, i64)_MAV_RETURN_ARRAY(float, f)_MAV_RETURN_ARRAY(double, d)#endif// _MAVLINK_PROTOCOL_H_//作者:恒久力行 qq:624668529
12.其他代码均未修改,详细移植步骤请参考教程二和教程一。
现在代码已经移植成功。
二:实验测试代码是否移植成功
将代码下载到stm32f407的开发板中去。
打开串口调试助手,设置波特率115200,16进制显示接收到的数据。不细讲,看图
1.测试开发板发送功能
然后重启或者复位开发板,会有数据返回(注意:选中16进制显示)。如图收到如图数据表示发送移植成功。复位一次返回一次同样的数据//作者:恒久力行 qq:624668529

2.测试开发板接收功能
将接收到的数据原封不动的拷贝下来,(复制下来的是16进制的哦,别弄成字符乱码了,注意从FE到结尾的空格都不能少),然后选中16进制发送 同时取消16进制显示。然后将数据粘贴在发送窗(发送窗一定要清空,不能有空格或者回车让光标删除到最前端),先清空接收,点击发送,会有如下字符返回,如图表示接受移植成功。点击一次发送返回一次同样的字符//作者:恒久力行 qq:624668529

三:分析数据
1.下面是串口助手接收到的开发板发过来的数据
FE 0900000000000000000203510403855D FE 1C01000021010000000200000003000000040000000500000006000700080009002A16
2.下图是消息包的发送格式说明
3.将从开发板收到的16进制的数据以FE为分界将两条消息按格式展开如图

4分析
开发板发出的数据,首先都是以FE开头,先看第一帧数据的第二个字节,LEN代表有效载荷PAYLOAD的长度,经自己亲自数数PAYLOAD 确实是9个字节(注意16进制要转换成10进制),同理,再来看第二帧数据的第二个字节1C转换成10进制是28.数一数PAYLOAD的长度确实为28.表示移植数据发送成功。
开发板接收的数据是我们原封不动发回去的数据,其收到后,会对数据进行解析。其对两帧数据解析的结果是(即第二次发回来的字符):
Received message with ID 0, sequence: 0 from component 0 of system 0
Received message with ID 33, sequence: 1 from component 0 of system 0
对比message with ID 即是 MSG (10进制)
sequence 既是SEQ
component 既是COMP
system 既是SYS
对比之后发现数据一一对应。即开发板收到数据后成功的解析了数据。表示移植开发板接收部分成功
移植成功。作者:恒久力行 qq:624668529
附件列表
希望我的分享对你有一定的帮助,希望每一个中国人都能发愤图强,为国家的科技事业做出自己的贡献。同时祝愿中国的科学技术水平越来越高,相信我国会越来越强大。加油,每一个中国人

浙公网安备 33010602011771号