float test_quat2(void) { struct FloatEulers eula2b; EULERS_ASSIGN(eula2b, RadOfDeg(70.), RadOfDeg(0.), RadOfDeg(0.)); // DISPLAY_FLOAT_EULERS_DEG("eula2b", eula2b); struct FloatQuat qa2b; FLOAT_QUAT_OF_EULERS(qa2b, eula2b); DISPLAY_FLOAT_QUAT("qa2b", qa2b); struct DoubleEulers eula2b_d; EULERS_ASSIGN(eula2b_d, RadOfDeg(70.), RadOfDeg(0.), RadOfDeg(0.)); struct DoubleQuat qa2b_d; DOUBLE_QUAT_OF_EULERS(qa2b_d, eula2b_d); DISPLAY_FLOAT_QUAT("qa2b_d", qa2b_d); struct FloatVect3 u = { 1., 0., 0.}; float angle = RadOfDeg(70.); struct FloatQuat q; FLOAT_QUAT_OF_AXIS_ANGLE(q, u, angle); DISPLAY_FLOAT_QUAT("q ", q); struct FloatEulers eula2c; EULERS_ASSIGN(eula2c, RadOfDeg(80.), RadOfDeg(0.), RadOfDeg(0.)); // DISPLAY_FLOAT_EULERS_DEG("eula2c", eula2c); struct FloatQuat qa2c; FLOAT_QUAT_OF_EULERS(qa2c, eula2c); DISPLAY_FLOAT_QUAT("qa2c", qa2c); struct FloatQuat qb2a; FLOAT_QUAT_INVERT(qb2a, qa2b); DISPLAY_FLOAT_QUAT("qb2a", qb2a); struct FloatQuat qb2c1; FLOAT_QUAT_COMP(qb2c1, qb2a, qa2c); DISPLAY_FLOAT_QUAT("qb2c1", qb2c1); struct FloatQuat qb2c2; FLOAT_QUAT_INV_COMP(qb2c2, qa2b, qa2c); DISPLAY_FLOAT_QUAT("qb2c2", qb2c2); return 0.; }
float test_quat2(void) { struct FloatEulers eula2b; EULERS_ASSIGN(eula2b, RadOfDeg(70.), RadOfDeg(0.), RadOfDeg(0.)); // DISPLAY_FLOAT_EULERS_DEG("eula2b", eula2b); struct FloatQuat qa2b; float_quat_of_eulers(&qa2b, &eula2b); DISPLAY_FLOAT_QUAT("qa2b", qa2b); struct DoubleEulers eula2b_d; EULERS_ASSIGN(eula2b_d, RadOfDeg(70.), RadOfDeg(0.), RadOfDeg(0.)); struct DoubleQuat qa2b_d; double_quat_of_eulers(&qa2b_d, &eula2b_d); DISPLAY_FLOAT_QUAT("qa2b_d", qa2b_d); struct FloatVect3 u = { 1., 0., 0.}; float angle = RadOfDeg(70.); struct FloatQuat q; FLOAT_QUAT_OF_AXIS_ANGLE(q, u, angle); DISPLAY_FLOAT_QUAT("q ", q); struct FloatEulers eula2c; EULERS_ASSIGN(eula2c, RadOfDeg(80.), RadOfDeg(0.), RadOfDeg(0.)); // DISPLAY_FLOAT_EULERS_DEG("eula2c", eula2c); struct FloatQuat qa2c; float_quat_of_eulers(&qa2c, &eula2c); DISPLAY_FLOAT_QUAT("qa2c", qa2c); struct FloatQuat qb2a; FLOAT_QUAT_INVERT(qb2a, qa2b); DISPLAY_FLOAT_QUAT("qb2a", qb2a); struct FloatQuat qb2c1; float_quat_comp(&qb2c1, &qb2a, &qa2c); DISPLAY_FLOAT_QUAT("qb2c1", qb2c1); struct FloatQuat qb2c2; float_quat_inv_comp(&qb2c2, &qa2b, &qa2c); DISPLAY_FLOAT_QUAT("qb2c2", qb2c2); return 0.; }
float test_quat(void) { struct FloatVect3 u = { 1., 2., 3.}; FLOAT_VECT3_NORMALIZE(u); float angle = RadOfDeg(30.); struct FloatQuat q; FLOAT_QUAT_OF_AXIS_ANGLE(q, u, angle); DISPLAY_FLOAT_QUAT("q ", q); struct FloatQuat iq; FLOAT_QUAT_INVERT(iq, q); DISPLAY_FLOAT_QUAT("iq", iq); struct FloatQuat q1; FLOAT_QUAT_COMP(q1, q, iq); DISPLAY_FLOAT_QUAT("q1", q1); struct FloatQuat q2; FLOAT_QUAT_COMP(q2, q, iq); DISPLAY_FLOAT_QUAT("q2", q2); struct FloatQuat qe; QUAT_EXPLEMENTARY(qe, q); DISPLAY_FLOAT_QUAT("qe", qe); struct FloatVect3 a = { 2., 1., 3.}; DISPLAY_FLOAT_VECT3("a ", a); struct FloatVect3 a1; FLOAT_QUAT_VMULT(a1, q, a); DISPLAY_FLOAT_VECT3("a1", a1); struct FloatVect3 a2; FLOAT_QUAT_VMULT(a2, qe, a); DISPLAY_FLOAT_VECT3("a2", a2); return 0.; }
static void ahrs_do_update_mag(void) { int i, j, k; #ifdef BAFL_DEBUG2 printf("Mag update.\n"); #endif MAGS_FLOAT_OF_BFP(bafl_mag, imu.mag); /* P_prio = P */ for (i = 0; i < BAFL_SSIZE; i++) { for (j = 0; j < BAFL_SSIZE; j++) { bafl_Pprio[i][j] = bafl_P[i][j]; } } /* * set up measurement matrix * * h = [236.; -2.; 396.]; * hx = [ h(2); -h(1); 0]; //only psi (phi and theta = 0) * Hm = Cnb * hx; * H = [ 0 0 0 0 0 * 0 0 Cnb*hx 0 0 0 * 0 0 0 0 0 ]; * */ /*bafl_H[0][2] = RMAT_ELMT(bafl_dcm, 0, 0) * bafl_h.y - RMAT_ELMT(bafl_dcm, 0, 1) * bafl_h.x; bafl_H[1][2] = RMAT_ELMT(bafl_dcm, 1, 0) * bafl_h.y - RMAT_ELMT(bafl_dcm, 1, 1) * bafl_h.x; bafl_H[2][2] = RMAT_ELMT(bafl_dcm, 2, 0) * bafl_h.y - RMAT_ELMT(bafl_dcm, 2, 1) * bafl_h.x;*/ bafl_H[0][2] = -RMAT_ELMT(bafl_dcm, 0, 1); bafl_H[1][2] = -RMAT_ELMT(bafl_dcm, 1, 1); bafl_H[2][2] = -RMAT_ELMT(bafl_dcm, 2, 1); //rest is zero /********************************************** * compute Kalman gain K * * K = P_prio * H_T * inv(S) * S = H * P_prio * HT + R * * K = P_prio * HT * inv(H * P_prio * HT + R) * **********************************************/ /* covariance residual S = H * P_prio * HT + R */ /* temp_S(3x6) = H(3x6) * P_prio(6x6) * * only third column of H is non-zero */ for (i = 0; i < 3; i++) { for (j = 0; j < BAFL_SSIZE; j++) { bafl_tempS[i][j] = bafl_H[i][2] * bafl_Pprio[2][j]; } } /* S(3x3) = temp_S(3x6) * HT(6x3) + R(3x3) * * only third row of HT is non-zero */ for (i = 0; i < 3; i++) { for (j = 0; j < 3; j++) { bafl_S[i][j] = bafl_tempS[i][2] * bafl_H[j][2]; /* H[j][2] = HT[2][j] */ } bafl_S[i][i] += bafl_R_mag; } /* invert S */ FLOAT_MAT33_INVERT(bafl_invS, bafl_S); /* temp_K(6x3) = P_prio(6x6) * HT(6x3) * * only third row of HT is non-zero */ for (i = 0; i < BAFL_SSIZE; i++) { for (j = 0; j < 3; j++) { /* not computing zero elements */ bafl_tempK[i][j] = bafl_Pprio[i][2] * bafl_H[j][2]; /* H[j][2] = HT[2][j] */ } } /* K(6x3) = temp_K(6x3) * invS(3x3) */ for (i = 0; i < BAFL_SSIZE; i++) { for (j = 0; j < 3; j++) { bafl_K[i][j] = bafl_tempK[i][0] * bafl_invS[0][j]; bafl_K[i][j] += bafl_tempK[i][1] * bafl_invS[1][j]; bafl_K[i][j] += bafl_tempK[i][2] * bafl_invS[2][j]; } } /********************************************** * Update filter state. * * The a priori filter state is zero since the errors are corrected after each update. * * X = X_prio + K (y - H * X_prio) * X = K * y **********************************************/ /* innovation * y = Cnb * [hx; hy; hz] - mag */ FLOAT_RMAT_VECT3_MUL(bafl_ym, bafl_dcm, bafl_h); //can be optimized FLOAT_VECT3_SUB(bafl_ym, bafl_mag); /* X(6) = K(6x3) * y(3) */ for (i = 0; i < BAFL_SSIZE; i++) { bafl_X[i] = bafl_K[i][0] * bafl_ym.x; bafl_X[i] += bafl_K[i][1] * bafl_ym.y; bafl_X[i] += bafl_K[i][2] * bafl_ym.z; } /********************************************** * Update the filter covariance. * * P = P_prio - K * H * P_prio * P = ( I - K * H ) * P_prio * **********************************************/ /* temp(6x6) = I(6x6) - K(6x3)*H(3x6) * * last 3 columns of H are zero */ for (i = 0; i < 6; i++) { for (j = 0; j < 6; j++) { if (i == j) { bafl_tempP[i][j] = 1.; } else { bafl_tempP[i][j] = 0.; } if (j == 2) { /* omit the parts where H is zero */ for (k = 0; k < 3; k++) { bafl_tempP[i][j] -= bafl_K[i][k] * bafl_H[k][j]; } } } } /* P(6x6) = temp(6x6) * P_prio(6x6) */ for (i = 0; i < BAFL_SSIZE; i++) { for (j = 0; j < BAFL_SSIZE; j++) { bafl_P[i][j] = bafl_tempP[i][0] * bafl_Pprio[0][j]; for (k = 1; k < BAFL_SSIZE; k++) { bafl_P[i][j] += bafl_tempP[i][k] * bafl_Pprio[k][j]; } } } #ifdef LKF_PRINT_P printf("Pum="); for (i = 0; i < 6; i++) { printf("["); for (j = 0; j < 6; j++) { printf("%f\t", bafl_P[i][j]); } printf("]\n "); } printf("\n"); #endif /********************************************** * Correct errors. * * **********************************************/ /* Error quaternion. */ QUAT_ASSIGN(bafl_q_m_err, 1.0, bafl_X[0]/2, bafl_X[1]/2, bafl_X[2]/2); FLOAT_QUAT_INVERT(bafl_q_m_err, bafl_q_m_err); /* normalize */ float q_sq; q_sq = bafl_q_m_err.qx * bafl_q_m_err.qx + bafl_q_m_err.qy * bafl_q_m_err.qy + bafl_q_m_err.qz * bafl_q_m_err.qz; if (q_sq > 1) { /* this should actually never happen */ FLOAT_QUAT_SMUL(bafl_q_m_err, bafl_q_m_err, 1 / sqrtf(1 + q_sq)); printf("mag error quaternion q_sq > 1!!\n"); } else { bafl_q_m_err.qi = sqrtf(1 - q_sq); } /* correct attitude */ FLOAT_QUAT_COMP(bafl_qtemp, bafl_q_m_err, bafl_quat); FLOAT_QUAT_COPY(bafl_quat, bafl_qtemp); /* correct gyro bias */ RATES_ASSIGN(bafl_b_m_err, bafl_X[3], bafl_X[4], bafl_X[5]); RATES_SUB(bafl_bias, bafl_b_m_err); /* * compute all representations */ /* maintain rotation matrix representation */ FLOAT_RMAT_OF_QUAT(bafl_dcm, bafl_quat); /* maintain euler representation */ FLOAT_EULERS_OF_RMAT(bafl_eulers, bafl_dcm); AHRS_TO_BFP(); AHRS_LTP_TO_BODY(); }
static void ahrs_do_update_accel(void) { int i, j, k; #ifdef BAFL_DEBUG2 printf("Accel update.\n"); #endif /* P_prio = P */ for (i = 0; i < BAFL_SSIZE; i++) { for (j = 0; j < BAFL_SSIZE; j++) { bafl_Pprio[i][j] = bafl_P[i][j]; } } /* * set up measurement matrix * * g = 9.81 * gx = [ 0 -g 0 * g 0 0 * 0 0 0 ] * H = [ 0 0 0 ] * [ -Cnb*gx 0 0 0 ] * [ 0 0 0 ] * * */ bafl_H[0][0] = -RMAT_ELMT(bafl_dcm, 0, 1) * BAFL_g; bafl_H[0][1] = RMAT_ELMT(bafl_dcm, 0, 0) * BAFL_g; bafl_H[1][0] = -RMAT_ELMT(bafl_dcm, 1, 1) * BAFL_g; bafl_H[1][1] = RMAT_ELMT(bafl_dcm, 1, 0) * BAFL_g; bafl_H[2][0] = -RMAT_ELMT(bafl_dcm, 2, 1) * BAFL_g; bafl_H[2][1] = RMAT_ELMT(bafl_dcm, 2, 0) * BAFL_g; /* rest is zero bafl_H[0][2] = 0.; bafl_H[1][2] = 0.; bafl_H[2][2] = 0.;*/ /********************************************** * compute Kalman gain K * * K = P_prio * H_T * inv(S) * S = H * P_prio * HT + R * * K = P_prio * HT * inv(H * P_prio * HT + R) * **********************************************/ /* covariance residual S = H * P_prio * HT + R */ /* temp_S(3x6) = H(3x6) * P_prio(6x6) * last 4 columns of H are zero */ for (i = 0; i < 3; i++) { for (j = 0; j < BAFL_SSIZE; j++) { bafl_tempS[i][j] = bafl_H[i][0] * bafl_Pprio[0][j]; bafl_tempS[i][j] += bafl_H[i][1] * bafl_Pprio[1][j]; } } /* S(3x3) = temp_S(3x6) * HT(6x3) + R(3x3) * * bottom 4 rows of HT are zero */ for (i = 0; i < 3; i++) { for (j = 0; j < 3; j++) { bafl_S[i][j] = bafl_tempS[i][0] * bafl_H[j][0]; /* H[j][0] = HT[0][j] */ bafl_S[i][j] += bafl_tempS[i][1] * bafl_H[j][1]; /* H[j][0] = HT[0][j] */ } bafl_S[i][i] += bafl_R_accel; } /* invert S */ FLOAT_MAT33_INVERT(bafl_invS, bafl_S); /* temp_K(6x3) = P_prio(6x6) * HT(6x3) * * bottom 4 rows of HT are zero */ for (i = 0; i < BAFL_SSIZE; i++) { for (j = 0; j < 3; j++) { /* not computing zero elements */ bafl_tempK[i][j] = bafl_Pprio[i][0] * bafl_H[j][0]; /* H[j][0] = HT[0][j] */ bafl_tempK[i][j] += bafl_Pprio[i][1] * bafl_H[j][1]; /* H[j][1] = HT[1][j] */ } } /* K(6x3) = temp_K(6x3) * invS(3x3) */ for (i = 0; i < BAFL_SSIZE; i++) { for (j = 0; j < 3; j++) { bafl_K[i][j] = bafl_tempK[i][0] * bafl_invS[0][j]; bafl_K[i][j] += bafl_tempK[i][1] * bafl_invS[1][j]; bafl_K[i][j] += bafl_tempK[i][2] * bafl_invS[2][j]; } } /********************************************** * Update filter state. * * The a priori filter state is zero since the errors are corrected after each update. * * X = X_prio + K (y - H * X_prio) * X = K * y **********************************************/ /*printf("R = "); for (i = 0; i < 3; i++) { printf("["); for (j = 0; j < 3; j++) { printf("%f\t", RMAT_ELMT(bafl_dcm, i, j)); } printf("]\n "); } printf("\n");*/ /* innovation * y = Cnb * -[0; 0; g] - accel */ bafl_ya.x = -RMAT_ELMT(bafl_dcm, 0, 2) * BAFL_g - bafl_accel_measure.x; bafl_ya.y = -RMAT_ELMT(bafl_dcm, 1, 2) * BAFL_g - bafl_accel_measure.y; bafl_ya.z = -RMAT_ELMT(bafl_dcm, 2, 2) * BAFL_g - bafl_accel_measure.z; /* X(6) = K(6x3) * y(3) */ for (i = 0; i < BAFL_SSIZE; i++) { bafl_X[i] = bafl_K[i][0] * bafl_ya.x; bafl_X[i] += bafl_K[i][1] * bafl_ya.y; bafl_X[i] += bafl_K[i][2] * bafl_ya.z; } /********************************************** * Update the filter covariance. * * P = P_prio - K * H * P_prio * P = ( I - K * H ) * P_prio * **********************************************/ /* temp(6x6) = I(6x6) - K(6x3)*H(3x6) * * last 4 columns of H are zero */ for (i = 0; i < BAFL_SSIZE; i++) { for (j = 0; j < BAFL_SSIZE; j++) { if (i == j) { bafl_tempP[i][j] = 1.; } else { bafl_tempP[i][j] = 0.; } if (j < 2) { /* omit the parts where H is zero */ for (k = 0; k < 3; k++) { bafl_tempP[i][j] -= bafl_K[i][k] * bafl_H[k][j]; } } } } /* P(6x6) = temp(6x6) * P_prio(6x6) */ for (i = 0; i < BAFL_SSIZE; i++) { for (j = 0; j < BAFL_SSIZE; j++) { bafl_P[i][j] = bafl_tempP[i][0] * bafl_Pprio[0][j]; for (k = 1; k < BAFL_SSIZE; k++) { bafl_P[i][j] += bafl_tempP[i][k] * bafl_Pprio[k][j]; } } } #ifdef LKF_PRINT_P printf("Pua="); for (i = 0; i < 6; i++) { printf("["); for (j = 0; j < 6; j++) { printf("%f\t", bafl_P[i][j]); } printf("]\n "); } printf("\n"); #endif /********************************************** * Correct errors. * * **********************************************/ /* Error quaternion. */ QUAT_ASSIGN(bafl_q_a_err, 1.0, bafl_X[0]/2, bafl_X[1]/2, bafl_X[2]/2); FLOAT_QUAT_INVERT(bafl_q_a_err, bafl_q_a_err); /* normalize * Is this needed? Or is the approximation good enough?*/ float q_sq; q_sq = bafl_q_a_err.qx * bafl_q_a_err.qx + bafl_q_a_err.qy * bafl_q_a_err.qy + bafl_q_a_err.qz * bafl_q_a_err.qz; if (q_sq > 1) { /* this should actually never happen */ FLOAT_QUAT_SMUL(bafl_q_a_err, bafl_q_a_err, 1 / sqrtf(1 + q_sq)); printf("Accel error quaternion q_sq > 1!!\n"); } else { bafl_q_a_err.qi = sqrtf(1 - q_sq); } /* correct attitude */ FLOAT_QUAT_COMP(bafl_qtemp, bafl_q_a_err, bafl_quat); FLOAT_QUAT_COPY(bafl_quat, bafl_qtemp); /* correct gyro bias */ RATES_ASSIGN(bafl_b_a_err, bafl_X[3], bafl_X[4], bafl_X[5]); RATES_SUB(bafl_bias, bafl_b_a_err); /* * compute all representations */ /* maintain rotation matrix representation */ FLOAT_RMAT_OF_QUAT(bafl_dcm, bafl_quat); /* maintain euler representation */ FLOAT_EULERS_OF_RMAT(bafl_eulers, bafl_dcm); AHRS_TO_BFP(); AHRS_LTP_TO_BODY(); }