kalman.c
Go to the documentation of this file.
00001 #include "kalman.h"
00002 
00003 //volatile int64_t g_latest_kf_time = 0;
00004 volatile int64_t g_last_height_pkt_time = 0;
00005 
00006 float g_cos_psi;
00007 float g_sin_psi;
00008 float g_vz_p_f = 0;
00009 
00010 float g_accel_x;
00011 float g_accel_y;
00012 float g_accel_z;
00013 
00014 extern uint8_t g_kf_x_enabled;
00015 extern uint8_t g_kf_y_enabled;
00016 extern uint8_t g_kf_z_enabled;
00017 extern uint8_t g_kf_yaw_enabled;
00018 extern float g_imu_gravity;
00019 extern MAV_IMU_PKT g_imu_pkt;
00020 
00021 extern MAV_POSE2D_PKT        g_mav_pose2D_pkt;
00022 extern PacketInfo *          g_mav_pose2D_pkt_info;
00023 
00024 extern MAV_HEIGHT_PKT        g_mav_height_pkt;
00025 extern PacketInfo *          g_mav_height_pkt_info;
00026 
00027 extern MAV_KF_CFG_PKT        g_mav_kf_cfg_pkt;
00028 
00029 extern MAV_CTRL_DEBUG_PKT    g_ctrl_debug_pkt;
00030 
00031 extern unsigned int g_sdk_loops;
00032 
00033 void InitKalPos(KalPos *k)
00034 {
00035   k->Input = 0;
00036 
00037   for (int i=0; i<2; i++)
00038   {
00039     for (int j=0; j<2; j++)
00040     {
00041       if (i==j)
00042         k->A[i][j] = k->At[i][j] = k->P[i][j] = k->T[i][j] = k->I[i][j] = 1;
00043       else
00044         k->A[i][j] = k->At[i][j] = k->P[i][j] = k->T[i][j] = k->I[i][j] = 0;
00045     }
00046   }
00047 
00048   for (int i=0; i<2; i++)
00049   {
00050     for (int j=0; j<2; j++)
00051     {
00052         k->K[i][j] = k->Q[i][j] = k->R[i][j] = 0;
00053     }
00054   }
00055 
00056   for (int i=0; i<2; i++)
00057   {
00058     k->Correction[i] = k->Res[i] = 0;//KalPos->Est_out[i] =
00059   }
00060 
00061   k->Q[0][0] = k->Sigma2Q1;
00062   k->Q[1][1] = k->Sigma2Q2;
00063 
00064   k->R[0][0] = k->Sigma2R1;
00065   k->R[1][1] = k->Sigma2R2;
00066 }
00067 
00068 void InitKalYaw(KalYaw *k)
00069 {
00070   k->Q = k->Sigma2Q;
00071   k->R = k->Sigma2R;
00072   k->P = k->T = 1;
00073   k->Input = k->State = k->Correction  = 0;//KalYaw->Est_out = KalYaw->Res KalYaw->B =
00074 }
00075 
00076 void PredictPos(KalPos *k, float dt)
00077 {
00078   float dt2;
00079   float Est[2];
00080   float tmpA[2][2];
00081   float tmpB[2];
00082   float tmpA1[2][2];
00083 
00084   dt2 = (dt*dt)/2;
00085 
00086   k->A[0][1] = dt;
00087   k->At[1][0] = dt;
00088   k->B[0] = dt2;
00089   k->B[1] = dt;
00090 
00091   VectmultSc2(k->B, k->Input,tmpB);
00092   multMatVec2(k->A, k->State, Est);
00093   addVector2(Est,tmpB,k->State);
00094 
00095   // propagate covariances
00096   multMatrix2(k->A, k->T, tmpA); //mtmpA=A*T  2x2
00097   multMatrix2(tmpA, k->At, tmpA1);//mtmpC=A*T*A'  2x2
00098   addMatrix2(k->Q, tmpA1, k->P);// P = A*T*A'+ Q  2x2 matrix
00099 }
00100 
00101 void CorrectPos(KalPos *k)
00102 {
00103   // Compute Kalman gains: K = P*C'*inv(C*P*C'+R)
00104   // C matrix = Identity matrix so: K = P*inv(P + R)
00105   float tmpP[2][2];
00106   float tmpP1[2][2];
00107   float tmpVect[2];
00108 
00109   addMatrix2(k->P, k->R, tmpP); // P + R
00110   invert2(tmpP, tmpP1); // (P + R)^-1
00111   multMatrix2(k->P, tmpP1, k->K); // K = P*(P + R)^-1
00112 
00113   // compute residual as difference between sensor output and estimated output (state)
00114   subVector2(k->Correction, k->State, k->Res);
00115   multMatVec2(k->K, k->Res, tmpVect); //K*residual
00116 
00117   //apply correction
00118   k->State[0] += tmpVect[0];
00119   k->State[1] += tmpVect[1];
00120 
00121   //Compute "a posteriori " covariance matrix T = (I-K*C)*P
00122   subMatrix2(k->I, k->K,tmpP); //I-K*C
00123   multMatrix2(tmpP, k->P, k->T); //(I-K*C)*P
00124 }
00125 
00126 void PredictYaw(KalYaw *k, float dt)
00127 {
00128   float Est_yaw;
00129   Est_yaw = k->State + dt * k->Input;
00130   k->State = Est_yaw;
00131   normalizeSIAngle2Pi(&k->State);
00132   k->P = k->T + k->Q; // P = T + Q
00133 }
00134 
00135 void CorrectYaw(KalYaw *k)
00136 {
00137   k->K = (k->P) / (k->P + k->R);
00138 
00139   float Res = k->Correction - k->State;
00140   normalizeSIAnglePi(&Res);
00141 
00142   k->State += k->K * Res;
00143   normalizeSIAngle2Pi(&k->State);
00144 
00145   //Compute "a posteriori " covariance T = (I-K*C)*P
00146   k->T = (1 - k->K) * k->P;
00147 }
00148 
00149 void KFilter (void)
00150 {
00151   static unsigned short first_time = 1;
00152   //float accel_x, accel_y, accel_z;
00153   float roll, pitch, yaw, yaw_rate;
00154   float accel_x_wf, accel_y_wf, accel_z_wf;
00155   float dt = 0.001;
00156   float vz_p;
00157 
00158   vz_p = LLToSIClimb(LL_1khz_attitude_data.dheight);  // z velocity from pressure, SI
00159 
00160   g_vz_p_f = 0.995 * g_vz_p_f + 0.005 * vz_p;   // simple smoothing filter
00161 
00162   roll     = LLToSIAngleRoll (LL_1khz_attitude_data.angle_roll);
00163   pitch    = LLToSIAnglePitch(LL_1khz_attitude_data.angle_pitch);
00164 
00165   yaw_rate = LLToSIAngleRateYaw(LL_1khz_attitude_data.angvel_yaw);
00166 
00167   if (first_time == 1)
00168   {
00169     first_time = 0;
00170     resetKalmanFilter();
00171   }
00172 
00173   float cos_phi   = cos(roll);    float sin_phi   = sin(roll);
00174   float cos_theta = cos(pitch);   float sin_theta = sin(pitch);
00175 
00176   if (g_kf_yaw_enabled != 0)
00177   {
00178     yaw = kal_yaw.State;
00179   }
00180   else
00181   {
00182     yaw = LLToSIAngleYaw (LL_1khz_attitude_data.angle_yaw);
00183   }
00184 
00185   g_cos_psi = cos(yaw);
00186   g_sin_psi = sin(yaw);
00187 
00188   g_accel_x = LLToSIAccX(LL_1khz_attitude_data.acc_x);//, g_imu_gravity);
00189   g_accel_y = LLToSIAccY(LL_1khz_attitude_data.acc_y);//, g_imu_gravity);
00190   g_accel_z = LLToSIAccZ(LL_1khz_attitude_data.acc_z);//, g_imu_gravity);
00191 
00192   // body frame to world frame transform
00193 
00194   float accel_x_cos_theta = g_accel_x*cos_theta;
00195   float sin_phi_sin_theta = sin_phi*sin_theta;
00196   float cos_phi_sin_theta = cos_phi*sin_theta;
00197 
00198   accel_x_wf =  accel_x_cos_theta*g_cos_psi + g_accel_y*(sin_phi_sin_theta*g_cos_psi - cos_phi*g_sin_psi) + g_accel_z*(cos_phi_sin_theta*g_cos_psi + sin_phi*g_sin_psi);
00199   accel_y_wf =  accel_x_cos_theta*g_sin_psi + g_accel_y*(sin_phi_sin_theta*g_sin_psi + cos_phi*g_cos_psi) + g_accel_z*(cos_phi_sin_theta*g_sin_psi - sin_phi*g_cos_psi);
00200   accel_z_wf = -g_accel_x*sin_theta         + g_accel_y*sin_phi*cos_theta                                 + g_accel_z*cos_phi*cos_theta - GRAVITY_SI;
00201 
00202   g_imu_pkt.acc_x = g_accel_x;
00203   g_imu_pkt.acc_y = g_accel_y;
00204   g_imu_pkt.acc_z = g_accel_z;
00205 
00206   // debug purposes
00207   g_ctrl_debug_pkt.acc_x_wf = accel_x_wf;
00208   g_ctrl_debug_pkt.acc_y_wf = accel_y_wf;
00209   g_ctrl_debug_pkt.acc_z_wf = accel_z_wf;
00210 
00211   //dt  = (g_timestamp - g_latest_kf_time) * 0.000001;
00212   //g_latest_kf_time = g_timestamp;
00213 
00214   if (g_kf_yaw_enabled != 0)
00215   {
00216     kal_yaw.Input = yaw_rate;
00217     PredictYaw(&kal_yaw, dt);
00218     if (g_mav_pose2D_pkt_info->updated == 1)
00219     {
00220       kal_yaw.Correction = g_mav_pose2D_pkt.yaw;
00221       CorrectYaw(&kal_yaw);
00222     }
00223     kal_out.yaw_filtered = kal_yaw.State;
00224   }
00225 
00226   if (g_kf_x_enabled != 0)
00227   {
00228     kal_x.Input = accel_x_wf;
00229     PredictPos(&kal_x, dt);
00230     if (g_mav_pose2D_pkt_info->updated == 1)
00231     {
00232       kal_x.Correction[0] = g_mav_pose2D_pkt.x;
00233       kal_x.Correction[1] = g_mav_pose2D_pkt.vx;
00234       CorrectPos(&kal_x);
00235     }
00236     kal_out.pos_filtered[0] = kal_x.State[0];
00237     kal_out.vel_filtered[0] = kal_x.State[1];
00238   }
00239 
00240   if (g_kf_y_enabled != 0)
00241   {
00242     kal_y.Input = accel_y_wf;
00243     PredictPos(&kal_y, dt);
00244     if (g_mav_pose2D_pkt_info->updated==1)
00245     {
00246       kal_y.Correction[0] = g_mav_pose2D_pkt.y;
00247       kal_y.Correction[1] = g_mav_pose2D_pkt.vy;
00248       CorrectPos(&kal_y);
00249     }
00250     kal_out.pos_filtered[1] = kal_y.State[0];
00251     kal_out.vel_filtered[1] = kal_y.State[1];
00252   }
00253 
00254   if (g_kf_z_enabled != 0  )
00255   {
00256     kal_z.Input = accel_z_wf;
00257     PredictPos(&kal_z, dt);
00258 
00259     // correct z, vz from laser
00260     if (g_mav_height_pkt_info->updated == 1)
00261     {
00262       g_last_height_pkt_time = g_timestamp;
00263       kal_z.Sigma2R1 = g_mav_kf_cfg_pkt.R_z;
00264       kal_z.Sigma2R2 = g_mav_kf_cfg_pkt.R_vz;
00265       kal_z.Correction[0] = g_mav_height_pkt.z;
00266       kal_z.Correction[1] = g_mav_height_pkt.vz;
00267       CorrectPos(&kal_z);
00268     }
00269     //if (g_sdk_loops % 200 == 0 ) // old
00270     if (g_last_height_pkt_time - g_timestamp > HEIGHT_PKT_TIMEOUT)
00271     {
00272       // correct vz from pressure
00273       kal_z.Sigma2R1 = 100.00e6;//(float) g_mav_kf_cfg_pkt.R_z;
00274       kal_z.Sigma2R2 = g_mav_kf_cfg_pkt.R_vz_p;
00275       kal_z.Correction[0] = kal_z.State[0]; //force residual to zero to have the predicted state as output
00276       kal_z.Correction[1] = g_vz_p_f;
00277       CorrectPos(&kal_z);
00278     }
00279 
00280     kal_out.pos_filtered[2] = kal_z.State[0];
00281     kal_out.vel_filtered[2] = kal_z.State[1];
00282   }
00283 
00284   g_mav_pose2D_pkt_info->updated = 0;
00285   g_mav_height_pkt_info->updated = 0;
00286 }
00287 
00288 void resetKalmanFilter()
00289 {
00290   InitKalPos(&kal_x);
00291   InitKalPos(&kal_y);
00292   InitKalPos(&kal_z);
00293   InitKalYaw(&kal_yaw);
00294 }


ccny_asctec_firmware_2
Author(s): Ivan Dryanovski, Roberto G. Valenti
autogenerated on Tue Jan 7 2014 11:04:17