예제 #1
0
/*
 * function [eulerAngles,Rot_matrix,x_aposteriori,P_aposteriori] = attitudeKalmanfilter_wo(updateVect,dt,z,x_aposteriori_k,P_aposteriori_k,q,r)
 */
void attitudeKalmanfilter(const uint8_T updateVect[3], real32_T dt, const
  real32_T z[9], const real32_T x_aposteriori_k[12], const real32_T
  P_aposteriori_k[144], const real32_T q[12], const real32_T r[9], real32_T
  eulerAngles[3], real32_T Rot_matrix[9], real32_T x_aposteriori[12], real32_T
  P_aposteriori[144])
{
  real32_T a[12];
  int32_T i;
  real32_T b_a[12];
  real32_T Q[144];
  real32_T O[9];
  real_T dv0[9];
  real32_T c_a[9];
  real32_T d_a[9];
  real32_T x_n_b[3];
  real32_T z_n_b[3];
  real32_T x_apriori[12];
  real32_T y_n_b[3];
  int32_T i0;
  real32_T e_a[3];
  real_T dv1[144];
  real32_T A_lin[144];
  real32_T b_A_lin[144];
  int32_T i1;
  real32_T y;
  real32_T P_apriori[144];
  real32_T R[81];
  real32_T b_P_apriori[108];
  static const int8_T iv0[108] = { 1, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0,
    0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
    0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
    0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
    0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1 };

  real32_T K_k[108];
  static const int8_T iv1[108] = { 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0,
    0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0,
    0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0,
    1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0,
    0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1 };

  real32_T fv0[81];
  real32_T c_P_apriori[36];
  static const int8_T iv2[36] = { 1, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0,
    1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 1, 0, 0, 0, 0, 0, 0 };

  real32_T fv1[36];
  static const int8_T iv3[36] = { 1, 0, 0, 0, 1, 0, 0, 0, 1, 1, 0, 0, 0, 1, 0, 0,
    0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 };

  real32_T S_k[36];
  real32_T d_P_apriori[72];
  static const int8_T iv4[72] = { 1, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0,
    1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
    1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
    1, 0, 0, 0 };

  real32_T b_K_k[72];
  static const int8_T iv5[72] = { 1, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 1, 0,
    0, 0, 1, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 1, 0, 0,
    0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
    0, 0, 0, 0 };

  real32_T b_r[6];
  static const int8_T iv6[72] = { 1, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 1, 0,
    0, 0, 1, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0,
    0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0,
    0, 0, 0, 1 };

  static const int8_T iv7[72] = { 1, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0,
    1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
    0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0,
    0, 0, 0, 1 };

  real32_T fv2[6];
  real32_T b_z[6];
  real32_T b_y;

  /*  Extended Attitude Kalmanfilter */
  /*  */
  /*  state vector x has the following entries [ax,ay,az||mx,my,mz||wox,woy,woz||wx,wy,wz]' */
  /*  measurement vector z has the following entries [ax,ay,az||mx,my,mz||wmx,wmy,wmz]' */
  /*  knownConst has the following entries [PrvaA,PrvarM,PrvarWO,PrvarW||MsvarA,MsvarM,MsvarW] */
  /*  */
  /*  [x_aposteriori,P_aposteriori] = AttKalman(dt,z_k,x_aposteriori_k,P_aposteriori_k,knownConst) */
  /*  */
  /*  Example.... */
  /*  */
  /*  $Author: Tobias Naegeli $    $Date: 2012 $    $Revision: 1 $ */
  /* coder.varsize('udpIndVect', [9,1], [1,0]) */
  /* udpIndVect=find(updVect); */
  /* process and measurement noise covariance matrix */
  /* 'attitudeKalmanfilter:27' Q = diag(q.^2*dt); */
  power(q, 2.0, a);
  for (i = 0; i < 12; i++) {
    b_a[i] = a[i] * dt;
  }

  diag(b_a, Q);

  /* observation matrix */
  /* 'attitudeKalmanfilter:37' wx=  x_aposteriori_k(1); */
  /* 'attitudeKalmanfilter:38' wy=  x_aposteriori_k(2); */
  /* 'attitudeKalmanfilter:39' wz=  x_aposteriori_k(3); */
  /* 'attitudeKalmanfilter:41' wox=  x_aposteriori_k(4); */
  /* 'attitudeKalmanfilter:42' woy=  x_aposteriori_k(5); */
  /* 'attitudeKalmanfilter:43' woz=  x_aposteriori_k(6); */
  /* 'attitudeKalmanfilter:45' zex=  x_aposteriori_k(7); */
  /* 'attitudeKalmanfilter:46' zey=  x_aposteriori_k(8); */
  /* 'attitudeKalmanfilter:47' zez=  x_aposteriori_k(9); */
  /* 'attitudeKalmanfilter:49' mux=  x_aposteriori_k(10); */
  /* 'attitudeKalmanfilter:50' muy=  x_aposteriori_k(11); */
  /* 'attitudeKalmanfilter:51' muz=  x_aposteriori_k(12); */
  /* 'attitudeKalmanfilter:54' wk =[wx; */
  /* 'attitudeKalmanfilter:55'      wy; */
  /* 'attitudeKalmanfilter:56'      wz]; */
  /* 'attitudeKalmanfilter:58' wok =[wox;woy;woz]; */
  /* 'attitudeKalmanfilter:59' O=[0,-wz,wy;wz,0,-wx;-wy,wx,0]'; */
  O[0] = 0.0F;
  O[1] = -x_aposteriori_k[2];
  O[2] = x_aposteriori_k[1];
  O[3] = x_aposteriori_k[2];
  O[4] = 0.0F;
  O[5] = -x_aposteriori_k[0];
  O[6] = -x_aposteriori_k[1];
  O[7] = x_aposteriori_k[0];
  O[8] = 0.0F;

  /* 'attitudeKalmanfilter:60' zek =(eye(3)+O*dt)*[zex;zey;zez]; */
  eye(dv0);
  for (i = 0; i < 9; i++) {
    c_a[i] = (real32_T)dv0[i] + O[i] * dt;
  }

  /* 'attitudeKalmanfilter:61' muk =(eye(3)+O*dt)*[mux;muy;muz]; */
  eye(dv0);
  for (i = 0; i < 9; i++) {
    d_a[i] = (real32_T)dv0[i] + O[i] * dt;
  }

  /* 'attitudeKalmanfilter:63' EZ=[0,zez,-zey; */
  /* 'attitudeKalmanfilter:64'     -zez,0,zex; */
  /* 'attitudeKalmanfilter:65'     zey,-zex,0]'; */
  /* 'attitudeKalmanfilter:66' MA=[0,muz,-muy; */
  /* 'attitudeKalmanfilter:67'     -muz,0,mux; */
  /* 'attitudeKalmanfilter:68'     zey,-mux,0]'; */
  /* 'attitudeKalmanfilter:72' E=eye(3); */
  /* 'attitudeKalmanfilter:73' Z=zeros(3); */
  /* 'attitudeKalmanfilter:74' x_apriori=[wk;wok;zek;muk]; */
  x_n_b[0] = x_aposteriori_k[6];
  x_n_b[1] = x_aposteriori_k[7];
  x_n_b[2] = x_aposteriori_k[8];
  z_n_b[0] = x_aposteriori_k[9];
  z_n_b[1] = x_aposteriori_k[10];
  z_n_b[2] = x_aposteriori_k[11];
  x_apriori[0] = x_aposteriori_k[0];
  x_apriori[1] = x_aposteriori_k[1];
  x_apriori[2] = x_aposteriori_k[2];
  x_apriori[3] = x_aposteriori_k[3];
  x_apriori[4] = x_aposteriori_k[4];
  x_apriori[5] = x_aposteriori_k[5];
  for (i = 0; i < 3; i++) {
    y_n_b[i] = 0.0F;
    for (i0 = 0; i0 < 3; i0++) {
      y_n_b[i] += c_a[i + 3 * i0] * x_n_b[i0];
    }

    e_a[i] = 0.0F;
    for (i0 = 0; i0 < 3; i0++) {
      e_a[i] += d_a[i + 3 * i0] * z_n_b[i0];
    }

    x_apriori[i + 6] = y_n_b[i];
  }

  for (i = 0; i < 3; i++) {
    x_apriori[i + 9] = e_a[i];
  }

  /* 'attitudeKalmanfilter:76' A_lin=[ Z,  Z,  Z,  Z */
  /* 'attitudeKalmanfilter:77'         Z,  Z,  Z,  Z */
  /* 'attitudeKalmanfilter:78'         EZ, Z,  O,  Z */
  /* 'attitudeKalmanfilter:79'         MA, Z,  Z,  O]; */
  /* 'attitudeKalmanfilter:82' A_lin=eye(12)+A_lin*dt; */
  b_eye(dv1);
  for (i = 0; i < 12; i++) {
    for (i0 = 0; i0 < 3; i0++) {
      A_lin[i0 + 12 * i] = 0.0F;
    }

    for (i0 = 0; i0 < 3; i0++) {
      A_lin[(i0 + 12 * i) + 3] = 0.0F;
    }
  }

  A_lin[6] = 0.0F;
  A_lin[7] = x_aposteriori_k[8];
  A_lin[8] = -x_aposteriori_k[7];
  A_lin[18] = -x_aposteriori_k[8];
  A_lin[19] = 0.0F;
  A_lin[20] = x_aposteriori_k[6];
  A_lin[30] = x_aposteriori_k[7];
  A_lin[31] = -x_aposteriori_k[6];
  A_lin[32] = 0.0F;
  for (i = 0; i < 3; i++) {
    for (i0 = 0; i0 < 3; i0++) {
      A_lin[(i0 + 12 * (i + 3)) + 6] = 0.0F;
    }
  }

  for (i = 0; i < 3; i++) {
    for (i0 = 0; i0 < 3; i0++) {
      A_lin[(i0 + 12 * (i + 6)) + 6] = O[i0 + 3 * i];
    }
  }

  for (i = 0; i < 3; i++) {
    for (i0 = 0; i0 < 3; i0++) {
      A_lin[(i0 + 12 * (i + 9)) + 6] = 0.0F;
    }
  }

  A_lin[9] = 0.0F;
  A_lin[10] = x_aposteriori_k[11];
  A_lin[11] = -x_aposteriori_k[10];
  A_lin[21] = -x_aposteriori_k[11];
  A_lin[22] = 0.0F;
  A_lin[23] = x_aposteriori_k[9];
  A_lin[33] = x_aposteriori_k[7];
  A_lin[34] = -x_aposteriori_k[9];
  A_lin[35] = 0.0F;
  for (i = 0; i < 3; i++) {
    for (i0 = 0; i0 < 3; i0++) {
      A_lin[(i0 + 12 * (i + 3)) + 9] = 0.0F;
    }
  }

  for (i = 0; i < 3; i++) {
    for (i0 = 0; i0 < 3; i0++) {
      A_lin[(i0 + 12 * (i + 6)) + 9] = 0.0F;
    }
  }

  for (i = 0; i < 3; i++) {
    for (i0 = 0; i0 < 3; i0++) {
      A_lin[(i0 + 12 * (i + 9)) + 9] = O[i0 + 3 * i];
    }
  }

  for (i = 0; i < 12; i++) {
    for (i0 = 0; i0 < 12; i0++) {
      b_A_lin[i0 + 12 * i] = (real32_T)dv1[i0 + 12 * i] + A_lin[i0 + 12 * i] *
        dt;
    }
  }

  /* 'attitudeKalmanfilter:88' P_apriori=A_lin*P_aposteriori_k*A_lin'+Q; */
  for (i = 0; i < 12; i++) {
    for (i0 = 0; i0 < 12; i0++) {
      A_lin[i + 12 * i0] = 0.0F;
      for (i1 = 0; i1 < 12; i1++) {
        A_lin[i + 12 * i0] += b_A_lin[i + 12 * i1] * P_aposteriori_k[i1 + 12 *
          i0];
      }
    }
  }

  for (i = 0; i < 12; i++) {
    for (i0 = 0; i0 < 12; i0++) {
      y = 0.0F;
      for (i1 = 0; i1 < 12; i1++) {
        y += A_lin[i + 12 * i1] * b_A_lin[i0 + 12 * i1];
      }

      P_apriori[i + 12 * i0] = y + Q[i + 12 * i0];
    }
  }

  /* %update */
  /* 'attitudeKalmanfilter:92' if updateVect(1)==1&&updateVect(2)==1&&updateVect(3)==1 */
  if ((updateVect[0] == 1) && (updateVect[1] == 1) && (updateVect[2] == 1)) {
    /* 'attitudeKalmanfilter:93' R=diag(r); */
    b_diag(r, R);

    /* observation matrix */
    /* 'attitudeKalmanfilter:96' H_k=[  E,     E,      Z,    Z; */
    /* 'attitudeKalmanfilter:97'         Z,     Z,      E,    Z; */
    /* 'attitudeKalmanfilter:98'         Z,     Z,      Z,    E]; */
    /* 'attitudeKalmanfilter:100' y_k=z(1:9)-H_k*x_apriori; */
    /* 'attitudeKalmanfilter:102' S_k=H_k*P_apriori*H_k'+R; */
    /* 'attitudeKalmanfilter:103' K_k=(P_apriori*H_k'/(S_k)); */
    for (i = 0; i < 12; i++) {
      for (i0 = 0; i0 < 9; i0++) {
        b_P_apriori[i + 12 * i0] = 0.0F;
        for (i1 = 0; i1 < 12; i1++) {
          b_P_apriori[i + 12 * i0] += P_apriori[i + 12 * i1] * (real32_T)iv0[i1
            + 12 * i0];
        }
      }
    }

    for (i = 0; i < 9; i++) {
      for (i0 = 0; i0 < 12; i0++) {
        K_k[i + 9 * i0] = 0.0F;
        for (i1 = 0; i1 < 12; i1++) {
          K_k[i + 9 * i0] += (real32_T)iv1[i + 9 * i1] * P_apriori[i1 + 12 * i0];
        }
      }
    }

    for (i = 0; i < 9; i++) {
      for (i0 = 0; i0 < 9; i0++) {
        y = 0.0F;
        for (i1 = 0; i1 < 12; i1++) {
          y += K_k[i + 9 * i1] * (real32_T)iv0[i1 + 12 * i0];
        }

        fv0[i + 9 * i0] = y + R[i + 9 * i0];
      }
    }

    mrdivide(b_P_apriori, fv0, K_k);

    /* 'attitudeKalmanfilter:106' x_aposteriori=x_apriori+K_k*y_k; */
    for (i = 0; i < 9; i++) {
      y = 0.0F;
      for (i0 = 0; i0 < 12; i0++) {
        y += (real32_T)iv1[i + 9 * i0] * x_apriori[i0];
      }

      c_a[i] = z[i] - y;
    }

    for (i = 0; i < 12; i++) {
      y = 0.0F;
      for (i0 = 0; i0 < 9; i0++) {
        y += K_k[i + 12 * i0] * c_a[i0];
      }

      x_aposteriori[i] = x_apriori[i] + y;
    }

    /* 'attitudeKalmanfilter:107' P_aposteriori=(eye(12)-K_k*H_k)*P_apriori; */
    b_eye(dv1);
    for (i = 0; i < 12; i++) {
      for (i0 = 0; i0 < 12; i0++) {
        y = 0.0F;
        for (i1 = 0; i1 < 9; i1++) {
          y += K_k[i + 12 * i1] * (real32_T)iv1[i1 + 9 * i0];
        }

        Q[i + 12 * i0] = (real32_T)dv1[i + 12 * i0] - y;
      }
    }

    for (i = 0; i < 12; i++) {
      for (i0 = 0; i0 < 12; i0++) {
        P_aposteriori[i + 12 * i0] = 0.0F;
        for (i1 = 0; i1 < 12; i1++) {
          P_aposteriori[i + 12 * i0] += Q[i + 12 * i1] * P_apriori[i1 + 12 * i0];
        }
      }
    }
  } else {
    /* 'attitudeKalmanfilter:108' else */
    /* 'attitudeKalmanfilter:109' if updateVect(1)==1&&updateVect(2)==0&&updateVect(3)==0 */
    if ((updateVect[0] == 1) && (updateVect[1] == 0) && (updateVect[2] == 0)) {
      /* 'attitudeKalmanfilter:110' R=diag(r(1:3)); */
      c_diag(*(real32_T (*)[3])&r[0], O);

      /* observation matrix */
      /* 'attitudeKalmanfilter:113' H_k=[  E,     E,      Z,    Z]; */
      /* 'attitudeKalmanfilter:115' y_k=z(1:3)-H_k(1:3,1:12)*x_apriori; */
      /* 'attitudeKalmanfilter:117' S_k=H_k(1:3,1:12)*P_apriori*H_k(1:3,1:12)'+R(1:3,1:3); */
      /* 'attitudeKalmanfilter:118' K_k=(P_apriori*H_k(1:3,1:12)'/(S_k)); */
      for (i = 0; i < 12; i++) {
        for (i0 = 0; i0 < 3; i0++) {
          c_P_apriori[i + 12 * i0] = 0.0F;
          for (i1 = 0; i1 < 12; i1++) {
            c_P_apriori[i + 12 * i0] += P_apriori[i + 12 * i1] * (real32_T)
              iv2[i1 + 12 * i0];
          }
        }
      }

      for (i = 0; i < 3; i++) {
        for (i0 = 0; i0 < 12; i0++) {
          fv1[i + 3 * i0] = 0.0F;
          for (i1 = 0; i1 < 12; i1++) {
            fv1[i + 3 * i0] += (real32_T)iv3[i + 3 * i1] * P_apriori[i1 + 12 *
              i0];
          }
        }
      }

      for (i = 0; i < 3; i++) {
        for (i0 = 0; i0 < 3; i0++) {
          y = 0.0F;
          for (i1 = 0; i1 < 12; i1++) {
            y += fv1[i + 3 * i1] * (real32_T)iv2[i1 + 12 * i0];
          }

          c_a[i + 3 * i0] = y + O[i + 3 * i0];
        }
      }

      b_mrdivide(c_P_apriori, c_a, S_k);

      /* 'attitudeKalmanfilter:121' x_aposteriori=x_apriori+K_k*y_k; */
      for (i = 0; i < 3; i++) {
        y = 0.0F;
        for (i0 = 0; i0 < 12; i0++) {
          y += (real32_T)iv3[i + 3 * i0] * x_apriori[i0];
        }

        x_n_b[i] = z[i] - y;
      }

      for (i = 0; i < 12; i++) {
        y = 0.0F;
        for (i0 = 0; i0 < 3; i0++) {
          y += S_k[i + 12 * i0] * x_n_b[i0];
        }

        x_aposteriori[i] = x_apriori[i] + y;
      }

      /* 'attitudeKalmanfilter:122' P_aposteriori=(eye(12)-K_k*H_k(1:3,1:12))*P_apriori; */
      b_eye(dv1);
      for (i = 0; i < 12; i++) {
        for (i0 = 0; i0 < 12; i0++) {
          y = 0.0F;
          for (i1 = 0; i1 < 3; i1++) {
            y += S_k[i + 12 * i1] * (real32_T)iv3[i1 + 3 * i0];
          }

          Q[i + 12 * i0] = (real32_T)dv1[i + 12 * i0] - y;
        }
      }

      for (i = 0; i < 12; i++) {
        for (i0 = 0; i0 < 12; i0++) {
          P_aposteriori[i + 12 * i0] = 0.0F;
          for (i1 = 0; i1 < 12; i1++) {
            P_aposteriori[i + 12 * i0] += Q[i + 12 * i1] * P_apriori[i1 + 12 *
              i0];
          }
        }
      }
    } else {
      /* 'attitudeKalmanfilter:123' else */
      /* 'attitudeKalmanfilter:124' if  updateVect(1)==1&&updateVect(2)==1&&updateVect(3)==0 */
      if ((updateVect[0] == 1) && (updateVect[1] == 1) && (updateVect[2] == 0))
      {
        /* 'attitudeKalmanfilter:125' R=diag(r(1:6)); */
        d_diag(*(real32_T (*)[6])&r[0], S_k);

        /* observation matrix */
        /* 'attitudeKalmanfilter:128' H_k=[  E,     E,      Z,    Z; */
        /* 'attitudeKalmanfilter:129'                 Z,     Z,      E,    Z]; */
        /* 'attitudeKalmanfilter:131' y_k=z(1:6)-H_k(1:6,1:12)*x_apriori; */
        /* 'attitudeKalmanfilter:133' S_k=H_k(1:6,1:12)*P_apriori*H_k(1:6,1:12)'+R(1:6,1:6); */
        /* 'attitudeKalmanfilter:134' K_k=(P_apriori*H_k(1:6,1:12)'/(S_k)); */
        for (i = 0; i < 12; i++) {
          for (i0 = 0; i0 < 6; i0++) {
            d_P_apriori[i + 12 * i0] = 0.0F;
            for (i1 = 0; i1 < 12; i1++) {
              d_P_apriori[i + 12 * i0] += P_apriori[i + 12 * i1] * (real32_T)
                iv4[i1 + 12 * i0];
            }
          }
        }

        for (i = 0; i < 6; i++) {
          for (i0 = 0; i0 < 12; i0++) {
            b_K_k[i + 6 * i0] = 0.0F;
            for (i1 = 0; i1 < 12; i1++) {
              b_K_k[i + 6 * i0] += (real32_T)iv5[i + 6 * i1] * P_apriori[i1 + 12
                * i0];
            }
          }
        }

        for (i = 0; i < 6; i++) {
          for (i0 = 0; i0 < 6; i0++) {
            y = 0.0F;
            for (i1 = 0; i1 < 12; i1++) {
              y += b_K_k[i + 6 * i1] * (real32_T)iv4[i1 + 12 * i0];
            }

            fv1[i + 6 * i0] = y + S_k[i + 6 * i0];
          }
        }

        c_mrdivide(d_P_apriori, fv1, b_K_k);

        /* 'attitudeKalmanfilter:137' x_aposteriori=x_apriori+K_k*y_k; */
        for (i = 0; i < 6; i++) {
          y = 0.0F;
          for (i0 = 0; i0 < 12; i0++) {
            y += (real32_T)iv5[i + 6 * i0] * x_apriori[i0];
          }

          b_r[i] = z[i] - y;
        }

        for (i = 0; i < 12; i++) {
          y = 0.0F;
          for (i0 = 0; i0 < 6; i0++) {
            y += b_K_k[i + 12 * i0] * b_r[i0];
          }

          x_aposteriori[i] = x_apriori[i] + y;
        }

        /* 'attitudeKalmanfilter:138' P_aposteriori=(eye(12)-K_k*H_k(1:6,1:12))*P_apriori; */
        b_eye(dv1);
        for (i = 0; i < 12; i++) {
          for (i0 = 0; i0 < 12; i0++) {
            y = 0.0F;
            for (i1 = 0; i1 < 6; i1++) {
              y += b_K_k[i + 12 * i1] * (real32_T)iv5[i1 + 6 * i0];
            }

            Q[i + 12 * i0] = (real32_T)dv1[i + 12 * i0] - y;
          }
        }

        for (i = 0; i < 12; i++) {
          for (i0 = 0; i0 < 12; i0++) {
            P_aposteriori[i + 12 * i0] = 0.0F;
            for (i1 = 0; i1 < 12; i1++) {
              P_aposteriori[i + 12 * i0] += Q[i + 12 * i1] * P_apriori[i1 + 12 *
                i0];
            }
          }
        }
      } else {
        /* 'attitudeKalmanfilter:139' else */
        /* 'attitudeKalmanfilter:140' if  updateVect(1)==1&&updateVect(2)==0&&updateVect(3)==1 */
        if ((updateVect[0] == 1) && (updateVect[1] == 0) && (updateVect[2] == 1))
        {
          /* 'attitudeKalmanfilter:141' R=diag([r(1:3);r(7:9)]); */
          /* observation matrix */
          /* 'attitudeKalmanfilter:144' H_k=[  E,     E,      Z,    Z; */
          /* 'attitudeKalmanfilter:145'                     Z,     Z,      Z,    E]; */
          /* 'attitudeKalmanfilter:147' y_k=[z(1:3);z(7:9)]-H_k(1:6,1:12)*x_apriori; */
          /* 'attitudeKalmanfilter:149' S_k=H_k(1:6,1:12)*P_apriori*H_k(1:6,1:12)'+R(1:6,1:6); */
          for (i = 0; i < 6; i++) {
            for (i0 = 0; i0 < 12; i0++) {
              b_K_k[i + 6 * i0] = 0.0F;
              for (i1 = 0; i1 < 12; i1++) {
                b_K_k[i + 6 * i0] += (real32_T)iv6[i + 6 * i1] * P_apriori[i1 +
                  12 * i0];
              }
            }
          }

          for (i = 0; i < 3; i++) {
            b_r[i << 1] = r[i];
            b_r[1 + (i << 1)] = r[6 + i];
          }

          for (i = 0; i < 6; i++) {
            for (i0 = 0; i0 < 6; i0++) {
              y = 0.0F;
              for (i1 = 0; i1 < 12; i1++) {
                y += b_K_k[i + 6 * i1] * (real32_T)iv7[i1 + 12 * i0];
              }

              S_k[i + 6 * i0] = y + b_r[3 * (i + i0)];
            }
          }

          /* 'attitudeKalmanfilter:150' K_k=(P_apriori*H_k(1:6,1:12)'/(S_k)); */
          for (i = 0; i < 12; i++) {
            for (i0 = 0; i0 < 6; i0++) {
              d_P_apriori[i + 12 * i0] = 0.0F;
              for (i1 = 0; i1 < 12; i1++) {
                d_P_apriori[i + 12 * i0] += P_apriori[i + 12 * i1] * (real32_T)
                  iv7[i1 + 12 * i0];
              }
            }
          }

          c_mrdivide(d_P_apriori, S_k, b_K_k);

          /* 'attitudeKalmanfilter:153' x_aposteriori=x_apriori+K_k*y_k; */
          for (i = 0; i < 3; i++) {
            b_r[i] = z[i];
          }

          for (i = 0; i < 3; i++) {
            b_r[i + 3] = z[i + 6];
          }

          for (i = 0; i < 6; i++) {
            fv2[i] = 0.0F;
            for (i0 = 0; i0 < 12; i0++) {
              fv2[i] += (real32_T)iv6[i + 6 * i0] * x_apriori[i0];
            }

            b_z[i] = b_r[i] - fv2[i];
          }

          for (i = 0; i < 12; i++) {
            y = 0.0F;
            for (i0 = 0; i0 < 6; i0++) {
              y += b_K_k[i + 12 * i0] * b_z[i0];
            }

            x_aposteriori[i] = x_apriori[i] + y;
          }

          /* 'attitudeKalmanfilter:154' P_aposteriori=(eye(12)-K_k*H_k(1:6,1:12))*P_apriori; */
          b_eye(dv1);
          for (i = 0; i < 12; i++) {
            for (i0 = 0; i0 < 12; i0++) {
              y = 0.0F;
              for (i1 = 0; i1 < 6; i1++) {
                y += b_K_k[i + 12 * i1] * (real32_T)iv6[i1 + 6 * i0];
              }

              Q[i + 12 * i0] = (real32_T)dv1[i + 12 * i0] - y;
            }
          }

          for (i = 0; i < 12; i++) {
            for (i0 = 0; i0 < 12; i0++) {
              P_aposteriori[i + 12 * i0] = 0.0F;
              for (i1 = 0; i1 < 12; i1++) {
                P_aposteriori[i + 12 * i0] += Q[i + 12 * i1] * P_apriori[i1 + 12
                  * i0];
              }
            }
          }
        } else {
          /* 'attitudeKalmanfilter:155' else */
          /* 'attitudeKalmanfilter:156' x_aposteriori=x_apriori; */
          for (i = 0; i < 12; i++) {
            x_aposteriori[i] = x_apriori[i];
          }

          /* 'attitudeKalmanfilter:157' P_aposteriori=P_apriori; */
          memcpy((void *)&P_aposteriori[0], (void *)&P_apriori[0], 144U * sizeof
                 (real32_T));
        }
      }
    }
  }

  /* % euler anglels extraction */
  /* 'attitudeKalmanfilter:166' z_n_b = -x_aposteriori(7:9)./norm(x_aposteriori(7:9)); */
  y = norm(*(real32_T (*)[3])&x_aposteriori[6]);

  /* 'attitudeKalmanfilter:167' m_n_b = x_aposteriori(10:12)./norm(x_aposteriori(10:12)); */
  b_y = norm(*(real32_T (*)[3])&x_aposteriori[9]);

  /* 'attitudeKalmanfilter:169' y_n_b=cross(z_n_b,m_n_b); */
  for (i = 0; i < 3; i++) {
    z_n_b[i] = -x_aposteriori[i + 6] / y;
    x_n_b[i] = x_aposteriori[i + 9] / b_y;
  }

  cross(z_n_b, x_n_b, y_n_b);

  /* 'attitudeKalmanfilter:170' y_n_b=y_n_b./norm(y_n_b); */
  y = norm(y_n_b);
  for (i = 0; i < 3; i++) {
    y_n_b[i] /= y;
  }

  /* 'attitudeKalmanfilter:172' x_n_b=(cross(y_n_b,z_n_b)); */
  cross(y_n_b, z_n_b, x_n_b);

  /* 'attitudeKalmanfilter:173' x_n_b=x_n_b./norm(x_n_b); */
  y = norm(x_n_b);
  for (i = 0; i < 3; i++) {
    /* 'attitudeKalmanfilter:179' Rot_matrix=[x_n_b,y_n_b,z_n_b]; */
    Rot_matrix[i] = x_n_b[i] / y;
    Rot_matrix[3 + i] = y_n_b[i];
    Rot_matrix[6 + i] = z_n_b[i];
  }

  /* 'attitudeKalmanfilter:183' phi=atan2(Rot_matrix(2,3),Rot_matrix(3,3)); */
  /* 'attitudeKalmanfilter:184' theta=-asin(Rot_matrix(1,3)); */
  /* 'attitudeKalmanfilter:185' psi=atan2(Rot_matrix(1,2),Rot_matrix(1,1)); */
  /* 'attitudeKalmanfilter:186' eulerAngles=[phi;theta;psi]; */
  eulerAngles[0] = rt_atan2f_snf(Rot_matrix[7], Rot_matrix[8]);
  eulerAngles[1] = -(real32_T)asinf(Rot_matrix[6]);
  eulerAngles[2] = rt_atan2f_snf(Rot_matrix[3], Rot_matrix[0]);
}
예제 #2
0
/* Function Definitions */
void updateCompass2(states_T *x, real32_T P[400], const real32_T y_Compass[3],
                    const real32_T b_N[3], const real32_T acc[3], boolean_T
                    constWind, boolean_T constQFF, boolean_T constK)
{
  real32_T r;
  real32_T b_r[3];
  real32_T R_Compass[9];
  real32_T C_NS[9];
  int32_T i13;
  real32_T y_Compass_N[3];
  int32_T i14;
  real32_T b_p_N[3];
  static const int8_T b[9] = { 1, 0, 0, 0, 1, 0, 0, 0, 0 };

  real32_T y_p_N[3];
  real32_T X[9];
  real32_T b_X[9];
  real32_T y;
  int32_T ar;
  real32_T N[9];
  real32_T dtheta_half_norm;
  int32_T ib;
  int32_T i;
  real32_T c_X[9];
  static const int8_T a[3] = { 0, 0, 1 };

  real32_T b_a[3];
  real32_T E_z[3];
  real32_T d_X[9];
  real32_T e_X[9];
  real32_T K[20];
  real32_T e;
  static const int8_T iv4[3] = { 0, 0, 1 };

  real32_T H[20];
  real32_T b_y[3];
  boolean_T selector[20];
  emxArray_int32_T *r28;
  boolean_T b_selector[20];
  emxArray_int32_T *r29;
  emxArray_real32_T *c_a;
  emxArray_int32_T *r30;
  emxArray_int32_T *r31;
  int32_T br;
  emxArray_int32_T *r32;
  emxArray_int32_T *r33;
  emxArray_int32_T *r34;
  emxArray_int32_T *r35;
  emxArray_real32_T *d_a;
  emxArray_real32_T *b_b;
  emxArray_real32_T *c_y;
  uint32_T unnamed_idx_1;
  int32_T ic;
  int32_T ia;
  emxArray_real32_T *e_a;
  emxArray_real32_T *KH;
  emxArray_real32_T *r36;
  emxArray_real32_T *C;
  uint32_T unnamed_idx_0;
  int32_T c;
  emxArray_int32_T *r37;
  emxArray_int32_T *r38;
  real32_T dq[4];
  real32_T Q[16];

  /*  */
  /*  [x,P] = UPDATECOMPASS2(x,P,y_Compass, b_N, e_acc, constWind, constQFF,constK) */
  /*  */
  /*  Kalman filter update with 3-axis compass measurements. */
  /*  */
  /*  Author: lestefan */
  /*  date:  02/2013 */
  /*  */
  /*  Inputs: */
  /*    x:            states [p(lat*1e7,lon*1e7,h),q_NS,v_N,b_g,b_a,QFF,w,K] */
  /*    P:            covariance */
  /*    y_Compass:    magnetic field measurement 3x1 (in sensor frame S) [uT] */
  /*    b_N:          true magnetic flux density 3x1 (nav frame N) [uT] */
  /*    constWind:    keep wind constant [true/false] (use true on GPS out) */
  /*    constQFF:     keep QFF constant [true/false] (use true on GPS out) */
  /*    constK:       K (sideslip parameter) const. [true/false] (use true) */
  /*  */
  /*  Outputs: */
  /*    x:            updated states (see inputs) */
  /*    P:            updated covariance (see inputs) */
  /*  */
  /*  Needed globals: */
  /*    global configuration; */
  /*    configuration.tau:         accelerometer autocorrelation time [s] */
  /*    configuration.sigma_a_c:   accelerometer noise [m/s^2/sqrt(Hz)] */
  /*    configuration.sigma_a_d:   accelerometer standard diviation [m/s^2] */
  /*    configuration.sigma_aw_c:  accelerometer bias noise [m/s^3/sqrt(Hz)] */
  /*    configuration.sigma_g_c:   gyro noise [rad/s/sqrt(Hz)] */
  /*    configuration.sigma_gw_c:  gyro bias noise [rad/s^2/sqrt(Hz)] */
  /*    configuration.sigma_pw_c:  static pressure bias noise [kPa/s/sqrt(Hz)] */
  /*    configuration.sigma_w_c:   wind drift noise [m/s^2/sqrt(Hz)] */
  /*    configuration.sigma_psmd:  static pressure measurement variance [kPa] */
  /*    configuration.sigma_pdmd:  dynamic pressure measurement variance [kPa] */
  /*    configuration.sigma_Td=1:  temperature measurement variance [°K] */
  /*    configuration.sigma_md=1:  magnetometer noise [uT] */
  /*  */
  /*  See also UPDATEPOSITION, UPDATEVELNED, UPDATEPRESSURES,  */
  /*  UPDATEPRESSURES2, UPDATEPRESSURES3, PROPATATE, GETINITIALQ */
  /*  */
  r = rt_powf_snf(configuration.sigma_md, 2.0F);

  /* R_Compass=single(diag(configuration.sigma_md^2*single([1 1 1]))); */
  b_r[0] = r;
  b_r[1] = r;
  b_r[2] = r;
  b_diag(b_r, R_Compass);

  /* *configuration.sigma_md; */
  /*  TODO: update in the past, re-propagate. This might not be fast enough... */
  /*  set float type */
  C_NS[0] = ((x->q_NS[0] * x->q_NS[0] - x->q_NS[1] * x->q_NS[1]) - x->q_NS[2] *
             x->q_NS[2]) + x->q_NS[3] * x->q_NS[3];
  C_NS[3] = x->q_NS[0] * x->q_NS[1] * 2.0F + x->q_NS[2] * x->q_NS[3] * 2.0F;
  C_NS[6] = x->q_NS[0] * x->q_NS[2] * 2.0F - x->q_NS[1] * x->q_NS[3] * 2.0F;
  C_NS[1] = x->q_NS[0] * x->q_NS[1] * 2.0F - x->q_NS[2] * x->q_NS[3] * 2.0F;
  C_NS[4] = ((-x->q_NS[0] * x->q_NS[0] + x->q_NS[1] * x->q_NS[1]) - x->q_NS[2] *
             x->q_NS[2]) + x->q_NS[3] * x->q_NS[3];
  C_NS[7] = x->q_NS[0] * x->q_NS[3] * 2.0F + x->q_NS[1] * x->q_NS[2] * 2.0F;
  C_NS[2] = x->q_NS[0] * x->q_NS[2] * 2.0F + x->q_NS[1] * x->q_NS[3] * 2.0F;
  C_NS[5] = x->q_NS[0] * x->q_NS[3] * -2.0F + x->q_NS[1] * x->q_NS[2] * 2.0F;
  C_NS[8] = ((-x->q_NS[0] * x->q_NS[0] - x->q_NS[1] * x->q_NS[1]) + x->q_NS[2] *
             x->q_NS[2]) + x->q_NS[3] * x->q_NS[3];

  /*  error term: */
  for (i13 = 0; i13 < 3; i13++) {
    y_Compass_N[i13] = 0.0F;
    for (i14 = 0; i14 < 3; i14++) {
      y_Compass_N[i13] += C_NS[i13 + 3 * i14] * y_Compass[i14];
    }

    /* b_S=C_NS'*b_N; */
    /*  error and Jacobians: */
    /* [e,J]=autogen_angleJacobian2d(y_Compass_N,b_N); */
    /* dz=1e-3; */
    /* y_Compass_N_1p=C_NS*(y_Compass+[dz;0;0]); */
    /* y_Compass_N_2p=C_NS*(y_Compass+[0;dz;0]); */
    /* y_Compass_N_3p=C_NS*(y_Compass+[0;0;dz]); */
    /* y_Compass_N_1m=C_NS*(y_Compass-[dz;0;0]); */
    /* y_Compass_N_2m=C_NS*(y_Compass-[0;dz;0]); */
    /* y_Compass_N_3m=C_NS*(y_Compass-[0;0;dz]); */
    /* [e1,J]=autogen_angleJacobian2d(y_Compass_N_1p,b_N); */
    /* [e2,J]=autogen_angleJacobian2d(y_Compass_N_2p,b_N); */
    /* [e3,J]=autogen_angleJacobian2d(y_Compass_N_3p,b_N); */
    /* [e1,J]=autogen_angleJacobian2d(y_Compass_N_1m,b_N); */
    /* [e2,J]=autogen_angleJacobian2d(y_Compass_N_2m,b_N); */
    /* [e3,J]=autogen_angleJacobian2d(y_Compass_N_3m,b_N); */
    /* E_x=[single(zeros(1,3)),J*crossMx(y_Compass_N),single(zeros(1,14))]; */
    /* E_z=J*C_NS; */
    b_p_N[i13] = 0.0F;
    for (i14 = 0; i14 < 3; i14++) {
      b_p_N[i13] += (real32_T)b[i13 + 3 * i14] * b_N[i14];
    }
  }

  for (i13 = 0; i13 < 3; i13++) {
    y_p_N[i13] = 0.0F;
    for (i14 = 0; i14 < 3; i14++) {
      y_p_N[i13] += (real32_T)b[i13 + 3 * i14] * y_Compass_N[i14];
    }
  }

  /*  set float type */
  X[0] = 0.0F;
  X[3] = -y_p_N[2];
  X[6] = y_p_N[1];
  X[1] = y_p_N[2];
  X[4] = 0.0F;
  X[7] = -y_p_N[0];
  X[2] = -y_p_N[1];
  X[5] = y_p_N[0];
  X[8] = 0.0F;

  /*  set float type */
  b_X[0] = 0.0F;
  b_X[3] = -y_p_N[2];
  b_X[6] = y_p_N[1];
  b_X[1] = y_p_N[2];
  b_X[4] = 0.0F;
  b_X[7] = -y_p_N[0];
  b_X[2] = -y_p_N[1];
  b_X[5] = y_p_N[0];
  b_X[8] = 0.0F;
  y = 0.0F;
  for (ar = 0; ar < 3; ar++) {
    y += y_p_N[ar] * y_p_N[ar];
  }

  r = rt_powf_snf((real32_T)sqrt(y), 3.0F);
  for (i13 = 0; i13 < 3; i13++) {
    for (i14 = 0; i14 < 3; i14++) {
      dtheta_half_norm = 0.0F;
      for (ib = 0; ib < 3; ib++) {
        dtheta_half_norm += X[i13 + 3 * ib] * b_X[i14 + 3 * ib];
      }

      N[i13 + 3 * i14] = dtheta_half_norm / r;
    }
  }

  y = 0.0F;
  for (ar = 0; ar < 3; ar++) {
    y += b_p_N[ar] * b_p_N[ar];
  }

  r = (real32_T)sqrt(y);
  for (i = 0; i < 3; i++) {
    b_r[i] = -b_p_N[i] / r;
  }

  /*  set float type */
  c_X[0] = 0.0F;
  c_X[3] = -b_r[2];
  c_X[6] = b_r[1];
  c_X[1] = b_r[2];
  c_X[4] = 0.0F;
  c_X[7] = -b_r[0];
  c_X[2] = -b_r[1];
  c_X[5] = b_r[0];
  c_X[8] = 0.0F;
  for (i13 = 0; i13 < 3; i13++) {
    b_r[i13] = 0.0F;
    for (i14 = 0; i14 < 3; i14++) {
      b_r[i13] += (real32_T)a[i14] * c_X[i14 + 3 * i13];
    }
  }

  for (i13 = 0; i13 < 3; i13++) {
    b_a[i13] = 0.0F;
    for (i14 = 0; i14 < 3; i14++) {
      b_a[i13] += b_r[i14] * N[i14 + 3 * i13];
    }
  }

  for (i13 = 0; i13 < 3; i13++) {
    b_r[i13] = 0.0F;
    for (i14 = 0; i14 < 3; i14++) {
      b_r[i13] += b_a[i14] * (real32_T)b[i14 + 3 * i13];
    }
  }

  y = 0.0F;
  for (i13 = 0; i13 < 3; i13++) {
    E_z[i13] = 0.0F;
    for (i14 = 0; i14 < 3; i14++) {
      E_z[i13] += b_r[i14] * C_NS[i14 + 3 * i13];
    }

    y += b_p_N[i13] * b_p_N[i13];
  }

  r = (real32_T)sqrt(y);
  for (i = 0; i < 3; i++) {
    b_r[i] = -b_p_N[i] / r;
  }

  /*  set float type */
  d_X[0] = 0.0F;
  d_X[3] = -b_r[2];
  d_X[6] = b_r[1];
  d_X[1] = b_r[2];
  d_X[4] = 0.0F;
  d_X[7] = -b_r[0];
  d_X[2] = -b_r[1];
  d_X[5] = b_r[0];
  d_X[8] = 0.0F;

  /*  set float type */
  e_X[0] = 0.0F;
  e_X[3] = -y_Compass_N[2];
  e_X[6] = y_Compass_N[1];
  e_X[1] = y_Compass_N[2];
  e_X[4] = 0.0F;
  e_X[7] = -y_Compass_N[0];
  e_X[2] = -y_Compass_N[1];
  e_X[5] = y_Compass_N[0];
  e_X[8] = 0.0F;
  for (i13 = 0; i13 < 3; i13++) {
    b_r[i13] = 0.0F;
    for (i14 = 0; i14 < 3; i14++) {
      b_r[i13] += (real32_T)a[i14] * d_X[i14 + 3 * i13];
    }
  }

  for (i13 = 0; i13 < 3; i13++) {
    b_a[i13] = 0.0F;
    for (i14 = 0; i14 < 3; i14++) {
      b_a[i13] += b_r[i14] * N[i14 + 3 * i13];
    }
  }

  for (i13 = 0; i13 < 3; i13++) {
    b_r[i13] = 0.0F;
    for (i14 = 0; i14 < 3; i14++) {
      b_r[i13] += b_a[i14] * (real32_T)b[i14 + 3 * i13];
    }
  }

  for (i13 = 0; i13 < 3; i13++) {
    b_a[i13] = 0.0F;
    for (i14 = 0; i14 < 3; i14++) {
      b_a[i13] += b_r[i14] * e_X[i14 + 3 * i13];
    }

    K[i13] = 0.0F;
  }

  for (i13 = 0; i13 < 3; i13++) {
    K[i13 + 3] = b_a[i13];
  }

  for (i13 = 0; i13 < 14; i13++) {
    K[i13 + 6] = 0.0F;
  }

  y = 0.0F;
  for (ar = 0; ar < 3; ar++) {
    y += y_p_N[ar] * y_p_N[ar];
  }

  r = (real32_T)sqrt(y);
  y = 0.0F;
  for (ar = 0; ar < 3; ar++) {
    y += b_p_N[ar] * b_p_N[ar];
    b_a[ar] = y_p_N[ar] / r;
  }

  r = (real32_T)sqrt(y);
  for (i = 0; i < 3; i++) {
    b_r[i] = b_p_N[i] / r;
  }

  cross(b_a, b_r, y_Compass_N);
  e = 0.0F;
  for (ar = 0; ar < 3; ar++) {
    e += (real32_T)iv4[ar] * y_Compass_N[ar];
  }

  /* e1p=Pi_z*cross(Pi_xy0*y_Compass_N_1p/sqrt(y_Compass_N_1p'*y_Compass_N_1p),Pi_xy0*e_N); */
  /* e2p=Pi_z*cross(Pi_xy0*y_Compass_N_2p/sqrt(y_Compass_N_2p'*y_Compass_N_2p),Pi_xy0*e_N); */
  /* e3p=Pi_z*cross(Pi_xy0*y_Compass_N_3p/sqrt(y_Compass_N_3p'*y_Compass_N_3p),Pi_xy0*e_N); */
  /* e1m=Pi_z*cross(Pi_xy0*y_Compass_N_1m/sqrt(y_Compass_N_1m'*y_Compass_N_1m),Pi_xy0*e_N); */
  /* e2m=Pi_z*cross(Pi_xy0*y_Compass_N_2m/sqrt(y_Compass_N_2m'*y_Compass_N_2m),Pi_xy0*e_N); */
  /* e3m=Pi_z*cross(Pi_xy0*y_Compass_N_3m/sqrt(y_Compass_N_3m'*y_Compass_N_3m),Pi_xy0*e_N); */
  /* num_diff_Ez = [(e1p-e1m)/(2*dz) (e2p-e2m)/(2*dz) (e3p-e3m)/(2*dz)]; */
  /*  e_acc=single([0;0;1]); % rather random, but if mounted as advised, it's ok */
  /*  norm_acc_sq=acc'*acc; */
  /*  if norm_acc_sq>1 */
  /*      e_acc=acc/sqrt(norm_acc_sq); */
  /*  end */
  /*  [e,E_b_S,E_z]=autogen_angleJacobian2dAccDir(y_Compass,b_S,e_acc); */
  /*  E_x=[single(zeros(1,3)),-E_b_S*C_NS'*crossMx(b_N),single(zeros(1,14))]; */
  for (i13 = 0; i13 < 20; i13++) {
    H[i13] = -K[i13];
  }

  for (i13 = 0; i13 < 3; i13++) {
    b_y[i13] = 0.0F;
    for (i14 = 0; i14 < 3; i14++) {
      y = b_y[i13] + K[3 + i14] * P[(i14 + 20 * (3 + i13)) + 3];
      b_y[i13] = y;
    }
  }

  y = 0.0F;
  r = 0.0F;
  for (ar = 0; ar < 3; ar++) {
    y += b_y[ar] * K[3 + ar];
    b_y[ar] = 0.0F;
    for (i13 = 0; i13 < 3; i13++) {
      b_y[ar] += E_z[i13] * R_Compass[i13 + 3 * ar];
    }

    r += b_y[ar] * E_z[ar];
  }

  r += y;
  if (e * rt_powf_snf(r, -1.0F) * e > 100.0F) {
    /* disp(['magnetometer chi2 ' num2str(chi2)]); */
  } else {
    /* K=(S\(H(1:3,4:6)*P(4:6,:)))'; % gain */
    for (i = 0; i < 20; i++) {
      K[i] = 0.0F;

      /*  set float type */
      selector[i] = TRUE;
    }

    if (constK) {
      selector[19] = FALSE;
    }

    if (constQFF) {
      selector[15] = FALSE;
    }

    emxInit_int32_T(&r28, 1);

    /*  remove correlations of fixed states with active states */
    eml_li_find(selector, r28);
    i13 = r28->size[0];
    r28->size[0] = r28->size[0];
    emxEnsureCapacity((emxArray__common *)r28, i13, (int32_T)sizeof(int32_T));
    i = r28->size[0];
    for (i13 = 0; i13 < i; i13++) {
      r28->data[i13]--;
    }

    for (i = 0; i < 20; i++) {
      b_selector[i] = !selector[i];
    }

    emxInit_int32_T(&r29, 1);
    eml_li_find(b_selector, r29);
    i13 = r29->size[0];
    r29->size[0] = r29->size[0];
    emxEnsureCapacity((emxArray__common *)r29, i13, (int32_T)sizeof(int32_T));
    i = r29->size[0];
    for (i13 = 0; i13 < i; i13++) {
      r29->data[i13]--;
    }

    for (i = 0; i < 20; i++) {
      b_selector[i] = !selector[i];
    }

    emxInit_real32_T(&c_a, 2);
    emxInit_int32_T(&r30, 1);
    emxInit_int32_T(&r31, 1);
    eml_li_find(b_selector, r30);
    eml_li_find(selector, r31);
    i13 = c_a->size[0] * c_a->size[1];
    c_a->size[0] = r31->size[0];
    c_a->size[1] = r30->size[0];
    emxEnsureCapacity((emxArray__common *)c_a, i13, (int32_T)sizeof(real32_T));
    i = r30->size[0];
    for (i13 = 0; i13 < i; i13++) {
      br = r31->size[0];
      for (i14 = 0; i14 < br; i14++) {
        c_a->data[i14 + c_a->size[0] * i13] = P[(r31->data[i14] + 20 *
          (r30->data[i13] - 1)) - 1];
      }
    }

    emxInit_int32_T(&r32, 1);
    i13 = r32->size[0];
    r32->size[0] = r29->size[0];
    emxEnsureCapacity((emxArray__common *)r32, i13, (int32_T)sizeof(int32_T));
    i = r29->size[0];
    for (i13 = 0; i13 < i; i13++) {
      r32->data[i13] = r29->data[i13];
    }

    emxInit_int32_T(&r33, 1);
    i13 = r33->size[0];
    r33->size[0] = r28->size[0];
    emxEnsureCapacity((emxArray__common *)r33, i13, (int32_T)sizeof(int32_T));
    i = r28->size[0];
    for (i13 = 0; i13 < i; i13++) {
      r33->data[i13] = r28->data[i13];
    }

    i = c_a->size[1];
    for (i13 = 0; i13 < i; i13++) {
      br = c_a->size[0];
      for (i14 = 0; i14 < br; i14++) {
        P[r33->data[i14] + 20 * r32->data[i13]] = c_a->data[i14 + c_a->size[0] *
          i13] * 0.0F;
      }
    }

    emxFree_int32_T(&r33);
    emxFree_int32_T(&r32);
    for (i = 0; i < 20; i++) {
      b_selector[i] = !selector[i];
    }

    eml_li_find(b_selector, r28);
    i13 = r28->size[0];
    r28->size[0] = r28->size[0];
    emxEnsureCapacity((emxArray__common *)r28, i13, (int32_T)sizeof(int32_T));
    i = r28->size[0];
    for (i13 = 0; i13 < i; i13++) {
      r28->data[i13]--;
    }

    eml_li_find(selector, r29);
    i13 = r29->size[0];
    r29->size[0] = r29->size[0];
    emxEnsureCapacity((emxArray__common *)r29, i13, (int32_T)sizeof(int32_T));
    i = r29->size[0];
    for (i13 = 0; i13 < i; i13++) {
      r29->data[i13]--;
    }

    eml_li_find(selector, r30);
    for (i = 0; i < 20; i++) {
      b_selector[i] = !selector[i];
    }

    eml_li_find(b_selector, r31);
    i13 = c_a->size[0] * c_a->size[1];
    c_a->size[0] = r31->size[0];
    c_a->size[1] = r30->size[0];
    emxEnsureCapacity((emxArray__common *)c_a, i13, (int32_T)sizeof(real32_T));
    i = r30->size[0];
    for (i13 = 0; i13 < i; i13++) {
      br = r31->size[0];
      for (i14 = 0; i14 < br; i14++) {
        c_a->data[i14 + c_a->size[0] * i13] = P[(r31->data[i14] + 20 *
          (r30->data[i13] - 1)) - 1];
      }
    }

    emxFree_int32_T(&r31);
    emxInit_int32_T(&r34, 1);
    i13 = r34->size[0];
    r34->size[0] = r29->size[0];
    emxEnsureCapacity((emxArray__common *)r34, i13, (int32_T)sizeof(int32_T));
    i = r29->size[0];
    for (i13 = 0; i13 < i; i13++) {
      r34->data[i13] = r29->data[i13];
    }

    emxInit_int32_T(&r35, 1);
    i13 = r35->size[0];
    r35->size[0] = r28->size[0];
    emxEnsureCapacity((emxArray__common *)r35, i13, (int32_T)sizeof(int32_T));
    i = r28->size[0];
    for (i13 = 0; i13 < i; i13++) {
      r35->data[i13] = r28->data[i13];
    }

    i = c_a->size[1];
    for (i13 = 0; i13 < i; i13++) {
      br = c_a->size[0];
      for (i14 = 0; i14 < br; i14++) {
        P[r35->data[i14] + 20 * r34->data[i13]] = c_a->data[i14 + c_a->size[0] *
          i13] * 0.0F;
      }
    }

    emxFree_int32_T(&r35);
    emxFree_int32_T(&r34);

    /* P(~selector,~selector)=P(~selector,~selector)*0; */
    eml_li_find(selector, r28);
    i13 = r28->size[0];
    r28->size[0] = r28->size[0];
    emxEnsureCapacity((emxArray__common *)r28, i13, (int32_T)sizeof(int32_T));
    i = r28->size[0];
    for (i13 = 0; i13 < i; i13++) {
      r28->data[i13]--;
    }

    emxInit_real32_T(&d_a, 2);
    eml_li_find(selector, r29);
    i13 = d_a->size[0] * d_a->size[1];
    d_a->size[0] = 1;
    d_a->size[1] = r29->size[0];
    emxEnsureCapacity((emxArray__common *)d_a, i13, (int32_T)sizeof(real32_T));
    i = r29->size[0];
    for (i13 = 0; i13 < i; i13++) {
      d_a->data[d_a->size[0] * i13] = H[r29->data[i13] - 1];
    }

    emxInit_real32_T(&b_b, 2);
    eml_li_find(selector, r29);
    eml_li_find(selector, r30);
    i13 = b_b->size[0] * b_b->size[1];
    b_b->size[0] = r30->size[0];
    b_b->size[1] = r29->size[0];
    emxEnsureCapacity((emxArray__common *)b_b, i13, (int32_T)sizeof(real32_T));
    i = r29->size[0];
    for (i13 = 0; i13 < i; i13++) {
      br = r30->size[0];
      for (i14 = 0; i14 < br; i14++) {
        b_b->data[i14 + b_b->size[0] * i13] = P[(r30->data[i14] + 20 *
          (r29->data[i13] - 1)) - 1];
      }
    }

    emxFree_int32_T(&r30);
    emxInit_real32_T(&c_y, 2);
    if ((d_a->size[1] == 1) || (b_b->size[0] == 1)) {
      i13 = c_y->size[0] * c_y->size[1];
      c_y->size[0] = 1;
      c_y->size[1] = b_b->size[1];
      emxEnsureCapacity((emxArray__common *)c_y, i13, (int32_T)sizeof(real32_T));
      i = b_b->size[1];
      for (i13 = 0; i13 < i; i13++) {
        c_y->data[c_y->size[0] * i13] = 0.0F;
        br = d_a->size[1];
        for (i14 = 0; i14 < br; i14++) {
          c_y->data[c_y->size[0] * i13] += d_a->data[d_a->size[0] * i14] *
            b_b->data[i14 + b_b->size[0] * i13];
        }
      }
    } else {
      unnamed_idx_1 = (uint32_T)b_b->size[1];
      i13 = c_y->size[0] * c_y->size[1];
      c_y->size[0] = 1;
      emxEnsureCapacity((emxArray__common *)c_y, i13, (int32_T)sizeof(real32_T));
      i13 = c_y->size[0] * c_y->size[1];
      c_y->size[1] = (int32_T)unnamed_idx_1;
      emxEnsureCapacity((emxArray__common *)c_y, i13, (int32_T)sizeof(real32_T));
      i = (int32_T)unnamed_idx_1;
      for (i13 = 0; i13 < i; i13++) {
        c_y->data[i13] = 0.0F;
      }

      if (b_b->size[1] == 0) {
      } else {
        for (i = 0; i < b_b->size[1]; i++) {
          for (ic = i; ic + 1 <= i + 1; ic++) {
            c_y->data[ic] = 0.0F;
          }
        }

        br = 0;
        for (i = 0; i < b_b->size[1]; i++) {
          ar = 0;
          i13 = br + d_a->size[1];
          for (ib = br; ib + 1 <= i13; ib++) {
            if (b_b->data[ib] != 0.0F) {
              ia = ar;
              for (ic = i; ic + 1 <= i + 1; ic++) {
                ia++;
                c_y->data[ic] += b_b->data[ib] * d_a->data[ia - 1];
              }
            }

            ar++;
          }

          br += d_a->size[1];
        }
      }
    }

    i = c_y->size[1];
    for (i13 = 0; i13 < i; i13++) {
      K[r28->data[i13]] = c_y->data[i13] / r;
    }

    emxFree_real32_T(&c_y);
    b_emxInit_real32_T(&e_a, 1);

    /*  check Jacobian */
    /*  delta=1e-12; */
    /*  db=[-C_SN*crossMx(b_N)*[delta;0;0],-C_SN*crossMx(b_N)*[0;delta;0],-C_SN*crossMx(b_N)*[0;0;delta]]; */
    /*  q1=quatUpdate(x(4:7),[delta;0;0]); */
    /*  q2=quatUpdate(x(4:7),[0;delta;0]); */
    /*  q3=quatUpdate(x(4:7),[0;0;delta]); */
    /*  db_finiteDiff=[quat2r(q1)'*b_N-C_SN*b_N, quat2r(q2)'*b_N-C_SN*b_N, quat2r(q3)'*b_N-C_SN*b_N]; */
    /*  db-db_finiteDiff */
    /*  update: */
    eml_li_find(selector, r28);
    i13 = e_a->size[0];
    e_a->size[0] = r28->size[0];
    emxEnsureCapacity((emxArray__common *)e_a, i13, (int32_T)sizeof(real32_T));
    i = r28->size[0];
    for (i13 = 0; i13 < i; i13++) {
      e_a->data[i13] = K[r28->data[i13] - 1];
    }

    eml_li_find(selector, r28);
    i13 = d_a->size[0] * d_a->size[1];
    d_a->size[0] = 1;
    d_a->size[1] = r28->size[0];
    emxEnsureCapacity((emxArray__common *)d_a, i13, (int32_T)sizeof(real32_T));
    i = r28->size[0];
    for (i13 = 0; i13 < i; i13++) {
      d_a->data[d_a->size[0] * i13] = H[r28->data[i13] - 1];
    }

    emxInit_real32_T(&KH, 2);
    i13 = KH->size[0] * KH->size[1];
    KH->size[0] = e_a->size[0];
    KH->size[1] = d_a->size[1];
    emxEnsureCapacity((emxArray__common *)KH, i13, (int32_T)sizeof(real32_T));
    i = e_a->size[0];
    for (i13 = 0; i13 < i; i13++) {
      br = d_a->size[1];
      for (i14 = 0; i14 < br; i14++) {
        KH->data[i13 + KH->size[0] * i14] = e_a->data[i13] * d_a->data[d_a->
          size[0] * i14];
      }
    }

    emxInit_real32_T(&r36, 2);
    eml_li_find(selector, r28);
    eml_li_find(selector, r29);
    i13 = r36->size[0] * r36->size[1];
    r36->size[0] = r29->size[0];
    r36->size[1] = r28->size[0];
    emxEnsureCapacity((emxArray__common *)r36, i13, (int32_T)sizeof(real32_T));
    i = r28->size[0];
    for (i13 = 0; i13 < i; i13++) {
      br = r29->size[0];
      for (i14 = 0; i14 < br; i14++) {
        r36->data[i14 + r36->size[0] * i13] = P[(r29->data[i14] + 20 *
          (r28->data[i13] - 1)) - 1];
      }
    }

    eml_li_find(selector, r28);
    eml_li_find(selector, r29);
    i13 = b_b->size[0] * b_b->size[1];
    b_b->size[0] = r29->size[0];
    b_b->size[1] = r28->size[0];
    emxEnsureCapacity((emxArray__common *)b_b, i13, (int32_T)sizeof(real32_T));
    i = r28->size[0];
    for (i13 = 0; i13 < i; i13++) {
      br = r29->size[0];
      for (i14 = 0; i14 < br; i14++) {
        b_b->data[i14 + b_b->size[0] * i13] = P[(r29->data[i14] + 20 *
          (r28->data[i13] - 1)) - 1];
      }
    }

    emxInit_real32_T(&C, 2);
    if ((KH->size[1] == 1) || (b_b->size[0] == 1)) {
      i13 = C->size[0] * C->size[1];
      C->size[0] = KH->size[0];
      C->size[1] = b_b->size[1];
      emxEnsureCapacity((emxArray__common *)C, i13, (int32_T)sizeof(real32_T));
      i = KH->size[0];
      for (i13 = 0; i13 < i; i13++) {
        br = b_b->size[1];
        for (i14 = 0; i14 < br; i14++) {
          C->data[i13 + C->size[0] * i14] = 0.0F;
          ar = KH->size[1];
          for (ib = 0; ib < ar; ib++) {
            C->data[i13 + C->size[0] * i14] += KH->data[i13 + KH->size[0] * ib] *
              b_b->data[ib + b_b->size[0] * i14];
          }
        }
      }
    } else {
      unnamed_idx_0 = (uint32_T)KH->size[0];
      unnamed_idx_1 = (uint32_T)b_b->size[1];
      i13 = C->size[0] * C->size[1];
      C->size[0] = (int32_T)unnamed_idx_0;
      emxEnsureCapacity((emxArray__common *)C, i13, (int32_T)sizeof(real32_T));
      i13 = C->size[0] * C->size[1];
      C->size[1] = (int32_T)unnamed_idx_1;
      emxEnsureCapacity((emxArray__common *)C, i13, (int32_T)sizeof(real32_T));
      i = (int32_T)unnamed_idx_0 * (int32_T)unnamed_idx_1;
      for (i13 = 0; i13 < i; i13++) {
        C->data[i13] = 0.0F;
      }

      if ((KH->size[0] == 0) || (b_b->size[1] == 0)) {
      } else {
        c = KH->size[0] * (b_b->size[1] - 1);
        for (i = 0; i <= c; i += KH->size[0]) {
          i13 = i + KH->size[0];
          for (ic = i; ic + 1 <= i13; ic++) {
            C->data[ic] = 0.0F;
          }
        }

        br = 0;
        for (i = 0; i <= c; i += KH->size[0]) {
          ar = 0;
          i13 = br + KH->size[1];
          for (ib = br; ib + 1 <= i13; ib++) {
            if (b_b->data[ib] != 0.0F) {
              ia = ar;
              i14 = i + KH->size[0];
              for (ic = i; ic + 1 <= i14; ic++) {
                ia++;
                C->data[ic] += b_b->data[ib] * KH->data[ia - 1];
              }
            }

            ar += KH->size[0];
          }

          br += KH->size[1];
        }
      }
    }

    eml_li_find(selector, r28);
    eml_li_find(selector, r29);
    i13 = c_a->size[0] * c_a->size[1];
    c_a->size[0] = r29->size[0];
    c_a->size[1] = r28->size[0];
    emxEnsureCapacity((emxArray__common *)c_a, i13, (int32_T)sizeof(real32_T));
    i = r28->size[0];
    for (i13 = 0; i13 < i; i13++) {
      br = r29->size[0];
      for (i14 = 0; i14 < br; i14++) {
        c_a->data[i14 + c_a->size[0] * i13] = P[(r29->data[i14] + 20 *
          (r28->data[i13] - 1)) - 1];
      }
    }

    i13 = b_b->size[0] * b_b->size[1];
    b_b->size[0] = KH->size[1];
    b_b->size[1] = KH->size[0];
    emxEnsureCapacity((emxArray__common *)b_b, i13, (int32_T)sizeof(real32_T));
    i = KH->size[0];
    for (i13 = 0; i13 < i; i13++) {
      br = KH->size[1];
      for (i14 = 0; i14 < br; i14++) {
        b_b->data[i14 + b_b->size[0] * i13] = KH->data[i13 + KH->size[0] * i14];
      }
    }

    if ((c_a->size[1] == 1) || (b_b->size[0] == 1)) {
      i13 = KH->size[0] * KH->size[1];
      KH->size[0] = c_a->size[0];
      KH->size[1] = b_b->size[1];
      emxEnsureCapacity((emxArray__common *)KH, i13, (int32_T)sizeof(real32_T));
      i = c_a->size[0];
      for (i13 = 0; i13 < i; i13++) {
        br = b_b->size[1];
        for (i14 = 0; i14 < br; i14++) {
          KH->data[i13 + KH->size[0] * i14] = 0.0F;
          ar = c_a->size[1];
          for (ib = 0; ib < ar; ib++) {
            KH->data[i13 + KH->size[0] * i14] += c_a->data[i13 + c_a->size[0] *
              ib] * b_b->data[ib + b_b->size[0] * i14];
          }
        }
      }
    } else {
      unnamed_idx_0 = (uint32_T)c_a->size[0];
      unnamed_idx_1 = (uint32_T)b_b->size[1];
      i13 = KH->size[0] * KH->size[1];
      KH->size[0] = (int32_T)unnamed_idx_0;
      emxEnsureCapacity((emxArray__common *)KH, i13, (int32_T)sizeof(real32_T));
      i13 = KH->size[0] * KH->size[1];
      KH->size[1] = (int32_T)unnamed_idx_1;
      emxEnsureCapacity((emxArray__common *)KH, i13, (int32_T)sizeof(real32_T));
      i = (int32_T)unnamed_idx_0 * (int32_T)unnamed_idx_1;
      for (i13 = 0; i13 < i; i13++) {
        KH->data[i13] = 0.0F;
      }

      if ((c_a->size[0] == 0) || (b_b->size[1] == 0)) {
      } else {
        c = c_a->size[0] * (b_b->size[1] - 1);
        for (i = 0; i <= c; i += c_a->size[0]) {
          i13 = i + c_a->size[0];
          for (ic = i; ic + 1 <= i13; ic++) {
            KH->data[ic] = 0.0F;
          }
        }

        br = 0;
        for (i = 0; i <= c; i += c_a->size[0]) {
          ar = 0;
          i13 = br + c_a->size[1];
          for (ib = br; ib + 1 <= i13; ib++) {
            if (b_b->data[ib] != 0.0F) {
              ia = ar;
              i14 = i + c_a->size[0];
              for (ic = i; ic + 1 <= i14; ic++) {
                ia++;
                KH->data[ic] += b_b->data[ib] * c_a->data[ia - 1];
              }
            }

            ar += c_a->size[0];
          }

          br += c_a->size[1];
        }
      }
    }

    emxFree_real32_T(&b_b);
    emxFree_real32_T(&c_a);
    eml_li_find(selector, r28);
    i13 = e_a->size[0];
    e_a->size[0] = r28->size[0];
    emxEnsureCapacity((emxArray__common *)e_a, i13, (int32_T)sizeof(real32_T));
    i = r28->size[0];
    for (i13 = 0; i13 < i; i13++) {
      e_a->data[i13] = K[r28->data[i13] - 1];
    }

    eml_li_find(selector, r28);
    i13 = d_a->size[0] * d_a->size[1];
    d_a->size[0] = 1;
    d_a->size[1] = r28->size[0];
    emxEnsureCapacity((emxArray__common *)d_a, i13, (int32_T)sizeof(real32_T));
    i = r28->size[0];
    for (i13 = 0; i13 < i; i13++) {
      d_a->data[d_a->size[0] * i13] = K[r28->data[i13] - 1];
    }

    eml_li_find(selector, r28);
    i13 = r28->size[0];
    r28->size[0] = r28->size[0];
    emxEnsureCapacity((emxArray__common *)r28, i13, (int32_T)sizeof(int32_T));
    i = r28->size[0];
    for (i13 = 0; i13 < i; i13++) {
      r28->data[i13]--;
    }

    eml_li_find(selector, r29);
    i13 = r29->size[0];
    r29->size[0] = r29->size[0];
    emxEnsureCapacity((emxArray__common *)r29, i13, (int32_T)sizeof(int32_T));
    i = r29->size[0];
    for (i13 = 0; i13 < i; i13++) {
      r29->data[i13]--;
    }

    emxInit_int32_T(&r37, 1);
    i13 = r37->size[0];
    r37->size[0] = r29->size[0];
    emxEnsureCapacity((emxArray__common *)r37, i13, (int32_T)sizeof(int32_T));
    i = r29->size[0];
    for (i13 = 0; i13 < i; i13++) {
      r37->data[i13] = r29->data[i13];
    }

    emxFree_int32_T(&r29);
    emxInit_int32_T(&r38, 1);
    i13 = r38->size[0];
    r38->size[0] = r28->size[0];
    emxEnsureCapacity((emxArray__common *)r38, i13, (int32_T)sizeof(int32_T));
    i = r28->size[0];
    for (i13 = 0; i13 < i; i13++) {
      r38->data[i13] = r28->data[i13];
    }

    emxFree_int32_T(&r28);
    i = e_a->size[0];
    for (i13 = 0; i13 < i; i13++) {
      br = d_a->size[1];
      for (i14 = 0; i14 < br; i14++) {
        dtheta_half_norm = e_a->data[i13] * r * d_a->data[d_a->size[0] * i14];
        P[r38->data[i13] + 20 * r37->data[i14]] = ((r36->data[i13 + r36->size[0]
          * i14] - C->data[i13 + C->size[0] * i14]) - KH->data[i13 + KH->size[0]
          * i14]) + dtheta_half_norm;
      }
    }

    emxFree_int32_T(&r38);
    emxFree_int32_T(&r37);
    emxFree_real32_T(&e_a);
    emxFree_real32_T(&d_a);
    emxFree_real32_T(&C);
    emxFree_real32_T(&r36);
    emxFree_real32_T(&KH);
    for (i13 = 0; i13 < 20; i13++) {
      K[i13] *= e;
    }

    for (i13 = 0; i13 < 3; i13++) {
      x->p[i13] += (real_T)K[i13];
    }

    for (i = 0; i < 3; i++) {
      y_Compass_N[i] = 0.5F * K[i + 3];
    }

    dtheta_half_norm = (real32_T)sqrt(dot(y_Compass_N, y_Compass_N));
    if ((real32_T)fabs(dtheta_half_norm) < 0.01F) {
      r = dtheta_half_norm * dtheta_half_norm;
      y = ((1.0F - 0.166666672F * r) + 0.00833333377F * (r * r)) -
        0.000198412701F * (r * r * r);
    } else {
      y = (real32_T)sin(dtheta_half_norm) / dtheta_half_norm;
    }

    for (i = 0; i < 3; i++) {
      dq[i] = y * y_Compass_N[i];
    }

    dq[3] = (real32_T)cos(dtheta_half_norm);

    /*  optimization (rectification of sinc) */
    /*  [ q3, q2, -q1, q0] */
    /*  [ -q2, q3, q0, q1] */
    /*  [ q1, -q0, q3, q2] */
    /*  [ -q0, -q1, -q2, q3] */
    /*  set float type */
    Q[0] = dq[3];
    Q[4] = dq[2];
    Q[8] = -dq[1];
    Q[12] = dq[0];
    Q[1] = -dq[2];
    Q[5] = dq[3];
    Q[9] = dq[0];
    Q[13] = dq[1];
    Q[2] = dq[1];
    Q[6] = -dq[0];
    Q[10] = dq[3];
    Q[14] = dq[2];
    Q[3] = -dq[0];
    Q[7] = -dq[1];
    Q[11] = -dq[2];
    Q[15] = dq[3];
    for (i13 = 0; i13 < 4; i13++) {
      dq[i13] = 0.0F;
      for (i14 = 0; i14 < 4; i14++) {
        r = dq[i13] + Q[i13 + (i14 << 2)] * x->q_NS[i14];
        dq[i13] = r;
      }
    }

    r = 0.0F;
    i = 0;
    br = 0;
    for (ar = 0; ar < 4; ar++) {
      r += dq[i] * dq[br];
      i++;
      br++;
    }

    r = (real32_T)sqrt(r);
    for (i13 = 0; i13 < 4; i13++) {
      dq[i13] /= r;
    }

    for (i = 0; i < 4; i++) {
      x->q_NS[i] = dq[i];
    }

    /*  Correct the angular state only with tilt D (tilt N and tilt E are Zero) */
    for (i13 = 0; i13 < 3; i13++) {
      x->v_N[i13] += K[6 + i13];
    }

    for (i13 = 0; i13 < 3; i13++) {
      x->b_g[i13] += K[9 + i13];
    }

    for (i13 = 0; i13 < 3; i13++) {
      x->b_a[i13] += K[12 + i13];
    }

    x->QFF += K[15];
    for (i13 = 0; i13 < 3; i13++) {
      x->w[i13] += K[16 + i13];
    }

    x->K += K[19];
  }
}