找回密码
 立即注册

QQ登录

只需一步,快速开始

搜索
查看: 10729|回复: 6
收起左侧

51单片机四轴飞控STC8A8K16S4A12-LQFP44-PPM-V10源码与说明资料下载

  [复制链接]
ID:80420 发表于 2018-3-26 12:24 | 显示全部楼层 |阅读模式
开源了,感兴趣的朋友看一下,里面有代码和pcb都有的.
0.jpg
STC8A8K飞控使用说明
本飞控使用世界上速度最快的51:宏晶科技出品的STC8系列单片机STC8A8K64S4A12 LQFP44
嘴主控,单片机价在3yuan左右,更宜好用。
本飞控已严格调试通过,用户可d行参考、消化程序,不提供技术支持。
持別注意:下载时选杼内部时钟24MHZ,设罝用户EEPROM大小为2K或以上.
资源简介:
内核:
超髙速805丨内核(1T),是全球最快速的8051,比传统805丨玦丨2倍,井且价格低廉.
指令代码究全兼容传统8051的111条指令
22个中断源,4级中断优先级.
支持在线编程(丨SP).
支持在线仿真《
工作电压:2(K5.5V.内建LDO.
工作温度:WC〜85-C,
FLASH存储器:最大64K字节FLASH空间.
用户可将部分FLASH配置为EEPROM. 512字节单页療除。
SRA.X1: 128字节直接或间接访问RAM  (DATA或IDATA访问)
128 字节间接 RAM ( IDATA)
8192字节内部扩展RAM (内部XDATA)
外部可扩展64K字节RAM (外部XDATA)
时钟:内部24MI1Z高精度时钟(ISP编程可调整),常温(25)误差±0.3%。
温度范围-20°C〜65 °C时温漂-丨.0%~-0.5%,温度范围-40°C ~85 °C时温漂-1.8%—0.8%
内部32KJIZ低速时钟(误差较大)。
外部晶振或外部时钟(4MI1Z〜33VI11Z),用户软件自由选择这3种时钟源。
中断: 22个中断源。
数字外设:5个16位定时器,4个高速串口,4路PCA模块,8路15位增强型PWM,   SPI ,   I2C。
模拟外设:16通道12位ADC, 1组比较器。
GPIO:  LQFP44 封装又 39 个io, LQFP48 有 43 个丨0, LQFP64S 有 59 个io。
0.jpg

飞控的电路原理图:
0.png
本飞控仅仅是姿态飞行控制,没有GPS、电子罗盘、气压高度计、超声波测距、光流传感器等等, 不能实现定点悬停,但是飞行感觉非常好,稳定,特别是暴力飞行的刺激,是很多玩家所喜欢的。用户 可以A行增加这些传感器,编写相关的程序,以获得更好的飞行性能。
本飞控通过调整PID参数可以适应从250mm轴距到750mm轴距的,都实际装机验证过,效果很 好。
本例实用F450的四轴机架,大约40元,安装简单,入门快,让玩家可以快速的装配成功,如动手 能力强可以A己买配件做机架,铝合金或碳纤维均可。我喜欢用铝合金方管,好加工,强度好,还很轻。配套使用MC6B的遥控、接收套件,左手油门(俗称“美国手”),大约130元,是我能找到的最 便宜的遥控器了,不差钱的玩家可以使用更昂贵的遥控器套件。四轴实物照片如K阁所示。本例只说明如何使用飞控,对于四轴工作原理不做描述,要科普的用户可以A行上网搜索相关知识。
主要零件:
STC8A8K16S4A12 LQFP44 做的飞控 1 块。
MPU-6050三轴陀螺仪、三轴加速度传感器模块1块。
MC6B遥控、接收机1套。
F450玻纤四轴机架1套。
2212无刷电机4个(配香蕉插)。
20A电调4个。
9450正反桨2对(实际买多些,因为新手会有损耗)。
3S锂电池4200mAH  1块(用户可以购买多块爽飞)。
B6平衡充(带12V 5A电源)1套。
T插插头1个。
12号硅胶线红、黑色给20cm。
魔术带(捆绑电池的)1条。
3M双而胶(3*7cm,粘电调、飞控用)2片。
扎丝或扎带若千(我喜欢扎丝,因为可以方便的拧下来)。
红光、绿光LED灯条(可选)各2条。(用户可以先不装,要夜航的才装,我就喜欢夜航)。
0.jpg

单片机源程序如下:
  1. /* 本程序经过测试完全正常, 不提供电话技术支持, 如不能理解, 请自行补充相关基础.  */
  2. /***  特别注意: 下载时选择内部时钟24MHZ, 设置用户EEPROM大小为2K或以上.  ****/
  3. /*********************************************
  4.   四轴飞控-V10.C
  5. 使用遥控接收器型号: MC6B六通道2.4G 100mW.

  6. 四轴上电待机:上电后,航灯不亮,接收机LED闪烁,此时打开遥控器,将左右油门下拉到最小,接收机收到信号LED常亮,
  7.               表示RF通讯已连接。此时蜂鸣器"哔"一声,航灯闪烁,表示待机模式。

  8. 四轴启动:将遥控器左右操纵杆掰成下内八,启动四轴,四轴"哔"一声,4个螺旋桨开始低速旋转,航灯常亮。
  9.           此后提升油门,就可以加速螺旋桨,直到起飞。

  10. 四轴飞行:起飞后,可以操纵右手的俯仰、横滚操纵杆,实现前后左右或任意方向的飞行。
  11.           左手油门杆左掰是航向逆时针转,右掰是航向顺时钟转。

  12. 四轴下降停止:收油门,四轴逐渐下降到地面,然后两操纵杆掰成下外八,停止四轴,重新处于待机模式。

  13. 四轴水平校准:将四轴放置于水平地面,处于待机模式,然后两操纵杆掰成上内八,四轴"哔"一声进入校准,完成后"哔哔"两声完成校准。

  14. 四轴取消水平校准:将四轴放置于水平地面,处于待机模式,然后两操纵杆掰成上外八,四轴"哔"一声取消校准。取消水平校准或未进行水平校准过的四轴,起飞时即使无风也可能会有明显漂移。

  15. 电池低压报警:当电池低压时,蜂鸣器"哔哔"报警,同时航灯闪烁,此时请尽快回航降落。

  16. 无遥控信号异常:当四轴在空中突然收不到遥控信号时,四轴蜂鸣器发出"哔哔哔"报警,同时航灯闪烁,四轴保持水平,逐渐自动减小油门降落。
  17. ***********************************************/

  18. #define                Baudrate1                        115200UL
  19. #define                TX1_LENGTH        128
  20. #define                RX1_LENGTH        128


  21. #include "config.h"
  22. #include "STC8xxx_PWM.H"
  23. #include "MPU6050.H"
  24. #include "AD.H"       
  25. #include "EEPROM.H"
  26. #include "PCA.h"
  27. #include <math.H>

  28. sbit        P_Light  = P5^4;        //航灯
  29. sbit        P_BUZZER = P5^5;        //蜂鸣器


  30. int                xdata g_x=0,g_y=0,g_z=0;                                        //陀螺仪矫正参数
  31. float        xdata a_x=0,a_y=0;                                                        //角度矫正参数
  32. float        data  AngleX=0,AngleY=0;                                        //四元数解算出的欧拉角
  33. float        xdata Angle_gx=0,Angle_gy=0,Angle_gz=0;                //由角速度计算的角速率(角度制)
  34. float        xdata Angle_ax=0,Angle_ay=0,Angle_az=0;                //由加速度计算的加速度(弧度制)
  35. float        xdata Ax=0,Ay=0,Az=0;                                                //加入遥控器控制量后的角度   
  36. float        data PID_x=0,PID_y=0,PID_z=0;                                //PID最终输出量
  37. int                data  speed0=0,speed1=0,speed2=0,speed3=0;        //电机速度参数
  38. int                data  PWM0=0,PWM1=0,PWM2=0,PWM3=0;//,PWM4=0,PWM5=0;                        //加载至PWM模块的参数

  39. int                int_tmp;
  40. u8                YM=0,FRX=128,FRY=128,FRZ=128;                                //4通道遥控信号.
  41. u8                xdata        tp[16];                //读MP6050缓冲


  42. //****************姿态处理和PID*********************************************

  43. float xdata Out_PID_X=0,Last_Angle_gx=0;                                        //外环PI输出量  上一次陀螺仪数据
  44. float xdata ERRORX_Out=0,ERRORX_In=0;                        //外环P  外环I  外环误差积分
  45. float xdata Out_PID_Y=0,Last_Angle_gy=0;
  46. float xdata ERRORY_Out=0,ERRORY_In=0;            //规则1:内外环P乘积等于10.5

  47. float xdata Last_Ax=0,Last_Ay=0,Last_Az=0;


  48. /******************************************************************************/
  49. #define        Out_XP        6.65f        //ADC0        外环P        V1 / 10
  50. #define        Out_XI        0.0074f        //ADC4        外环I        V2 / 10000
  51. #define        Out_XD        6.0f        //ADC5        外环D        V3 / 10

  52. #define        In_XP        0.8275f        //ADC6        内环P        V4 / 100
  53. #define        In_XI        0.0074f        //ADC4        内环I        V2 / 10000
  54. #define        In_XD        6.0f        //ADC5        内环D        V3 / 10


  55. #define        Out_YP        Out_XP
  56. #define        Out_YI        Out_XI
  57. #define        Out_YD        Out_XD

  58. #define        In_YP        In_XP
  59. #define        In_YI        In_XI
  60. #define        In_YD        In_XD


  61. #define        ZP        5.0f
  62. #define        ZI        0.1f
  63. #define        ZD        4.0f        //自旋控制的P D
  64. float Z_integral=0;//Z轴积分

  65. #define        ERR_MAX        500
  66. //======================================================================


  67. u8        data YM_LostCnt=0, Lost16S; //上一次RxBuf[0]数据(RxBuf[0]数据在不断变动的)   状态标识
  68. u8        SW2_tmp;


  69. //======================================================================
  70. bit        B_8ms;        //8ms标志

  71. bit        B_rtn_ADC0;        //请求返回信息
  72. bit        B_BAT_LOW;        //低电压标志
  73. u8        xdata cnt_ms;                //时间计数


  74. u8                xdata UART1_cmd=0;        //串口命令
  75. u8                xdata TX1_Read=0;        //发送读指针
  76. u8                xdata TX1_Write=0;        //发送写指针
  77. u8                xdata TX1_cnt=0;        //发送计数
  78. u8                 xdata TX1_Buffer[TX1_LENGTH];        //发送缓冲
  79. bit                B_TX1_Busy;                        //发送忙标志
  80. u8                 xdata RX1_Cnt,RX1_Timer;
  81. u8                 xdata RX1_Buffer[RX1_LENGTH];
  82. bit         B_RX1_OK;


  83. u8                xdata Cal_Setp=0;                        //校准步骤
  84. u8                xdata Cal_cnt=0;                        //校准平均值计数
  85. int                xdata x_sum,y_sum,z_sum;        //校准累加和
  86. float        xdata float_x_sum,float_y_sum;        //校准累加和

  87. u8        xdata BuzzerOnTime,BuzzerOffTime,BuzzerRepeat,BuzzerOnCnt,BuzzerOffCnt;
  88. u8        xdata cnt_100ms;


  89. /* =================== PPM接收相关变量 ========================== */
  90. u16        xdata CCAP0_RiseTime;                //捕捉到的上升沿时刻
  91. u8        xdata PPM1_Rise_TimeOut;        //高电平限时
  92. u8        xdata PPM1_Rx_TimerOut;                //接收超时计数
  93. u8        xdata PPM1_RxCnt;                        //接收次数计数
  94. u16        xdata PPM1_Cap;                                //捕捉到的PPM脉冲宽度
  95. bit        B_PPM1_OK;                                        //接收到一个PPM脉冲宽度

  96. u16        xdata CCAP1_RiseTime;
  97. u8        xdata PPM2_Rise_TimeOut;        //高电平限时
  98. u8        xdata PPM2_Rx_TimerOut;
  99. u8        xdata PPM2_RxCnt;
  100. u16        xdata PPM2_Cap;
  101. bit        B_PPM2_OK;

  102. u16        xdata CCAP2_RiseTime;
  103. u8        xdata PPM3_Rise_TimeOut;        //高电平限时
  104. u8        xdata PPM3_Rx_TimerOut;
  105. u8        xdata PPM3_RxCnt;
  106. u16        xdata PPM3_Cap;
  107. bit        B_PPM3_OK;

  108. u16        xdata CCAP3_RiseTime;
  109. u8        xdata PPM4_Rise_TimeOut;        //高电平限时
  110. u8        xdata PPM4_Rx_TimerOut;
  111. u8        xdata PPM4_RxCnt;
  112. u16        xdata PPM4_Cap;
  113. bit        B_PPM4_OK;

  114. u16        xdata CCAP_FallTime;

  115. u8        PPM1,PPM2,PPM3,PPM4;
  116. bit        B_Start;
  117. u8        cnt_start;

  118. /* ============================================= */


  119. void        UART1_config(void);
  120. void         PrintString1(u8 *puts);        //发送一个字符串
  121. void        TX1_write2buff(u8 dat);        //写入发送缓冲,指针+1
  122. void        TX1_int_value(int i);
  123. void        delay_ms(u8 ms);
  124. void        Return_Message(void);
  125. u16         MODBUS_CRC16(u8 *p,u8 n);        //input:        *p--->First Data Address,n----->Data Number,        return:        CRC16
  126. void        PCA_config(void);
  127. void         Timer0_Config(void);
  128. void         Timer1_Config(void);
  129. void        return_TTMx(u8 id,PPMx);
  130. void         Timer0_Config(void);
  131. u16         MODBUS_CRC16(u8 *p,u8 n);        //input:        *p--->First Data Address,n----->Data Number,        return:        CRC16

  132. extern xdata u16        adc0;
  133. extern xdata int        Battery;


  134. //*********************************************************************
  135. //****************角度计算*********************************************
  136. //*********************************************************************
  137. #define        pi                3.14159265f                           
  138. #define        Kp                0.8f                        
  139. #define        Ki                0.001f                        
  140. #define        halfT        0.004f           

  141. float idata q0=1,q1=0,q2=0,q3=0;   
  142. float idata exInt=0,eyInt=0,ezInt=0;  


  143. void IMUupdate(float gx, float gy, float gz, float ax, float ay, float az)
  144. {
  145.         float data norm;
  146.         float idata vx, vy, vz;
  147.         float idata ex, ey, ez;

  148.         norm = sqrt(ax*ax + ay*ay + az*az);        //把加速度计的三维向量转成单维向量   
  149.         ax = ax / norm;
  150.         ay = ay / norm;
  151.         az = az / norm;

  152.                 //        下面是把四元数换算成《方向余弦矩阵》中的第三列的三个元素。
  153.                 //        根据余弦矩阵和欧拉角的定义,地理坐标系的重力向量,转到机体坐标系,正好是这三个元素
  154.                 //        所以这里的vx vy vz,其实就是当前的欧拉角(即四元数)的机体坐标参照系上,换算出来的
  155.                 //        重力单位向量。
  156.         vx = 2*(q1*q3 - q0*q2);
  157.         vy = 2*(q0*q1 + q2*q3);
  158.         vz = q0*q0 - q1*q1 - q2*q2 + q3*q3 ;

  159.         ex = (ay*vz - az*vy) ;
  160.         ey = (az*vx - ax*vz) ;
  161.         ez = (ax*vy - ay*vx) ;

  162.         exInt = exInt + ex * Ki;
  163.         eyInt = eyInt + ey * Ki;
  164.         ezInt = ezInt + ez * Ki;

  165.         gx = gx + Kp*ex + exInt;
  166.         gy = gy + Kp*ey + eyInt;
  167.         gz = gz + Kp*ez + ezInt;

  168.         q0 = q0 + (-q1*gx - q2*gy - q3*gz) * halfT;
  169.         q1 = q1 + ( q0*gx + q2*gz - q3*gy) * halfT;
  170.         q2 = q2 + ( q0*gy - q1*gz + q3*gx) * halfT;
  171.         q3 = q3 + ( q0*gz + q1*gy - q2*gx) * halfT;

  172.         norm = sqrt(q0*q0 + q1*q1 + q2*q2 + q3*q3);
  173.         q0 = q0 / norm;
  174.         q1 = q1 / norm;
  175.         q2 = q2 / norm;
  176.         q3 = q3 / norm;

  177.         AngleX = asin(2*(q0*q2 - q1*q3 )) * 57.2957795f; // 俯仰   换算成度
  178.         AngleY = asin(2*(q0*q1 + q2*q3 )) * 57.2957795f; // 横滚
  179. }



  180. //****************姿态计算*********************************************
  181. void PWM_int (void) interrupt         22        //PWM中断函数
  182. {
  183.         PWMCFG = 0;        //CBIF;        //清除中断标志

  184.         B_8ms = 1;

  185. //======================== 超时溢出处理 ==============================================
  186.         PPM1_Rise_TimeOut++;        //高电平限时
  187.         PPM2_Rise_TimeOut++;        //高电平限时
  188.         PPM3_Rise_TimeOut++;        //高电平限时
  189.         PPM4_Rise_TimeOut++;        //高电平限时

  190.         if(--PPM1_Rx_TimerOut == 0)                //超过100ms收不到信号
  191.         {
  192.                 PPM1_RxCnt = 0;                        //一旦出现溢出, 则开始的n个脉冲无效
  193.                 PPM1 = 128;;                        //默认中点
  194.         }
  195.         if(--PPM2_Rx_TimerOut == 0)                //超过100ms收不到信号
  196.         {
  197.                 PPM2_RxCnt = 0;                        //一旦出现溢出, 则开始的n个脉冲无效
  198.                 PPM2 = 128;;                        //默认中点
  199.         }
  200.         if(--PPM3_Rx_TimerOut == 0)                //超过200ms收不到信号
  201.         {
  202.                 PPM3_RxCnt = 0;                        //一旦出现溢出, 则开始的n个脉冲无效
  203.         }
  204.         if(--PPM4_Rx_TimerOut == 0)                //超过100ms收不到信号
  205.         {
  206.                 PPM4_RxCnt = 0;                        //一旦出现溢出, 则开始的n个脉冲无效
  207.                 PPM4 = 128;                                //默认中点
  208.         }
  209. //======================================================================

  210.         if(++YM_LostCnt >= 250)                //失联2秒后
  211.         {
  212.                 YM_LostCnt = 200;                //重复0.4秒,失控保护
  213.                 if(PPM3 > 80)        PPM3--;
  214.                 else if(++Lost16S >= 40)
  215.                 {
  216.                         Lost16S = 250;
  217.                         PPM3 = 0;
  218.                         B_Start = 0;
  219.                 }
  220.         }
  221.         if(YM_LostCnt  >= 25)        //失联200ms
  222.         {
  223.                 PPM1 = 128;
  224.                 PPM2 = 128;                //俯仰 横滚 航向均归0
  225.                 PPM4 = 128;
  226.         }

  227.         FRX = PPM1;
  228.         FRY = PPM2;
  229.         YM  = PPM3;        //油门
  230.         FRZ = PPM4;
  231.        

  232. //********************************************************************************************
  233.         Read_MPU6050(tp);        //680us

  234.         Angle_ax = ((float)(((int *)&tp)[0])) / 8192.0;        //加速度处理        结果单位是 +- g
  235.         Angle_ay = ((float)(((int *)&tp)[1])) / 8192.0;        //转换关系        8192 LSB/g, 1g对应读数8192
  236.         Angle_az = ((float)(((int *)&tp)[2])) / 8192.0;        //加速度量程 +-4g/S
  237.         Last_Angle_gx = Angle_gx;                //储存上一次角速度数据
  238.         Last_Angle_gy = Angle_gy;
  239.         Angle_gx = ((float)(((int *)&tp)[4] - g_x)) / 65.5;        //陀螺仪处理        结果单位是 +-度
  240.         Angle_gy = ((float)(((int *)&tp)[5] - g_y)) / 65.5;        //陀螺仪量程 +-500度/S, 1度/秒 对应读数 65.536
  241.         Angle_gz = ((float)(((int *)&tp)[6] - g_z)) / 65.5;        //转换关系65.5 LSB/度

  242.         IMUupdate(Angle_gx*0.0174533f, Angle_gy*0.0174533f, Angle_gz*0.0174533f, Angle_ax,Angle_ay,Angle_az);

  243. //**********************************X轴指向************************************************
  244.         Ax  = AngleX - a_x - ((float)FRX - 128) / 4.0;                //角度控制量加载至角度

  245.         if(YM > 35)        ERRORX_Out += Ax,        ERRORX_Out += Ax,        ERRORX_Out += Ax;        //外环积分(油门小于某个值时不积分)
  246.         else                ERRORX_Out = 0; //油门小于定值时清除积分值
  247.                  if(ERRORX_Out >  1500)        ERRORX_Out =  1500;
  248.         else if(ERRORX_Out < -1500)        ERRORX_Out = -1500;        //积分限幅

  249.         Out_PID_X = Ax*Out_XP + ERRORX_Out*Out_XI + (Ax-Last_Ax)*Out_XD;        //外环PI
  250.         Last_Ax = Ax;
  251.        
  252.         if(YM > 35)        ERRORX_In += (Angle_gy - Out_PID_X);        //内环积分(油门小于某个值时不积分)
  253.         else                ERRORX_In = 0;        //油门小于定值时清除积分值
  254.                  if(ERRORX_In >  500)        ERRORX_In =  500;
  255.         else if(ERRORX_In < -500)        ERRORX_In = -500;        //积分限幅

  256.         PID_x = (Angle_gy + Out_PID_X) * In_XP + ERRORX_In * In_XI + (Angle_gy - Last_Angle_gy) * In_XD;        //内环PID
  257.         if(PID_x >  500)        PID_x =  500;        //输出量限幅
  258.         if(PID_x < -500)        PID_x = -500;

  259. //**************Y轴指向**************************************************
  260.         Ay  = AngleY - a_y + ((float)FRY - 128) / 4.0;                //角度控制量加载至角度
  261.        
  262.         if(YM > 35)        ERRORY_Out += Ay,        ERRORY_Out += Ay,        ERRORY_Out += Ay;        //外环积分(油门小于某个值时不积分)
  263.         else                ERRORY_Out = 0; //油门小于定值时清除积分值
  264.                  if(ERRORY_Out >  1500)        ERRORY_Out =  1500;
  265.         else if(ERRORY_Out < -1500)        ERRORY_Out = -1500;        //积分限幅
  266.        
  267.         Out_PID_Y = Ay * Out_YP + ERRORY_Out * Out_YI + (Ay-Last_Ay)*Out_YD;        //外环PID
  268.         Last_Ay = Ay;

  269.         if(YM > 35)        ERRORY_In += (Angle_gx - Out_PID_Y);  //内环积分(油门小于某个值时不积分)
  270.         else                ERRORY_In = 0; //油门小于定值时清除积分值
  271.                  if(ERRORY_In >  500)        ERRORY_In =  500;
  272.         else if(ERRORY_In < -500)        ERRORY_In = -500;        //积分限幅
  273.        
  274.         PID_y = (Angle_gx + Out_PID_Y) * In_YP + ERRORY_In * In_YI + (Angle_gx - Last_Angle_gx) * In_YD;        //内环PID
  275.        
  276.         if(PID_y > 500)        PID_y =  500;        //输出量限幅
  277.         if(PID_y <-500)        PID_y = -500;

  278. //**************Z轴指向(Z轴随便啦,自旋控制没必要上串级PID)*****************************       
  279.         Az = Angle_gz - ((float)FRZ - 128);
  280.        
  281.         if(YM > 35)        Z_integral += Az;        //Z轴积分
  282.         else                Z_integral = 0;                //油门小于40积分清零
  283.                  if(Z_integral >  500.0f)        Z_integral =  500.0f;        //积分限幅
  284.         else if(Z_integral < -500.0f)        Z_integral = -500.0f;        //积分限幅

  285.         PID_z = Az * ZP + Z_integral * ZI + (Az - Last_Az) * ZD;
  286.         Last_Az = Az;
  287.         if(PID_z >  200)        PID_z =  200;        //输出量限幅
  288.         if(PID_z < -200)        PID_z = -200;

  289.         speed0 = (int)(  PID_x + PID_y + PID_z);        //M1改为逆时针
  290.         speed1 = (int)(  PID_x - PID_y - PID_z);
  291.         speed2 = (int)( -PID_x - PID_y + PID_z);
  292.         speed3 = (int)( -PID_x + PID_y - PID_z);

  293. //**************将速度参数加载至PWM模块*************************************************       
  294.        
  295.         if(YM < 10)        PWM0 = 1000, PWM1 = 1000, PWM2 = 1000, PWM3 = 1000;
  296.         else if(YM < 35)        PWM0 = 860, PWM1 = 860, PWM2 = 860, PWM3 = 860;
  297.         else
  298.         {
  299.                 int_tmp = 1000 - (int)YM * 4;

  300.                 PWM0 = int_tmp - speed0;

  301.                          if(PWM0 > 1000)        PWM0 = 1000;    //速度参数控制,防止超过PWM参数范围0-1000
  302.                 else if(PWM0 < 10)                PWM0 = 10;

  303.                 PWM1 = int_tmp - speed1;

  304.                          if(PWM1 > 1000)        PWM1 = 1000;
  305.                 else if(PWM1 < 10)                PWM1 = 10;

  306.                 PWM2 = int_tmp - speed2;

  307.                          if(PWM2 > 1000)        PWM2 = 1000;
  308.                 else if(PWM2 < 10)                PWM2 = 10;

  309.                 PWM3 = int_tmp - speed3;

  310.                          if(PWM3 > 1000)        PWM3 = 1000;
  311.                 else if(PWM3 < 10)                PWM3 = 10;
  312.         }

  313.         SW2_tmp = P_SW2;        //保存SW2设置
  314.         EAXSFR();        //访问XFR
  315.         PWM0T2 = (u16)(PWM0 * 2);
  316.         PWM1T2 = (u16)(PWM1 * 2);
  317.         PWM2T2 = (u16)(PWM2 * 2);
  318.         PWM3T2 = (u16)(PWM3 * 2);       
  319.         P_SW2  = SW2_tmp;        //恢复SW2设置

  320. }


  321. /********************** 蜂鸣函数 ************************/
  322. void        beep(void)        //100ms调用
  323. {
  324.         if(BuzzerRepeat > 0)        //蜂鸣器处理, 重复次数不为0,则蜂鸣器要发声
  325.         {
  326.                 if((BuzzerOnCnt == 0) && (BuzzerOffCnt == 0))        //On和OFF都为0,则开始装载On和Off的时间
  327.                 {
  328.                         P_BUZZER = 1;                        //允许蜂鸣
  329.                         BuzzerOnCnt  = BuzzerOnTime;        //装载on计数
  330.                         BuzzerOffCnt = BuzzerOffTime;        //装载off计数
  331.                 }
  332.                 else if(BuzzerOnCnt  > 0)        {if(--BuzzerOnCnt == 0)        P_BUZZER = 0;}        //On的时间
  333.                 else if(BuzzerOffCnt > 0)        //Off的时间
  334.                 {
  335.                         if(--BuzzerOffCnt == 0)        BuzzerRepeat--;
  336.                 }
  337.         }
  338.         else        P_BUZZER = 0;
  339. }

  340. void        SetBuzzer(u8 on,u8 off,u8 rep)        // rep: 重复次数, on: on的时间, off: off的时间
  341. {
  342.         BuzzerRepeat = rep;
  343.         BuzzerOnTime  = on;
  344.         BuzzerOffTime = off;
  345.         if(BuzzerOnTime  == 0)        BuzzerOnTime  = 1;
  346.         if(BuzzerOffTime == 0)        BuzzerOffTime = 1;
  347.         if(BuzzerRepeat == 1)        BuzzerOffTime = 1;
  348.         BuzzerOnCnt = 0,        BuzzerOffCnt = 0;
  349. }

  350. // ===================== 自动校准序列 =====================
  351. void        AutoCal(void)
  352. {
  353.         if(PPM3 < 40)        //停止时才允许校准
  354.         {
  355.                 if(Cal_Setp == 1)        //进入校准序列
  356.                 {
  357.                         x_sum = 0;        y_sum = 0;        z_sum = 0;
  358.                         Cal_cnt  = 0;
  359.                         Cal_Setp = 2;
  360.                 }
  361.                 else if(Cal_Setp == 2)        //对陀螺仪累加
  362.                 {
  363.                         x_sum += ((int *)&tp)[4];  //读取陀螺仪数据
  364.                         y_sum += ((int *)&tp)[5];
  365.                         z_sum += ((int *)&tp)[6];
  366.                         if(++Cal_cnt >= 64)
  367.                         {
  368.                                 g_x = x_sum / 64;
  369.                                 g_y = y_sum / 64;
  370.                                 g_z = z_sum / 64;
  371.                                 float_x_sum = 0;        float_y_sum = 0;
  372.                                 Cal_cnt  = 0;
  373.                                 Cal_Setp = 3;
  374.                         }
  375.                 }
  376.                 else if(Cal_Setp == 3)        //对X Y角度累加
  377.                 {
  378.                         float_x_sum += AngleX;
  379.                         float_y_sum += AngleY;
  380.                         if(++Cal_cnt >= 64)
  381.                         {
  382.                                 Cal_cnt  = 0;
  383.                                 Cal_Setp = 0;
  384.                                 a_x = float_x_sum / 64.0;
  385.                                 a_y = float_y_sum / 64.0;
  386.                                 IAP_Gyro();
  387.                                 SetBuzzer(5,1,1);
  388.                         }
  389.                 }
  390.         }
  391.         else
  392.         {
  393.                 Cal_Setp = 0;
  394.                 Cal_cnt  = 0;
  395.         }
  396. }

  397. // ===================== 主函数 =====================
  398. void main(void)
  399. {

  400.         //所有I/O口全设为准双向,弱上拉模式
  401.         P0M0=0x00;        P0M1=0x00;
  402.         P1M0=0x00;        P1M1=0x00;
  403.         P2M0=0x00;        P2M1=0x00;
  404.         P3M0=0x00;        P3M1=0x00;
  405.         P4M0=0x00;        P4M1=0x00;
  406.         P5M0=0x00;        P5M1=0x00;
  407.         P6M0=0x00;        P6M1=0x00;
  408.         P7M0=0x00;        P7M1=0x00;

  409.         PPM1 = 128;
  410.         PPM2 = 128;
  411.         PPM3 = 0;
  412.         PPM4 = 128;

  413.         PWMGO();

  414.         P_Light  = 0;
  415.         P_BUZZER = 0;
  416.         P5n_push_pull(0x30);

  417.         adc_init();    //启动A/D
  418.        
  419.         PCA_config();

  420.         delay_ms(100);
  421.         IAPRead();                //读取陀螺仪静差
  422.         InitMPU6050();        //初始化MPU-6050
  423.         delay_ms(100);

  424.         PWMCR =  0xc0;//ECBI;        //允许PWM计数器归零中断
  425.         EA = 1;        //允许总中断
  426.        
  427.         cnt_start = 0;
  428.         while(cnt_start < 25)        //等待油门最小        20ms * 25 = 500ms
  429.         {
  430.                 if(B_PPM3_OK)        //油门
  431.                 {
  432.                         B_PPM3_OK = 0;
  433.                         if(PPM3_Cap <= 1200)        cnt_start++;
  434.                 }
  435.                 delay_ms(1);
  436.         }
  437.         P_Light  = 0;
  438.        
  439.         cnt_start = 0;

  440.         SetBuzzer(5,1,1);
  441.        

  442. //==============================================
  443.         UART1_config();        // 选择波特率, 2: 使用Timer2做波特率, 其它值: 使用Timer1做波特率.
  444.         PrintString1("STC15W4K系列大四轴飞控程序!\r\n");        //SUART1发送一个字符串
  445. //==============================================

  446.         B_Start = 0;        //上电禁止运行

  447.         while(1)
  448.         {
  449.                 if(B_PPM1_OK)        //左右(横滚)
  450.                 {
  451.                         B_PPM1_OK = 0;
  452.                                  if(PPM1_Cap < 1120)        PPM1_Cap = 1120;
  453.                         else if(PPM1_Cap > 1880)        PPM1_Cap = 1880;
  454.                         PPM2 = (u8)((PPM1_Cap-1116)/3);        //转为0~255, 中间值为128
  455.                 }
  456.                
  457.                 if(B_PPM2_OK)        //前后(俯仰)
  458.                 {
  459.                         B_PPM2_OK = 0;
  460.                                  if(PPM2_Cap < 1120)        PPM2_Cap = 1120;
  461.                         else if(PPM2_Cap > 1880)        PPM2_Cap = 1880;
  462.                         PPM1 = (u8)((PPM2_Cap-1116)/3);        //转为0~255, 中间值为128
  463.                 }
  464.                
  465.                 if(B_PPM4_OK)        //航向
  466.                 {
  467.                         B_PPM4_OK = 0;
  468.                                  if(PPM4_Cap < 1056)        PPM4_Cap = 1056;
  469.                                  if(PPM4_Cap > 1940)        PPM4_Cap = 1940;
  470.                                  if(PPM4_Cap < 1440)        PPM4_Cap = PPM4_Cap + 60;
  471.                         else if(PPM4_Cap > 1560)        PPM4_Cap = PPM4_Cap - 60;
  472.                         else        PPM4_Cap = 1500;
  473.                         PPM4 = (u8)((PPM4_Cap-1116)/3);        //转为0~255, 中间值为128
  474.                 }
  475.                
  476.                 if(B_PPM3_OK)        //油门
  477.                 {
  478.                         B_PPM3_OK = 0;
  479.                         if(PPM3_Cap < 1000)        PPM3_Cap = 1000;
  480.                         if(PPM3_Cap > 1900)        PPM3_Cap = 1900;

  481.                         if(B_Start)                //正在运行时,
  482.                         {
  483.                                 PPM3 = (u8)((PPM3_Cap-1000)/4);        //转为0~255,        实际8~225
  484.                                 if(PPM3 < 32)        PPM3 = 32;
  485.                                
  486.                                 if((PPM1 < 50) && (PPM2 < 50) && (PPM3_Cap < 1120) && (PPM4 > 200))        //下外八, 禁止
  487.                                 {
  488.                                         if(++cnt_start >= 50)        //1秒
  489.                                         {
  490.                                                 cnt_start = 0;
  491.                                                 B_Start = 0;
  492.                                                 SetBuzzer(1,1,2);
  493.                                         }
  494.                                 }
  495.                                 else        cnt_start = 0;
  496.                         }
  497.                         else        //禁止运行时, 等待内八开启
  498.                         {
  499.                                 PPM3 = 0;
  500.                                 if((PPM1 < 50) && (PPM2 > 200) && (PPM3_Cap < 1120) && (PPM4 < 50))        //下内八, 启动
  501.                                 {
  502.                                         if(++cnt_start >= 50)        //1秒
  503.                                         {
  504.                                                 cnt_start = 0;
  505.                                                 B_Start = 1;
  506.                                                 SetBuzzer(5,1,1);
  507.                                         }
  508.                                 }
  509.                                 else if((PPM1 > 200) && (PPM2 > 200) && (PPM3_Cap > 1850) && (PPM4 < 50))        //上内八, 水平校准
  510.                                 {
  511.                                         if(++cnt_start >= 50)        //1秒
  512.                                         {
  513.                                                 cnt_start = 0;
  514.                                                 SetBuzzer(2,1,1);
  515.                                                 Cal_Setp = 1;
  516.                                         }
  517.                                 }
  518.                                 else if((PPM1 > 200) && (PPM2 < 50) && (PPM3_Cap > 1850) && (PPM4 > 200))        //上外八, 取消水平校准
  519.                                 {
  520.                                         if(++cnt_start >= 50)        //1秒
  521.                                         {
  522.                                                 cnt_start = 0;
  523.                                                 g_x = 0;
  524.                                                 g_y = 0;
  525.                                                 g_z = 0;
  526.                                                 a_x = 0;
  527.                                                 a_y = 0;
  528.                                                 IAP_Gyro();
  529.                                                 SetBuzzer(1,1,2);
  530.                                         }
  531.                                 }
  532.                                 else        cnt_start = 0;
  533.                         }
  534.                 }


  535.                 if(B_8ms)                //8ms到
  536.                 {
  537.                         B_8ms = 0;
  538.                        
  539.                         if(Cal_Setp != 0)        AutoCal();        //是否执行自动校准序列
  540.                         AD();                // 读ADC计算电压

  541.                         if(++cnt_100ms >= 12)        cnt_100ms = 0,        beep();        //100ms处理一次蜂鸣器

  542.                         B = cnt_ms;
  543.                         ++cnt_ms;
  544.                         B = (B ^ cnt_ms) & cnt_ms;

  545.                         if(B2)                //64ms
  546.                         {
  547.                                 if(!B_BAT_LOW && (YM_LostCnt < 120))        //电压足, 信号正常
  548.                                 {
  549.                                         if(!B_Start)        P_Light = 0;        // 空闲时, 则慢闪(每2048ms亮64ms)
  550.                                         else                         P_Light = 1;        // 启动后, 灯常亮
  551.                                 }
  552.                         }
  553.                         else if(B4)                //256ms
  554.                         {
  555.                                 if(B_BAT_LOW || (YM_LostCnt >= 120))        P_Light = ~P_Light;                //电压低, 或无信号, 航灯闪烁 2HZ
  556.                         }
  557.                         else if(B6)                //1024ms
  558.                         {
  559.                                 if(Battery < 1090)        B_BAT_LOW = 1;        else if(Battery > 1110)        B_BAT_LOW = 0;        //<10.90V电压低, >11.10V电压够
  560.                                
  561.                                 if(B_BAT_LOW)        SetBuzzer(1,1,2);        //电压低
  562.                                
  563.                                 if(B_rtn_ADC0)        Return_Message();        //请求返回ADC0数据

  564.                                 if(!B_BAT_LOW && (YM_LostCnt < 120))        P_Light = 1;        //遥控信号正常,        电压正常时
  565.                         }
  566.                         else if(B7)                //2048ms
  567.                         {
  568.                                 if(!B_BAT_LOW && (YM_LostCnt >= 120))        SetBuzzer(1,1,3);        //电压正常时 遥控信号丢失, 每两秒短鸣3次,
  569.                         }
  570.                 }


  571.                 if(UART1_cmd != 0)
  572.                 {
  573.                         if(UART1_cmd == 'a')                //PC发送a,飞控返回一些参数
  574.                         {
  575.                                 B_rtn_ADC0 = ~B_rtn_ADC0;
  576.                         }
  577.                         UART1_cmd = 0;
  578.                 }
  579.                
  580.                
  581.                 if((TX1_Read != TX1_Write) && (!B_TX1_Busy))        //有数据要发送, 并且发送空闲
  582.                 {
  583.                         SBUF = TX1_Buffer[TX1_Read];
  584.                         B_TX1_Busy = 1;
  585.                         if(++TX1_Read >= TX1_LENGTH)        TX1_Read = 0;
  586.                 }

  587.         }
  588. }

  589. //=========================================================

  590. void        Return_Message(void)
  591. {
  592.         TX1_write2buff('V');
  593.         TX1_write2buff('=');
  594.         TX1_write2buff(Battery/1000 + '0');
  595.         TX1_write2buff((Battery%1000)/100 + '0');
  596.         TX1_write2buff('.');
  597.         TX1_write2buff((Battery%100)/10 + '0');
  598.         TX1_write2buff(Battery%10 + '0');
  599.         TX1_write2buff(' ');
  600.         TX1_write2buff(' ');

  601.         PrintString1("AngleX=");
  602.         TX1_int_value((int)(AngleX * 10));

  603.         PrintString1("AngleY=");
  604.         TX1_int_value((int)(AngleY * 10));

  605.         PrintString1("AngleZ=");
  606.         TX1_int_value((int)(Angle_gz * 10));

  607.         PrintString1("a_x=");
  608.         TX1_int_value(a_x * 10);
  609.         PrintString1("a_y=");
  610.         TX1_int_value(a_y * 10);
  611.         PrintString1("g_z=");
  612.         TX1_int_value(g_z * 10);

  613.         TX1_cnt = 0;
  614.         TX1_write2buff(0x0d);
  615.         TX1_write2buff(0x0a);
  616. }


  617. void  delay_ms(u8 ms)
  618. {
  619.      u16 i;
  620.          do
  621.          {
  622.                  i = MAIN_Fosc / 13000;
  623.                 while(--i)        ;   //13T per loop
  624.      }while(--ms);
  625. }


  626. void        TX1_int_value(int i)
  627. {
  628.         if(i < 0)        TX1_write2buff('-'),        i = 0 - i;
  629.         else                TX1_write2buff(' ');
  630.         TX1_write2buff(i / 1000 + '0');
  631.         TX1_write2buff((i % 1000) / 100 + '0');
  632.         TX1_write2buff((i % 100) / 10 + '0');
  633.         TX1_write2buff('.');
  634.         TX1_write2buff(i % 10 + '0');
  635.         TX1_write2buff(' ');
  636.         TX1_write2buff(' ');
  637. }

  638. /*************** 装载串口1发送缓冲 *******************************/
  639. void TX1_write2buff(u8 dat)        //写入发送缓冲,指针+1
  640. {
  641.         TX1_Buffer[TX1_Write] = dat;
  642.         if(++TX1_Write >= TX1_LENGTH)        TX1_Write = 0;
  643. }


  644. //========================================================================
  645. // 函数: void PrintString1(u8 *puts)
  646. // 描述: 串口1发送字符串函数。
  647. // 参数: puts:  字符串指针.
  648. // 返回: none.
  649. // 版本: VER1.0
  650. // 日期: 2014-11-28
  651. // 备注:
  652. //========================================================================
  653. void PrintString1(u8 *puts)        //发送一个字符串
  654. {
  655.         for (; *puts != 0;        puts++)   TX1_write2buff(*puts);        //遇到停止符0结束
  656. }

  657. //========================================================================
  658. // 函数: SetTimer2Baudrate(u16 dat)
  659. // 描述: 设置Timer2做波特率发生器。
  660. // 参数: dat: Timer2的重装值.
  661. // 返回: none.
  662. // 版本: VER1.0
  663. // 日期: 2014-11-28
  664. // 备注:
  665. //========================================================================

  666. void        SetTimer2Baudrate(u16 dat)        // 选择波特率, 2: 使用Timer2做波特率, 其它值: 使用Timer1做波特率.
  667. {
  668.         AUXR &= ~(1<<4);        //Timer stop
  669.         AUXR &= ~(1<<3);        //Timer2 set As Timer
  670.         AUXR |=  (1<<2);        //Timer2 set as 1T mode
  671.         TH2 = dat / 256;
  672.         TL2 = dat % 256;
  673.         IE2  &= ~(1<<2);        //禁止中断
  674.         AUXR |=  (1<<4);        //Timer run enable
  675. }


  676. //========================================================================
  677. // 函数: void        UART1_config(u8 brt)
  678. // 描述: UART1初始化函数。
  679. // 参数: brt: 选择波特率, 2: 使用Timer2做波特率, 其它值: 使用Timer1做波特率.
  680. // 返回: none.
  681. // 版本: VER1.0
  682. // 日期: 2014-11-28
  683. // 备注:
  684. //========================================================================
  685. void        UART1_config(void)
  686. {
  687.         /*********** 波特率使用定时器2 *****************/
  688.         AUXR |= 0x01;                //S1 BRT Use Timer2;
  689.         SetTimer2Baudrate(65536UL - (MAIN_Fosc / 4) / Baudrate1);

  690.         /*********** 波特率使用定时器1 *****************/
  691. /*        TR1 = 0;
  692.         AUXR &= ~0x01;                //S1 BRT Use Timer1;
  693.         AUXR |=  (1<<6);        //Timer1 set as 1T mode
  694.         TMOD &= ~(1<<6);        //Timer1 set As Timer
  695.         TMOD &= ~0x30;                //Timer1_16bitAutoReload;
  696.         TH1 = (u8)((65536UL - (MAIN_Fosc / 4) / Baudrate1) / 256);
  697.         TL1 = (u8)((65536UL - (MAIN_Fosc / 4) / Baudrate1) % 256);
  698.         ET1 = 0;        //禁止中断
  699.         INT_CLKO &= ~0x02;        //不输出时钟
  700.         TR1  = 1;
  701. */        //========================================================================

  702.         SCON = (SCON & 0x3f) | 0x40;        //UART1模式, 0x00: 同步移位输出, 0x40: 8位数据,可变波特率, 0x80: 9位数据,固定波特率, 0xc0: 9位数据,可变波特率
  703.         PS  = 1;        //高优先级中断
  704.         ES  = 1;        //允许中断
  705.         REN = 1;        //允许接收
  706.         P_SW1 &= 0x3f;
  707.         P_SW1 |= 0x00;                //UART1 switch to, 0x00: P3.0 P3.1, 0x40: P3.6 P3.7, 0x80: P1.6 P1.7 (必须使用内部时钟)
  708. //        PCON2 |=  (1<<4);        //内部短路RXD与TXD, 做中继, ENABLE,DISABLE

  709.         B_TX1_Busy = 0;
  710.         TX1_Read   = 0;
  711.         TX1_Write  = 0;
  712.         UART1_cmd  = 0;
  713.         TX1_cnt    = 0;
  714. }


  715. //========================================================================
  716. // 函数: void UART1_int (void) interrupt UART1_VECTOR
  717. // 描述: UART1中断函数。
  718. // 参数: nine.
  719. // 返回: none.
  720. // 版本: VER1.0
  721. // 日期: 2014-11-28
  722. // 备注:
  723. //========================================================================
  724. void UART1_int (void) interrupt 4
  725. {
  726.         if(RI)
  727.         {
  728.                 RI = 0;
  729.                 UART1_cmd = SBUF;
  730.         }

  731.         if(TI)
  732.         {
  733.                 TI = 0;
  734.                 B_TX1_Busy = 0;
  735.         }
  736. }



  737. void        PCA_config(void)
  738. {
  739.         PPM1_Rise_TimeOut = 0;
  740.         PPM2_Rise_TimeOut = 0;
  741.         PPM3_Rise_TimeOut = 0;
  742.         PPM4_Rise_TimeOut = 0;

  743.         CR = 0;
  744.         CH = 0;
  745.         CL = 0;
  746.         AUXR1 = (AUXR1 & ~(3<<4)) | PCA_P12_P17_P16_P15_P14;        //切换IO口
  747.         CMOD  = (CMOD  & ~(7<<1)) | PCA_Clock_12T;                                //选择时钟源  STC8F8K D版本
  748. //        CMOD  = (CMOD  & ~1) | 1;                                                                //ECF
  749.         PPCA = 1;        //高优先级中断

  750.         CCAPM0     = PCA_Mode_Capture | PCA_Rise_Active | PCA_Fall_Active | ENABLE;        //工作模式, 中断模式
  751.         PCA_PWM0   = PCA_PWM_8bit;        //PWM宽度
  752. //        CCAP0L = (u8)CCAP0_tmp;                        //将影射寄存器写入捕获寄存器,先写CCAPnL
  753. //        CCAP0H = (u8)(CCAP0_tmp >> 8);        //后写CCAPnH

  754.         CCAPM1     = PCA_Mode_Capture | PCA_Rise_Active | PCA_Fall_Active | ENABLE;        //工作模式, 中断模式
  755.         PCA_PWM1   = PCA_PWM_8bit;        //PWM宽度
  756. //        CCAP1L = (u8)CCAP1_tmp;                        //将影射寄存器写入捕获寄存器,先写CCAPnL
  757. //        CCAP1H = (u8)(CCAP1_tmp >> 8);        //后写CCAPnH

  758.         CCAPM2     = PCA_Mode_Capture | PCA_Rise_Active | PCA_Fall_Active | ENABLE;        //工作模式, 中断模式
  759.         PCA_PWM2   = PCA_PWM_8bit;        //PWM宽度
  760. //        CCAP2L = (u8)CCAP2_tmp;                        //将影射寄存器写入捕获寄存器,先写CCAPnL
  761. //        CCAP2H = (u8)(CCAP2_tmp >> 8);        //后写CCAPnH

  762.         CCAPM3     = PCA_Mode_Capture | PCA_Rise_Active | PCA_Fall_Active | ENABLE;        //工作模式, 中断模式
  763.         PCA_PWM3   = PCA_PWM_8bit;        //PWM宽度
  764. //        CCAP3L = (u8)CCAP3_tmp;                        //将影射寄存器写入捕获寄存器,先写CCAPnL
  765. //        CCAP3H = (u8)(CCAP3_tmp >> 8);        //后写CCAPnH

  766.         CR = 1;
  767. }


  768. //========================================================================
  769. // 函数: void        PCA_Handler (void) interrupt PCA_VECTOR
  770. // 描述: PCA中断处理程序.
  771. // 参数: None
  772. // 返回: none.
  773. // 版本: V1.0, 2012-11-22
  774. //========================================================================
  775. void        PCA_Handler (void) interrupt PCA_VECTOR
  776. {
  777.         if(CCF0)                //PCA模块0中断
  778.         {
  779.                 CCF0 = 0;                //清PCA模块0中断标志
  780.                 if(P17)        //上升沿
  781.                 {
  782.                         CCAP0_RiseTime = ((u16)CCAP0H << 8) + CCAP0L;        //读CCAP0
  783.                         PPM1_Rise_TimeOut = 1;        //收到上升沿, 高电平限时
  784.                 }
  785.                 else        //下降沿
  786.                 {
  787.                         CCAP_FallTime = ((u16)CCAP0H << 8) + CCAP0L;        //读CCAP0
  788.                         if((PPM1_Rise_TimeOut != 0) && (PPM1_Rise_TimeOut < 3))        //收到过上升沿, 高电平也没有溢出
  789.                         {
  790.                                 CCAP_FallTime = (CCAP_FallTime - CCAP0_RiseTime) >> 1;        //为了好处理, 转成单位为us
  791.                                 if((CCAP_FallTime >= 800) && (CCAP_FallTime <= 2500))
  792.                                 {
  793.                                         if(++PPM1_RxCnt >= 5)        PPM1_RxCnt = 5;                //连续接收到5个脉冲
  794.                                         if(PPM1_RxCnt == 5)
  795.                                         {
  796.                                                 if(!B_PPM1_OK)
  797.                                                 {
  798.                                                         PPM1_Cap = CCAP_FallTime;
  799.                                                         B_PPM1_OK = 1;                //标志收到一个脉冲
  800.                                                         PPM1_Rx_TimerOut = 12;        //限时收不到脉冲
  801.                                                 }
  802.                                         }
  803.                                 }
  804.                         }
  805.                         PPM1_Rise_TimeOut = 0;
  806.                 }
  807.         }

  808.         if(CCF1)        //PCA模块1中断
  809.         {
  810.                 CCF1 = 0;                //清PCA模块1中断标志
  811.                 if(P16)        //上升沿
  812.                 {
  813.                         CCAP1_RiseTime = ((u16)CCAP1H << 8) + CCAP1L;        //读CCAP1
  814.                         PPM2_Rise_TimeOut = 1;        //收到上升沿, 高电平限时
  815.                 }
  816.                 else        //下降沿
  817.                 {
  818.                         CCAP_FallTime = ((u16)CCAP1H << 8) + CCAP1L;        //读CCAP1
  819.                         if((PPM2_Rise_TimeOut != 0) && (PPM2_Rise_TimeOut < 3))        //收到过上升沿, 高电平也没有溢出
  820.                         {
  821.                                 CCAP_FallTime = (CCAP_FallTime - CCAP1_RiseTime) >> 1;        //为了好处理, 转成单位为us
  822.                                 if((CCAP_FallTime >= 800) && (CCAP_FallTime <= 2500))
  823.                                 {
  824.                                         if(++PPM2_RxCnt >= 5)        PPM2_RxCnt = 5;
  825.                                         if(PPM2_RxCnt == 5)
  826.                                         {
  827.                                                 if(!B_PPM2_OK)
  828.                                                 {
  829.                                                         PPM2_Cap = CCAP_FallTime;
  830.                                                         B_PPM2_OK = 1;                //标志收到一个脉冲
  831.                                                         PPM2_Rx_TimerOut = 12;        //限时收不到脉冲
  832.                                                 }
  833.                                         }
  834.                                 }
  835.                         }
  836.                         PPM2_Rise_TimeOut = 0;
  837.                 }
  838.         }

  839.         if(CCF2)        //PCA模块2中断
  840.         {
  841.                 CCF2 = 0;                //清PCA模块1中断标志
  842.                 if(P15)        //上升沿
  843.                 {
  844.                         CCAP2_RiseTime = ((u16)CCAP2H << 8) + CCAP2L;        //读CCAP2
  845.                         PPM3_Rise_TimeOut = 1;        //收到上升沿, 高电平限时
  846.                 }
  847.                 else        //下降沿
  848.                 {
  849.                         CCAP_FallTime = ((u16)CCAP2H << 8) + CCAP2L;        //读CCAP2
  850.                         if((PPM3_Rise_TimeOut != 0) && (PPM3_Rise_TimeOut < 3))        //收到过上升沿, 高电平也没有溢出
  851.                         {
  852.                                 CCAP_FallTime = (CCAP_FallTime - CCAP2_RiseTime) >> 1;        //为了好处理, 转成单位为us
  853.                                 if((CCAP_FallTime >= 800) && (CCAP_FallTime <= 2500))
  854.                                 {
  855.                                         if(++PPM3_RxCnt >= 5)        PPM3_RxCnt = 5;
  856.                                         if(PPM3_RxCnt == 5)
  857.                                         {
  858.                                                 if(!B_PPM3_OK)
  859.                                                 {
  860.                                                         PPM3_Cap = CCAP_FallTime;
  861.                                                         B_PPM3_OK = 1;                //标志收到一个脉冲
  862.                                                         PPM3_Rx_TimerOut = 25;        //限时收不到脉冲
  863.                                                         YM_LostCnt = 0;
  864.                                                         Lost16S    = 0;
  865.                                                 }
  866.                                         }
  867.                                 }
  868.                         }
  869.                         PPM3_Rise_TimeOut = 0;
  870.                 }
  871.         }

  872.         if(CCF3)        //PCA模块3中断
  873.         {
  874.                 CCF3 = 0;                //清PCA模块1中断标志
  875.                 if(P14)        //上升沿
  876.                 {
  877.                         CCAP3_RiseTime = ((u16)CCAP3H << 8) + CCAP3L;        //读CCAP3
  878.                         PPM4_Rise_TimeOut = 1;        //收到上升沿, 高电平限时
  879.                 }
  880.                 else        //下降沿
  881.                 {
  882.                         CCAP_FallTime = ((u16)CCAP3H << 8) + CCAP3L;        //读CCAP3
  883.                         if((PPM4_Rise_TimeOut != 0) && (PPM4_Rise_TimeOut < 3))        //收到过上升沿, 高电平也没有溢出
  884.                         {
  885.                                 CCAP_FallTime = (CCAP_FallTime - CCAP3_RiseTime) >> 1;        //为了好处理, 转成单位为us
  886.                                 if((CCAP_FallTime >= 800) && (CCAP_FallTime <= 2500))
  887.                                 {
  888.                                         if(++PPM4_RxCnt >= 5)        PPM4_RxCnt = 5;
  889.                                         if(PPM4_RxCnt == 5)
  890.                                         {
  891.                                                 if(!B_PPM4_OK)
  892.                                                 {
  893.                                                         PPM4_Cap = CCAP_FallTime;
  894.                                                         B_PPM4_OK = 1;                //标志收到一个脉冲
  895.                                                         PPM4_Rx_TimerOut = 12;        //限时收不到脉冲
  896.                                                 }
  897.                                         }
  898.                                 }
  899.                         }
  900.                         PPM4_Rise_TimeOut = 0;
  901.                 }
  902.         }

  903. //        if(CF)        //PCA溢出中断
  904. //        {
  905. //                CF = 0;                        //清PCA溢出中断标志
  906. //        }

  907. }
复制代码
0.png

所有资料51hei提供下载:
四轴飞控-STC8A8K16S4A12-LQFP44-PPM-V10.zip (3.87 MB, 下载次数: 139)
回复

使用道具 举报

ID:138918 发表于 2018-6-3 20:38 | 显示全部楼层
好像没有人喜欢这个帖子啊
回复

使用道具 举报

ID:392801 发表于 2018-9-21 10:43 | 显示全部楼层
算法方面有吗,截图好像没有工程啊
回复

使用道具 举报

ID:440524 发表于 2019-6-26 19:51 | 显示全部楼层
感谢分享
回复

使用道具 举报

ID:490427 发表于 2019-11-3 00:26 | 显示全部楼层
没有pcb板程序呀?pcb板上的走线布置,信号处理能学习到很多知识
回复

使用道具 举报

ID:650780 发表于 2019-11-27 14:36 | 显示全部楼层
谢谢分享
回复

使用道具 举报

ID:79544 发表于 2019-12-14 15:37 | 显示全部楼层
感谢分享!!!!赞
回复

使用道具 举报

您需要登录后才可以回帖 登录 | 立即注册

本版积分规则

手机版|小黑屋|51黑电子论坛 |51黑电子论坛6群 QQ 管理员QQ:125739409;技术交流QQ群281945664

Powered by 单片机教程网

快速回复 返回顶部 返回列表