找回密碼
 立即注冊

QQ登錄

只需一步,快速開始

搜索
查看: 3859|回復(fù): 0
打印 上一主題 下一主題
收起左側(cè)

四軸飛行器 迷你飛控源碼 328P主控源碼

[復(fù)制鏈接]
跳轉(zhuǎn)到指定樓層
樓主
ID:233633 發(fā)表于 2017-9-17 13:08 | 只看該作者 |只看大圖 回帖獎勵 |倒序瀏覽 |閱讀模式
迷你飛控源碼 328P主控 四軸飛行器源碼


資料下載:
飛控程序源碼.rar (146.67 KB, 下載次數(shù): 27)

源程序:
  1. #include "Arduino.h"
  2. #include "config.h"
  3. #include "def.h"
  4. #include "types.h"
  5. #include "MultiWii.h"
  6. #include "IMU.h"
  7. #include "Sensors.h"

  8. void getEstimatedAttitude();

  9. void computeIMU () {
  10.   uint8_t axis;
  11.   static int16_t gyroADCprevious[3] = {0,0,0};
  12.   int16_t gyroADCp[3];
  13.   int16_t gyroADCinter[3];
  14.   static uint32_t timeInterleave = 0;

  15.   //we separate the 2 situations because reading gyro values with a gyro only setup can be acchieved at a higher rate
  16.   //gyro+nunchuk: we must wait for a quite high delay betwwen 2 reads to get both WM+ and Nunchuk data. It works with 3ms
  17.   //gyro only: the delay to read 2 consecutive values can be reduced to only 0.65ms
  18.   #if defined(NUNCHUCK)
  19.     annexCode();
  20.     while((uint16_t)(micros()-timeInterleave)<INTERLEAVING_DELAY) ; //interleaving delay between 2 consecutive reads
  21.     timeInterleave=micros();
  22.     ACC_getADC();
  23.     getEstimatedAttitude(); // computation time must last less than one interleaving delay
  24.     while((uint16_t)(micros()-timeInterleave)<INTERLEAVING_DELAY) ; //interleaving delay between 2 consecutive reads
  25.     timeInterleave=micros();
  26.     f.NUNCHUKDATA = 1;
  27.     while(f.NUNCHUKDATA) ACC_getADC(); // For this interleaving reading, we must have a gyro update at this point (less delay)

  28.     for (axis = 0; axis < 3; axis++) {
  29.       // empirical, we take a weighted value of the current and the previous values
  30.       // /4 is to average 4 values, note: overflow is not possible for WMP gyro here
  31.       imu.gyroData[axis] = (imu.gyroADC[axis]*3+gyroADCprevious[axis])>>2;
  32.       gyroADCprevious[axis] = imu.gyroADC[axis];
  33.     }
  34.   #else
  35.     #if ACC
  36.       ACC_getADC();
  37.       getEstimatedAttitude();
  38.     #endif
  39.     #if GYRO
  40.       Gyro_getADC();
  41.     #endif
  42.     for (axis = 0; axis < 3; axis++)
  43.       gyroADCp[axis] =  imu.gyroADC[axis];
  44.     timeInterleave=micros();
  45.     annexCode();
  46.     uint8_t t=0;
  47.     while((uint16_t)(micros()-timeInterleave)<650) t=1; //empirical, interleaving delay between 2 consecutive reads
  48.     if (!t) annex650_overrun_count++;
  49.     #if GYRO
  50.       Gyro_getADC();
  51.     #endif
  52.     for (axis = 0; axis < 3; axis++) {
  53.       gyroADCinter[axis] =  imu.gyroADC[axis]+gyroADCp[axis];
  54.       // empirical, we take a weighted value of the current and the previous values
  55.       imu.gyroData[axis] = (gyroADCinter[axis]+gyroADCprevious[axis])/3;
  56.       gyroADCprevious[axis] = gyroADCinter[axis]>>1;
  57.       if (!ACC) imu.accADC[axis]=0;
  58.     }
  59.   #endif
  60.   #if defined(GYRO_SMOOTHING)
  61.     static int16_t gyroSmooth[3] = {0,0,0};
  62.     for (axis = 0; axis < 3; axis++) {
  63.       imu.gyroData[axis] = (int16_t) ( ( (int32_t)((int32_t)gyroSmooth[axis] * (conf.Smoothing[axis]-1) )+imu.gyroData[axis]+1 ) / conf.Smoothing[axis]);
  64.       gyroSmooth[axis] = imu.gyroData[axis];
  65.     }
  66.   #elif defined(TRI)
  67.     static int16_t gyroYawSmooth = 0;
  68.     imu.gyroData[YAW] = (gyroYawSmooth*2+imu.gyroData[YAW])/3;
  69.     gyroYawSmooth = imu.gyroData[YAW];
  70.   #endif
  71. }

  72. // **************************************************
  73. // Simplified IMU based on "Complementary Filter"
  74. // Inspired by http://starlino.com/imu_guide.html
  75. //
  76. // adapted by ziss_dm : http://www.multiwii.com/forum/viewtopic.php?f=8&t=198
  77. //
  78. // The following ideas was used in this project:
  79. // 1) Rotation matrix: http://en.wikipedia.org/wiki/Rotation_matrix
  80. // 2) Small-angle approximation: http://en.wikipedia.org/wiki/Small-angle_approximation
  81. // 3) C. Hastings approximation for atan2()
  82. // 4) Optimization tricks: http://www.hackersdelight.org/
  83. //
  84. // Currently Magnetometer uses separate CF which is used only
  85. // for heading approximation.
  86. //
  87. // **************************************************

  88. //******  advanced users settings *******************
  89. /* Set the Low Pass Filter factor for ACC
  90.    Increasing this value would reduce ACC noise (visible in GUI), but would increase ACC lag time
  91.    Comment this if  you do not want filter at all.
  92.    unit = n power of 2 */
  93. // this one is also used for ALT HOLD calculation, should not be changed
  94. #ifndef ACC_LPF_FACTOR
  95.   #define ACC_LPF_FACTOR 4 // that means a LPF of 16
  96. #endif

  97. /* Set the Gyro Weight for Gyro/Acc complementary filter
  98.    Increasing this value would reduce and delay Acc influence on the output of the filter*/
  99. #ifndef GYR_CMPF_FACTOR
  100.   #define GYR_CMPF_FACTOR 600
  101. #endif

  102. /* Set the Gyro Weight for Gyro/Magnetometer complementary filter
  103.    Increasing this value would reduce and delay Magnetometer influence on the output of the filter*/
  104. #define GYR_CMPFM_FACTOR 250

  105. //****** end of advanced users settings *************
  106. #define INV_GYR_CMPF_FACTOR   (1.0f / (GYR_CMPF_FACTOR  + 1.0f))
  107. #define INV_GYR_CMPFM_FACTOR  (1.0f / (GYR_CMPFM_FACTOR + 1.0f))

  108. typedef struct fp_vector {               
  109.   float X,Y,Z;               
  110. } t_fp_vector_def;

  111. typedef union {               
  112.   float A[3];               
  113.   t_fp_vector_def V;               
  114. } t_fp_vector;

  115. typedef struct int32_t_vector {
  116.   int32_t X,Y,Z;
  117. } t_int32_t_vector_def;

  118. typedef union {
  119.   int32_t A[3];
  120.   t_int32_t_vector_def V;
  121. } t_int32_t_vector;

  122. int16_t _atan2(int32_t y, int32_t x){
  123.   float z = (float)y / x;
  124.   int16_t a;
  125.   if ( abs(y) < abs(x) ){
  126.      a = 573 * z / (1.0f + 0.28f * z * z);
  127.    if (x<0) {
  128.      if (y<0) a -= 1800;
  129.      else a += 1800;
  130.    }
  131.   } else {
  132.    a = 900 - 573 * z / (z * z + 0.28f);
  133.    if (y<0) a -= 1800;
  134.   }
  135.   return a;
  136. }

  137. float InvSqrt (float x){
  138.   union{  
  139.     int32_t i;  
  140.     float   f;
  141.   } conv;
  142.   conv.f = x;
  143.   conv.i = 0x5f3759df - (conv.i >> 1);
  144.   return 0.5f * conv.f * (3.0f - x * conv.f * conv.f);
  145. }

  146. // Rotate Estimated vector(s) with small angle approximation, according to the gyro data
  147. void rotateV(struct fp_vector *v,float* delta) {
  148.   fp_vector v_tmp = *v;
  149.   v->Z -= delta[ROLL]  * v_tmp.X + delta[PITCH] * v_tmp.Y;
  150.   v->X += delta[ROLL]  * v_tmp.Z - delta[YAW]   * v_tmp.Y;
  151.   v->Y += delta[PITCH] * v_tmp.Z + delta[YAW]   * v_tmp.X;
  152. }


  153. static int32_t accLPF32[3]    = {0, 0, 1};
  154. static float invG; // 1/|G|

  155. static t_fp_vector EstG;
  156. static t_int32_t_vector EstG32;
  157. #if MAG
  158.   static t_int32_t_vector EstM32;
  159.   static t_fp_vector EstM;
  160. #endif

  161. void getEstimatedAttitude(){
  162.   uint8_t axis;
  163.   int32_t accMag = 0;
  164.   float scale, deltaGyroAngle[3];
  165.   uint8_t validAcc;
  166.   static uint16_t previousT;
  167.   uint16_t currentT = micros();

  168.   scale = (currentT - previousT) * GYRO_SCALE; // GYRO_SCALE unit: radian/microsecond
  169.   previousT = currentT;

  170.   // Initialization
  171.   for (axis = 0; axis < 3; axis++) {
  172.     deltaGyroAngle[axis] = imu.gyroADC[axis]  * scale; // radian

  173.     accLPF32[axis]    -= accLPF32[axis]>>ACC_LPF_FACTOR;
  174.     accLPF32[axis]    += imu.accADC[axis];
  175.     imu.accSmooth[axis]    = accLPF32[axis]>>ACC_LPF_FACTOR;

  176.     accMag += (int32_t)imu.accSmooth[axis]*imu.accSmooth[axis] ;
  177.   }

  178.   rotateV(&EstG.V,deltaGyroAngle);
  179.   #if MAG
  180.     rotateV(&EstM.V,deltaGyroAngle);
  181.   #endif

  182.   accMag = accMag*100/((int32_t)ACC_1G*ACC_1G);
  183.   validAcc = 72 < (uint16_t)accMag && (uint16_t)accMag < 133;
  184.   // Apply complimentary filter (Gyro drift correction)
  185.   // If accel magnitude >1.15G or <0.85G and ACC vector outside of the limit range => we neutralize the effect of accelerometers in the angle estimation.
  186.   // To do that, we just skip filter, as EstV already rotated by Gyro
  187.   for (axis = 0; axis < 3; axis++) {
  188.     if ( validAcc )
  189.       EstG.A[axis] = (EstG.A[axis] * GYR_CMPF_FACTOR + imu.accSmooth[axis]) * INV_GYR_CMPF_FACTOR;
  190.     EstG32.A[axis] = EstG.A[axis]; //int32_t cross calculation is a little bit faster than float       
  191.     #if MAG
  192.       EstM.A[axis] = (EstM.A[axis] * GYR_CMPFM_FACTOR  + imu.magADC[axis]) * INV_GYR_CMPFM_FACTOR;
  193.       EstM32.A[axis] = EstM.A[axis];
  194.     #endif
  195.   }
  196.   
  197.   if ((int16_t)EstG32.A[2] > ACCZ_25deg)
  198.     f.SMALL_ANGLES_25 = 1;
  199.   else
  200.     f.SMALL_ANGLES_25 = 0;

  201.   // Attitude of the estimated vector
  202.   int32_t sqGX_sqGZ = sq(EstG32.V.X) + sq(EstG32.V.Z);
  203.   invG = InvSqrt(sqGX_sqGZ + sq(EstG32.V.Y));
  204.   att.angle[ROLL]  = _atan2(EstG32.V.X , EstG32.V.Z);
  205.   att.angle[PITCH] = _atan2(EstG32.V.Y , InvSqrt(sqGX_sqGZ)*sqGX_sqGZ);

  206.   #if MAG
  207.     att.heading = _atan2(
  208.       EstM32.V.Z * EstG32.V.X - EstM32.V.X * EstG32.V.Z,
  209.       (EstM.V.Y * sqGX_sqGZ  - (EstM32.V.X * EstG32.V.X + EstM32.V.Z * EstG32.V.Z) * EstG.V.Y)*invG );
  210.     att.heading += conf.mag_declination; // Set from GUI
  211.     att.heading /= 10;
  212.   #endif

  213.   #if defined(THROTTLE_ANGLE_CORRECTION)
  214.     cosZ = EstG.V.Z / ACC_1G * 100.0f;                                                        // cos(angleZ) * 100
  215.     throttleAngleCorrection = THROTTLE_ANGLE_CORRECTION * constrain(100 - cosZ, 0, 100) >>3;  // 16 bit ok: 200*150 = 30000  
  216.   #endif
  217. }

  218. #define UPDATE_INTERVAL 25000    // 40hz update rate (20hz LPF on acc)
  219. #define BARO_TAB_SIZE   21

  220. #define ACC_Z_DEADBAND (ACC_1G>>5) // was 40 instead of 32 now


  221. #define applyDeadband(value, deadband)  \
  222.   if(abs(value) < deadband) {           \
  223.     value = 0;                          \
  224.   } else if(value > 0){                 \
  225.     value -= deadband;                  \
  226.   } else if(value < 0){                 \
  227.     value += deadband;                  \
  228.   }

  229. #if BARO
  230. uint8_t getEstimatedAltitude(){
  231.   int32_t  BaroAlt;
  232.   static float baroGroundTemperatureScale,logBaroGroundPressureSum;
  233.   static float vel = 0.0f;
  234.   static uint16_t previousT;
  235.   uint16_t currentT = micros();
  236.   uint16_t dTime;

  237.   dTime = currentT - previousT;
  238.   if (dTime < UPDATE_INTERVAL) return 0;
  239.   previousT = currentT;

  240.   if(calibratingB > 0) {
  241.     logBaroGroundPressureSum = log(baroPressureSum);
  242.     baroGroundTemperatureScale = (baroTemperature + 27315) *  29.271267f;
  243.     calibratingB--;
  244.   }

  245.   // baroGroundPressureSum is not supposed to be 0 here
  246.   // see: https://code.google.com/p/ardupilot-mega/source/browse/libraries/AP_Baro/AP_Baro.cpp
  247.   BaroAlt = ( logBaroGroundPressureSum - log(baroPressureSum) ) * baroGroundTemperatureScale;

  248.   alt.EstAlt = (alt.EstAlt * 6 + BaroAlt * 2) >> 3; // additional LPF to reduce baro noise (faster by 30 µs)

  249.   #if (defined(VARIOMETER) && (VARIOMETER != 2)) || !defined(SUPPRESS_BARO_ALTHOLD)
  250.     //P
  251.     int16_t error16 = constrain(AltHold - alt.EstAlt, -300, 300);
  252.     applyDeadband(error16, 10); //remove small P parametr to reduce noise near zero position
  253.     BaroPID = constrain((conf.pid[PIDALT].P8 * error16 >>7), -150, +150);

  254.     //I
  255.     errorAltitudeI += conf.pid[PIDALT].I8 * error16 >>6;
  256.     errorAltitudeI = constrain(errorAltitudeI,-30000,30000);
  257.     BaroPID += errorAltitudeI>>9; //I in range +/-60

  258.     // projection of ACC vector to global Z, with 1G subtructed
  259.     // Math: accZ = A * G / |G| - 1G
  260.     int16_t accZ = (imu.accSmooth[ROLL] * EstG32.V.X + imu.accSmooth[PITCH] * EstG32.V.Y + imu.accSmooth[YAW] * EstG32.V.Z) * invG;

  261.     static int16_t accZoffset = 0;
  262.     if (!f.ARMED) {
  263.       accZoffset -= accZoffset>>3;
  264.       accZoffset += accZ;
  265.     }  
  266.     accZ -= accZoffset>>3;
  267.     applyDeadband(accZ, ACC_Z_DEADBAND);

  268.     static int32_t lastBaroAlt;
  269.     //int16_t baroVel = (alt.EstAlt - lastBaroAlt) * 1000000.0f / dTime;
  270.     int16_t baroVel = (alt.EstAlt - lastBaroAlt) * (1000000 / UPDATE_INTERVAL);
  271.     lastBaroAlt = alt.EstAlt;

  272.     baroVel = constrain(baroVel, -300, 300); // constrain baro velocity +/- 300cm/s
  273.     applyDeadband(baroVel, 10); // to reduce noise near zero

  274.     // Integrator - velocity, cm/sec
  275.     vel += accZ * ACC_VelScale * dTime;

  276.     // apply Complimentary Filter to keep the calculated velocity based on baro velocity (i.e. near real velocity).
  277.     // By using CF it's possible to correct the drift of integrated accZ (velocity) without loosing the phase, i.e without delay
  278.     vel = vel * 0.985f + baroVel * 0.015f;

  279.     //D
  280.     alt.vario = vel;
  281.     applyDeadband(alt.vario, 5);
  282.     BaroPID -= constrain(conf.pid[PIDALT].D8 * alt.vario >>4, -150, 150);
  283.   #endif
  284.   return 1;
  285. }
  286. #endif //BARO

復(fù)制代碼




分享到:  QQ好友和群QQ好友和群 QQ空間QQ空間 騰訊微博騰訊微博 騰訊朋友騰訊朋友
收藏收藏2 分享淘帖 頂 踩
回復(fù)

使用道具 舉報

您需要登錄后才可以回帖 登錄 | 立即注冊

本版積分規(guī)則

手機(jī)版|小黑屋|51黑電子論壇 |51黑電子論壇6群 QQ 管理員QQ:125739409;技術(shù)交流QQ群281945664

Powered by 單片機(jī)教程網(wǎng)

快速回復(fù) 返回頂部 返回列表