久久久久久久999_99精品久久精品一区二区爱城_成人欧美一区二区三区在线播放_国产精品日本一区二区不卡视频_国产午夜视频_欧美精品在线观看免费

 找回密碼
 立即注冊

QQ登錄

只需一步,快速開始

搜索
查看: 12186|回復: 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, 下載次數: 144)
回復

使用道具 舉報

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 單片機教程網

快速回復 返回頂部 返回列表
主站蜘蛛池模板: 超碰在线网站 | av大片| 91 在线| 国产99久久 | 91传媒在线播放 | 夫妻午夜影院 | 久久久国产一区二区三区四区小说 | 欧美精品一区二区三区在线 | 国产免费黄网 | 亚洲精品 在线播放 | 国产精品视频免费观看 | 亚洲精品在 | 国产乱码精品1区2区3区 | 亚洲成人免费在线观看 | 亚洲人成人一区二区在线观看 | 九九热在线视频免费观看 | 韩日在线 | 欧美日韩国产精品 | 伊人伊成久久人综合网站 | 国产日产精品一区二区三区四区 | 夜夜爽99久久国产综合精品女不卡 | 中文字幕国产一区 | 日韩和的一区二区 | 国产欧美在线播放 | 日韩在线小视频 | 亚洲va在线va天堂va狼色在线 | 啪一啪 | 在线成人免费视频 | 久久伊人精品 | 天天插天天操 | 欧美极品在线观看 | 一区二区三区精品在线 | 国产精品美女久久久久aⅴ国产馆 | 天天操夜夜操免费视频 | 婷婷免费在线 | 国产午夜精品一区二区三区嫩草 | 久久精品国产精品青草 | 欧美亚洲国产日韩 | 欧美激情啪啪 | 91九色视频 | 免费的一级视频 |