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

標(biāo)題: STM32F407飛控源碼 超聲波定高與循跡功能 [打印本頁(yè)]

作者: jljlyzp    時(shí)間: 2018-4-13 10:58
標(biāo)題: STM32F407飛控源碼 超聲波定高與循跡功能
STM32F407單片機(jī)的超聲波定高循跡飛控


APB1   42m
APB2   84m

TIMx clk = APBx *2

中斷優(yōu)先級(jí):

第0組:所有4位用于指定響應(yīng)優(yōu)先級(jí);
第1組:最高1位用于指定搶占式優(yōu)先級(jí),最低3位用于指定響應(yīng)優(yōu)先級(jí);
第2組:最高2位用于指定搶占式優(yōu)先級(jí),最低2位用于指定響應(yīng)優(yōu)先級(jí);
第3組:最高3位用于指定搶占式優(yōu)先級(jí),最低1位用于指定響應(yīng)優(yōu)先級(jí);
第4組:所有4位用于指定搶占式優(yōu)先級(jí)。
|先搶占,再響應(yīng)|
1)如果指定的搶占式優(yōu)先級(jí)別或響應(yīng)優(yōu)先級(jí)別超出了選定的優(yōu)先級(jí)分組所限定的范圍,將可能得到意想不到的結(jié)果;
2)搶占式優(yōu)先級(jí)別相同的中斷源之間沒(méi)有嵌套關(guān)系;
3)如果某個(gè)中斷源被指定為某個(gè)搶占式優(yōu)先級(jí)別,又沒(méi)有其它中斷源處于同一個(gè)搶占式優(yōu)先級(jí)別,則可以為這個(gè)中斷源指定任意有效的響應(yīng)優(yōu)先級(jí)別。


事件記錄,beta0.4開(kāi)始。


2015.5.18
beta 0.4  修復(fù)各種bug。



2015.5.19
beta 0.5  完善搖桿識(shí)別。


beta 0.6  pwm_in優(yōu)化


beta 0.7  修復(fù)bug,優(yōu)化rc,添加mapping


beta 0.9  起飛成功
beta 1.0  修復(fù)控制周期bug


beta 1.1  添加部分注釋

beta 1.2  優(yōu)化整定參數(shù),修改bug

beta 1.3  完成flash存儲(chǔ),上位機(jī)HID通信

beta 1.35 增加磁力計(jì)糾正航向

beta 1.36 增加磁力計(jì)校準(zhǔn)時(shí)燈管提示

beta 1.37 增加mpu6050,ak8975,ms5611自檢,未通過(guò)的LED狀態(tài)分別是:間隔連續(xù)閃爍1次;間隔連續(xù)閃爍2次;間隔連續(xù)閃爍3次

beta 1.37.1 增加滑動(dòng)窗口平均濾波函數(shù),增加ks103超聲波讀取,該版?zhèn)浞荨?br />
beta 1.37.2 添加user數(shù)據(jù),上位機(jī)顯示波形,串口超聲波改發(fā)送中斷。

beta 1.37.3 添加部分注釋,修改部分變量名,增加ano_private.lib。

beta 1.38 添加超聲波控制代碼(注意!暫未測(cè)試),修改磁力計(jì)糾正算法(重要更新),消除磁力計(jì)糾正YAW時(shí)對(duì)姿態(tài)的干擾。刪除ano_pribate.lib

beta 1.39 修復(fù)上一版數(shù)據(jù)傳輸一個(gè)小bug,添加環(huán)形緩存。

beta 1.39.1 超聲波直接控制高度,還有問(wèn)題。

beta 1.40 超聲波定高ok,暫沒(méi)優(yōu)化參數(shù),沒(méi)加上位機(jī)調(diào)參?筛膽T導(dǎo)豎直方向速率控制。

beta 1.40.1
#define CTRL_HEIGHT 1       //0失能,1使能
#define HEIGHT_MODE 1       //0,無(wú),1慣性控制高度,2氣壓計(jì)控制(空),3超聲波控制高度

beta 1.41 修復(fù)磁力計(jì)糾正的一個(gè)bug。

beta 1.42 us100超聲波定高穩(wěn)定

beta 1.43
1.模式0(呼吸白,解鎖綠長(zhǎng)),普通,油門直接輸出。模式1(呼吸淺綠,解鎖淺綠長(zhǎng)),垂直速率控制(下一步改為氣壓定高)。模式2(呼吸紫,解鎖紫長(zhǎng)),超聲波定高。
2.飛行時(shí),只能向模式0切換,其他切換無(wú)效。
3.只有插上超聲波,模式3才有效。(這個(gè)未優(yōu)化,比如臨時(shí)拔下超聲波,也能進(jìn)入該模式。)


beta 1.44
修復(fù)定高控制中積分的bug,優(yōu)化超聲波定高,優(yōu)化高度設(shè)定值調(diào)節(jié)速度。增加超聲波最大高度,可達(dá)到到1.5米比較穩(wěn)定(高度越低越穩(wěn)定)。

beta 1.46
氣壓計(jì)定高,測(cè)試版(無(wú)高度靜差修正)。

beta 1.47
氣壓計(jì)定高,測(cè)試版(無(wú)高度靜差修正)。改進(jìn)磁力計(jì)糾正算法,解決磁力計(jì)糾正時(shí)對(duì)姿態(tài)的干擾,修正磁力計(jì)糾正中180度的一個(gè)錯(cuò)誤。

beta 1.48
修復(fù)氣壓計(jì)速率的一個(gè)bug,并調(diào)整可控制的速率。

beta 1.48.1
注釋掉while(1);

beta 1.49 電賽版本,完善通信協(xié)議中串口接收通道數(shù)據(jù)部分。

beta 1.49.2 修改氣壓計(jì)定高速率環(huán)積分部分,優(yōu)化定高效果。

beta 1.49.3 濾波算法測(cè)試。

beta 1.50 修改磁力計(jì)糾正方法

beta 1.50.2 增加羅盤傾斜糾正,修復(fù)數(shù)據(jù)傳輸一個(gè)bug。

beta 1.51 修改氣壓計(jì)融合,定高控制等幾處小bug

beta 1.52 修改超聲波定高一個(gè)小bug

beta 1.6 細(xì)節(jié)優(yōu)化&新參數(shù)

beta 1.6.2 修正羅盤原始數(shù)據(jù)的一個(gè)錯(cuò)誤。

beta 1.6.2_fix 上版漏掉一句代碼,導(dǎo)致解鎖后yaw混亂,I'm sorry。。。

beta 1.6.3 新融合策略,解決加速度零點(diǎn)漂移(水平姿態(tài))。


STM32F407單片機(jī)源程序如下:
  1. /****************************************************************
  2. @本程序只供學(xué)習(xí)使用,未經(jīng)作者許可,不得用于其它任何用途
  3. +編者:普哥
  4. +描述:飛控核心控制程序(PID控制)
  5. +編寫日期:2017/3/10
  6. +版權(quán)所有,盜版必糾。
  7. ****************************************************************/

  8. #include "ctrl.h"
  9. #include "height_ctrl.h"
  10. #include "search.h"

  11. ctrl_t ctrl_1;//內(nèi)環(huán),角速度控制結(jié)構(gòu)體
  12. ctrl_t ctrl_2;//外環(huán),角度(姿態(tài))控制結(jié)構(gòu)體

  13. /*-----------------------------------------------
  14.    +實(shí)現(xiàn)功能:恢復(fù)默認(rèn)控制幅度
  15. -------------------------------------------------*/
  16. void Ctrl_Para_Init()                //設(shè)置默認(rèn)參數(shù)
  17. {
  18.   /* 微分控制幅度*/
  19.         ctrl_1.PID[PIDROLL].kdamp  = 1;
  20.         ctrl_1.PID[PIDPITCH].kdamp = 1;
  21.         ctrl_1.PID[PIDYAW].kdamp          = 1;
  22.         /* 角速度的偏差權(quán)重比例系數(shù)*/
  23.         ctrl_1.FB = 0.20;   //外  0<fb<1
  24. }

  25. xyz_f_t except_A = {0,0,0};//遙控控制期望姿態(tài)角度

  26. xyz_f_t ctrl_angle_offset = {0,0,0};//期望姿態(tài)角度偏移

  27. xyz_f_t compensation;
  28. /*----------------------------------------------------------
  29. + 實(shí)現(xiàn)功能:姿態(tài)PID控制角速度 由任務(wù)調(diào)度調(diào)用周期5ms
  30. + 調(diào)用參數(shù):兩次調(diào)用間隔
  31. ----------------------------------------------------------*/
  32. void CTRL_2(float T)   //外環(huán) 角度控制
  33. {
  34.        
  35.   /* 期望角度    遙控器控制量中心死區(qū)30 單位 微秒*/
  36.         except_A.x  = MAX_CTRL_ANGLE  *( my_deathzoom( ( CH_filter[ROL]) ,30 )/500.0f );  
  37.         except_A.y  = MAX_CTRL_ANGLE  *( my_deathzoom( (-CH_filter[PIT]) ,30 )/500.0f );  
  38.         if( Thr_Low == 0 )//遙控器控制量的油門拉起
  39.         {
  40.                 /* 期望航向姿態(tài)由遙控器航向控制積分*/
  41.                 except_A.z += (s16)( MAX_CTRL_YAW_SPEED *( my_deathzoom_2( (CH_filter[YAW]) ,40 )/500.0f ) ) *T ;  
  42.         }
  43.         else //遙控器控制量的油門低
  44.         {
  45.                 except_A.z += 1 *3.14 *T *( Yaw - except_A.z );//期望航向姿態(tài)為當(dāng)前姿態(tài)
  46.         }
  47.         except_A.z = To_180_degrees(except_A.z);//角度范圍控制在+-180角度


  48.   /* 得到角度誤差 為姿態(tài)自穩(wěn) 與 遙控器控制量 之和 */
  49.         ctrl_2.err.x =  To_180_degrees( ctrl_angle_offset.x + except_A.x - Roll  );
  50.         ctrl_2.err.y =  To_180_degrees( ctrl_angle_offset.y + except_A.y - Pitch );
  51.         ctrl_2.err.z =  To_180_degrees( ctrl_angle_offset.z + except_A.z - Yaw         );
  52.         /* 計(jì)算角度誤差權(quán)重 */
  53.         ctrl_2.err_weight.x = ABS(ctrl_2.err.x)/ANGLE_TO_MAX_AS;
  54.         ctrl_2.err_weight.y = ABS(ctrl_2.err.y)/ANGLE_TO_MAX_AS;
  55.         ctrl_2.err_weight.z = ABS(ctrl_2.err.z)/ANGLE_TO_MAX_AS;
  56.         /* 角度誤差微分(跟隨誤差曲線變化)*/
  57.         ctrl_2.err_d.x = 10 *ctrl_2.PID[PIDROLL].kd  *(ctrl_2.err.x - ctrl_2.err_old.x) *( 0.005f/T ) *( 0.65f + 0.35f *ctrl_2.err_weight.x );
  58.         ctrl_2.err_d.y = 10 *ctrl_2.PID[PIDPITCH].kd *(ctrl_2.err.y - ctrl_2.err_old.y) *( 0.005f/T ) *( 0.65f + 0.35f *ctrl_2.err_weight.y );
  59.         ctrl_2.err_d.z = 10 *ctrl_2.PID[PIDYAW].kd          *(ctrl_2.err.z - ctrl_2.err_old.z) *( 0.005f/T ) *( 0.65f + 0.35f *ctrl_2.err_weight.z );
  60.         /* 角度誤差積分 */
  61.         ctrl_2.err_i.x += ctrl_2.PID[PIDROLL].ki  *ctrl_2.err.x *T;
  62.         ctrl_2.err_i.y += ctrl_2.PID[PIDPITCH].ki *ctrl_2.err.y *T;
  63.         ctrl_2.err_i.z += ctrl_2.PID[PIDYAW].ki         *ctrl_2.err.z *T;
  64.         /* 角度誤差積分分離 */
  65.         ctrl_2.eliminate_I.x = Thr_Weight *CTRL_2_INT_LIMIT;
  66.         ctrl_2.eliminate_I.y = Thr_Weight *CTRL_2_INT_LIMIT;
  67.         ctrl_2.eliminate_I.z = Thr_Weight *CTRL_2_INT_LIMIT;
  68.         /* 角度誤差積分限幅 */
  69.         ctrl_2.err_i.x = LIMIT( ctrl_2.err_i.x, -ctrl_2.eliminate_I.x,ctrl_2.eliminate_I.x );
  70.         ctrl_2.err_i.y = LIMIT( ctrl_2.err_i.y, -ctrl_2.eliminate_I.y,ctrl_2.eliminate_I.y );
  71.         ctrl_2.err_i.z = LIMIT( ctrl_2.err_i.z, -ctrl_2.eliminate_I.z,ctrl_2.eliminate_I.z );
  72.         /* 對(duì)用于計(jì)算比例項(xiàng)輸出的角度誤差限幅 */
  73.         ctrl_2.err.x = LIMIT( ctrl_2.err.x, -90, 90 );
  74.         ctrl_2.err.y = LIMIT( ctrl_2.err.y, -90, 90 );
  75.         ctrl_2.err.z = LIMIT( ctrl_2.err.z, -90, 90 );
  76.         /* 角度PID輸出 */
  77.         ctrl_2.out.x = ctrl_2.PID[PIDROLL].kp  *( ctrl_2.err.x + ctrl_2.err_d.x + ctrl_2.err_i.x );        //rol
  78.         ctrl_2.out.y = ctrl_2.PID[PIDPITCH].kp *( ctrl_2.err.y + ctrl_2.err_d.y + ctrl_2.err_i.y );  //pit
  79.         ctrl_2.out.z = ctrl_2.PID[PIDYAW].kp   *( ctrl_2.err.z + ctrl_2.err_d.z + ctrl_2.err_i.z );
  80.         /* 記錄歷史數(shù)據(jù) */       
  81.         ctrl_2.err_old.x = ctrl_2.err.x;
  82.         ctrl_2.err_old.y = ctrl_2.err.y;
  83.         ctrl_2.err_old.z = ctrl_2.err.z;

  84. }

  85. xyz_f_t except_AS;//期望角速度
  86. float g_old[ITEMS];//記錄的陀螺儀數(shù)據(jù)
  87. /*----------------------------------------------------------
  88. + 實(shí)現(xiàn)功能:角速度電機(jī)輸出量 由任務(wù)調(diào)度調(diào)用周期2ms
  89. + 調(diào)用參數(shù):兩次調(diào)用間隔
  90. ----------------------------------------------------------*/
  91. void CTRL_1(float T)  //x roll,y pitch,z yaw內(nèi)環(huán) 角速度控制
  92. {
  93.         xyz_f_t EXP_LPF_TMP;//期望角速度
  94.         /* 給期望(目標(biāo))角速度 */
  95.         EXP_LPF_TMP.x = MAX_CTRL_ASPEED *(ctrl_2.out.x/ANGLE_TO_MAX_AS);
  96.         EXP_LPF_TMP.y = MAX_CTRL_ASPEED *(ctrl_2.out.y/ANGLE_TO_MAX_AS);
  97.         EXP_LPF_TMP.z = MAX_CTRL_ASPEED *(ctrl_2.out.z/ANGLE_TO_MAX_AS);
  98.         /* 期望角速度*/
  99.         except_AS.x = EXP_LPF_TMP.x;
  100.         except_AS.y = EXP_LPF_TMP.y;
  101.         except_AS.z = EXP_LPF_TMP.z;
  102.         /* 期望角速度限幅 */
  103.         except_AS.x = LIMIT(except_AS.x, -MAX_CTRL_ASPEED,MAX_CTRL_ASPEED );   //-300到300之間
  104.         except_AS.y = LIMIT(except_AS.y, -MAX_CTRL_ASPEED,MAX_CTRL_ASPEED );
  105.         except_AS.z = LIMIT(except_AS.z, -MAX_CTRL_ASPEED,MAX_CTRL_ASPEED );

  106.         /* 角速度直接微分(角加速度),負(fù)反饋可形成角速度的阻尼(阻礙角速度的變化)*/
  107.         ctrl_1.damp.x = ( mpu6050.Gyro_deg.x - g_old[A_X]) *( 0.002f/T );
  108.         ctrl_1.damp.y = (-mpu6050.Gyro_deg.y - g_old[A_Y]) *( 0.002f/T );
  109.         ctrl_1.damp.z = (-mpu6050.Gyro_deg.z - g_old[A_Z]) *( 0.002f/T );
  110.         /* 角速度誤差 */
  111.         ctrl_1.err.x =  ( except_AS.x - mpu6050.Gyro_deg.x ) *(300.0f/MAX_CTRL_ASPEED);
  112.         ctrl_1.err.y =  ( except_AS.y + mpu6050.Gyro_deg.y ) *(300.0f/MAX_CTRL_ASPEED);  //-y
  113.         ctrl_1.err.z =  ( except_AS.z + mpu6050.Gyro_deg.z ) *(300.0f/MAX_CTRL_ASPEED);         //-z
  114.         /* 角速度誤差權(quán)重 */
  115.         ctrl_1.err_weight.x = ABS(ctrl_1.err.x)/MAX_CTRL_ASPEED;
  116.         ctrl_1.err_weight.y = ABS(ctrl_1.err.y)/MAX_CTRL_ASPEED;
  117.         ctrl_1.err_weight.z = ABS(ctrl_1.err.z)/MAX_CTRL_YAW_SPEED;
  118.         /* 角速度微分 */
  119.         ctrl_1.err_d.x = ( ctrl_1.PID[PIDROLL].kd  *( -10 *ctrl_1.damp.x) *( 0.002f/T ) );
  120.         ctrl_1.err_d.y = ( ctrl_1.PID[PIDPITCH].kd *( -10 *ctrl_1.damp.y) *( 0.002f/T ) );
  121.         ctrl_1.err_d.z = ( ctrl_1.PID[PIDYAW].kd   *( -10 *ctrl_1.damp.z) *( 0.002f/T ) );
  122.         /* 角速度誤差積分 */
  123.         ctrl_1.err_i.x += ctrl_1.PID[PIDROLL].ki  *(ctrl_1.err.x - ctrl_1.damp.x) *T;
  124.         ctrl_1.err_i.y += ctrl_1.PID[PIDPITCH].ki *(ctrl_1.err.y - ctrl_1.damp.y) *T;
  125.         ctrl_1.err_i.z += ctrl_1.PID[PIDYAW].ki         *(ctrl_1.err.z - ctrl_1.damp.z) *T;
  126.         /* 角速度誤差積分分離 */
  127.         ctrl_1.eliminate_I.x = Thr_Weight *CTRL_1_INT_LIMIT ;
  128.         ctrl_1.eliminate_I.y = Thr_Weight *CTRL_1_INT_LIMIT ;
  129.         ctrl_1.eliminate_I.z = Thr_Weight *CTRL_1_INT_LIMIT ;
  130.         /* 角速度誤差積分限幅 */
  131.         ctrl_1.err_i.x = LIMIT( ctrl_1.err_i.x, -ctrl_1.eliminate_I.x,ctrl_1.eliminate_I.x );
  132.         ctrl_1.err_i.y = LIMIT( ctrl_1.err_i.y, -ctrl_1.eliminate_I.y,ctrl_1.eliminate_I.y );
  133.         ctrl_1.err_i.z = LIMIT( ctrl_1.err_i.z, -ctrl_1.eliminate_I.z,ctrl_1.eliminate_I.z );
  134.         /* 角速度PID輸出 */
  135.         ctrl_1.out.x = 3 *( ctrl_1.FB *LIMIT((0.45f + 0.55f*ctrl_2.err_weight.x),0,1)*except_AS.x + ( 1 - ctrl_1.FB ) *ctrl_1.PID[PIDROLL].kp  *( ctrl_1.err.x + ctrl_1.err_d.x + ctrl_1.err_i.x ) );
  136.         ctrl_1.out.y = 3 *( ctrl_1.FB *LIMIT((0.45f + 0.55f*ctrl_2.err_weight.y),0,1)*except_AS.y + ( 1 - ctrl_1.FB ) *ctrl_1.PID[PIDPITCH].kp *( ctrl_1.err.y + ctrl_1.err_d.y + ctrl_1.err_i.y ) );                                                                               
  137.         ctrl_1.out.z = 3 *( ctrl_1.FB *LIMIT((0.45f + 0.55f*ctrl_2.err_weight.z),0,1)*except_AS.z + ( 1 - ctrl_1.FB ) *ctrl_1.PID[PIDYAW].kp   *( ctrl_1.err.z + ctrl_1.err_d.z + ctrl_1.err_i.z ) );
  138.                                                                        
  139.         Thr_Ctrl(T);// 電機(jī)油門量控制
  140.        
  141.         All_Out(ctrl_1.out.x,ctrl_1.out.y,ctrl_1.out.z);//角速度控制量轉(zhuǎn)換到電機(jī)轉(zhuǎn)速的輸出量
  142.    /* 記錄角速度誤差積分*/
  143.         ctrl_1.err_old.x = ctrl_1.err.x;
  144.         ctrl_1.err_old.y = ctrl_1.err.y;
  145.         ctrl_1.err_old.z = ctrl_1.err.z;
  146.   /* 記錄角速度數(shù)據(jù)*/
  147.         g_old[A_X] =  mpu6050.Gyro_deg.x ;
  148.         g_old[A_Y] = -mpu6050.Gyro_deg.y ;
  149.         g_old[A_Z] = -mpu6050.Gyro_deg.z ;
  150. }


  151. float thr_value;//油門賦值
  152. u8 Thr_Low;//低油門信號(hào)判斷
  153. float Thr_Weight; //濾波后油門數(shù)據(jù)
  154. /*----------------------------------------------------------
  155. + 實(shí)現(xiàn)功能:油門信號(hào)控制
  156. + 調(diào)用參數(shù):兩次調(diào)用間隔
  157. ----------------------------------------------------------*/
  158. void Thr_Ctrl(float T)      
  159. {
  160.         static float thr;//油門值
  161.         static float Thr_tmp;//濾波后的油門值
  162.        
  163.         thr = 500 + CH_filter[THR]; //油門值范圍 0 ~ 1000
  164.         Thr_tmp += 10 *3.14f *T *(thr/400.0f - Thr_tmp); //低通濾玻,油門數(shù)據(jù)積分濾波
  165.         Thr_Weight = LIMIT(Thr_tmp,0,1);// 濾波后油門數(shù)據(jù)限幅,后邊多處分離數(shù)據(jù)會(huì)用到這個(gè)值
  166.        
  167.         if( thr < 100 )//低油門信號(hào)判斷
  168.         {
  169.                 Thr_Low = 1;
  170.         }
  171.         else
  172.         {
  173.                 Thr_Low = 0;
  174.         }
  175.         /* 允許高度控制*/
  176.         #if(CTRL_HEIGHT)
  177.         Height_Ctrl(T,thr);//油門控制高度
  178.        
  179.         thr_value = Thr_Weight *height_ctrl_out; //油門賦值
  180.         #else
  181.         thr_value = thr;   //實(shí)際使用值
  182.         #endif
  183.        
  184.         thr_value = LIMIT(thr_value,0,10 *MAX_THR *MAX_PWM/100);//油門限幅
  185. }


  186. float motor[MAXMOTORS];//電機(jī)數(shù)量
  187. float posture_value[MAXMOTORS];//姿態(tài)作用于電機(jī)位置的控制量
  188. float curve[MAXMOTORS];//姿態(tài)對(duì)電機(jī)的實(shí)際控制量
  189. /*----------------------------------------------------------
  190. + 實(shí)現(xiàn)功能:角速度控制量 轉(zhuǎn)換到電機(jī)轉(zhuǎn)速的輸出量
  191. + 調(diào)用參數(shù):角速度控制量
  192. ----------------------------------------------------------*/
  193. void All_Out(float out_roll,float out_pitch,float out_yaw)
  194. {
  195.         s16 motor_out[MAXMOTORS];
  196.         u8 i;//循環(huán)計(jì)數(shù)變量
  197.         float posture_value[MAXMOTORS];//姿態(tài)作用于電機(jī)位置的控制量
  198.   float curve[MAXMOTORS];//姿態(tài)對(duì)電機(jī)的實(shí)際控制量
  199.        
  200.         float Line_Out=0,Line_LR_Out=0;//尋線PID輸出
  201.         float Point_X=0,Point_Y=0;//定點(diǎn)PID輸出
  202.        
  203.         /* 允許循跡控制*/
  204.         #if(CTRL_SEARCH)
  205.   Line_Out    =  Line_ctrl_out;                                        //循跡偏移PID輸出
  206.         Line_LR_Out =  Line_LR_ctrl_out;                        //循跡偏移PID輸出
  207.         Point_X     =  Point_X_ctrl_out;                        //左右定點(diǎn)PID輸出
  208.         Point_Y     =  Point_Y_ctrl_out;                        //前后定點(diǎn)PID輸出
  209.        
  210.         #else
  211.         Line_Out    =  0
  212.         Line_LR_Out =  0
  213.         Point_X     =  0
  214.         Point_Y     =  0
  215.         #endif
  216.        
  217.   /* 航向的角速度控制量限幅 防止動(dòng)力不足*/
  218.         out_yaw = LIMIT( out_yaw , -5*MAX_THR ,5*MAX_THR ); //50%
  219.        
  220.         /*默認(rèn)是四旋翼X模式,CCW是從上方向下看逆時(shí)針選擇,CW與CCW剛好相反,
  221.         注意前方偏右是連接1號(hào)電機(jī)電調(diào),逆時(shí)針順序依次是2開(kāi)始
  222.                        CW2        1CCW
  223.                             \   /
  224.                             /   \
  225.                        CCW3      4CW              */
  226.         posture_value[0] = - out_roll + out_pitch + out_yaw - Line_Out -Point_X -Point_Y -Line_LR_Out ;//右前方,CCW
  227.         posture_value[1] = + out_roll + out_pitch - out_yaw + Line_Out +Point_X -Point_Y -Line_LR_Out ;//左前方,CW
  228.         posture_value[2] = + out_roll - out_pitch + out_yaw + Line_Out +Point_X +Point_Y +Line_LR_Out;//左后方,CCW
  229.         posture_value[3] = - out_roll - out_pitch - out_yaw - Line_Out -Point_X +Point_Y +Line_LR_Out ;//右后方,CW
  230.        
  231.         for(i=0;i<4;i++)//作用于電機(jī)位置的控制量
  232.         {
  233.                 posture_value[i] = LIMIT(posture_value[i], -1000,1000 );//姿態(tài)作用于電機(jī)位置的控制量限幅
  234.         }
  235.         /* 姿態(tài)對(duì)電機(jī)的實(shí)際控制量*/
  236.         curve[0] = (0.55f + 0.45f *ABS(posture_value[0])/1000.0f) *posture_value[0] ;
  237.         curve[1] = (0.55f + 0.45f *ABS(posture_value[1])/1000.0f) *posture_value[1] ;
  238.         curve[2] = (0.55f + 0.45f *ABS(posture_value[2])/1000.0f) *posture_value[2] ;
  239.         curve[3] = (0.55f + 0.45f *ABS(posture_value[3])/1000.0f) *posture_value[3] ;
  240.         /* 單個(gè)電機(jī)的總控制量*/
  241.   motor[0] = thr_value + Thr_Weight *curve[0] ;
  242.         motor[1] = thr_value + Thr_Weight *curve[1] ;
  243.         motor[2] = thr_value + Thr_Weight *curve[2] ;
  244.         motor[3] = thr_value + Thr_Weight *curve[3] ;
  245.         /* 是否解鎖 */
  246.         if(fly_ready)//已經(jīng)解鎖
  247.         {
  248.                 if( !Thr_Low )  //遙控器的控制量油門拉起
  249.                 {
  250.                         for(i=0;i<4;i++)
  251.                         {
  252.                                 /* 保證大于在電機(jī)最小起轉(zhuǎn)轉(zhuǎn)速*/
  253.                                 motor[i] = LIMIT(motor[i], (10 *READY_SPEED),(10*MAX_PWM) );
  254.                         }
  255.                 }
  256.                 else        //遙控器控制量的油門低
  257.                 {
  258.                         for(i=0;i<4;i++)
  259.                         {
  260.                                 motor[i] = LIMIT(motor[i], 0,(10*MAX_PWM) );
  261.                         }
  262.                 }
  263.         }
  264.         else//未解鎖
  265.         {
  266.                 for(i=0;i<4;i++)//電機(jī)停轉(zhuǎn)
  267.                 {
  268.                         motor[i] = 0;
  269.                 }
  270.         }
  271.         /* int16到float數(shù)據(jù)類型轉(zhuǎn)換*/
  272. ……………………

  273. …………限于本文篇幅 余下代碼請(qǐng)從51黑下載附件…………
復(fù)制代碼

所有資料51hei提供下載:
F407_FC_ANO - 超聲波定高_(dá)循跡.rar (2.15 MB, 下載次數(shù): 108)




作者: plyl    時(shí)間: 2018-5-16 16:16
收藏一波,樓主666
作者: 阿斯頓馬丁    時(shí)間: 2018-6-24 20:01
學(xué)習(xí)。。。。。。。。。。。!1
作者: wuxishun    時(shí)間: 2018-6-25 06:13
有電路原理圖嗎?
作者: 丿維灬納    時(shí)間: 2019-4-1 16:08
不是尋跡的
作者: 1320081644    時(shí)間: 2019-5-20 11:19
樓主,這個(gè)上位機(jī)軟件能分享下不?
作者: 810780579    時(shí)間: 2019-8-7 08:47
來(lái)學(xué)習(xí)下,需要資料
作者: happynocn    時(shí)間: 2019-8-7 09:03
謝謝分享,下載收藏了。
作者: zhukm    時(shí)間: 2019-12-27 10:53
謝謝分享,下載收藏




歡迎光臨 (http://www.zg4o1577.cn/bbs/) Powered by Discuz! X3.1
主站蜘蛛池模板: 丁香久久 | 青青草视频免费观看 | 亚洲日本乱码在线观看 | 日韩在线观看 | 日韩欧美一区二区三区 | 91精品国产综合久久福利软件 | 三a毛片| 成人在线精品 | 国产精品欧美一区二区三区不卡 | 日韩精品在线观看视频 | 国产黄a一级 | 国产又色又爽又黄又免费 | 亚洲欧美日韩中文在线 | av资源中文在线 | av 一区二区三区 | 精品亚洲一区二区三区 | 亚洲综合色视频在线观看 | 天天影视网天天综合色在线播放 | 亚洲天堂中文字幕 | 日一区二区| 久久精品高清视频 | 成人亚洲精品久久久久软件 | 亚洲精品在线视频 | 国产精品久久久久久一区二区三区 | 久久国产精品偷 | 国产成人一区二区三区精 | www国产亚洲精品久久网站 | 欧美性受xxxx白人性爽 | 国产精品久久久久aaaa | 在线免费观看色 | 在线观看精品视频网站 | 欧美性生交大片免费 | 国产高清视频一区 | 国户精品久久久久久久久久久不卡 | 久久亚洲春色中文字幕久久久 | 成人欧美一区二区三区黑人孕妇 | 久久久久久高潮国产精品视 | 久草在线青青草 | 亚洲精品2区 | 伊人久久综合 | 91中文在线观看 |