void ahrs_init(void) { QUAT_ASSIGN(ned_to_body_orientation_quat_i, 1, 0, 0, 0); INT32_QUAT_NORMALIZE(ned_to_body_orientation_quat_i); RATES_ASSIGN(body_rates_i, 0, 0, 0); ahrs.status = AHRS_UNINIT; ahrs_impl.ltp_vel_norm_valid = FALSE; ahrs_impl.heading_aligned = FALSE; /* set ltp_to_imu so that body is zero */ QUAT_COPY(ahrs_impl.ltp_to_imu_quat, imu.body_to_imu_quat); INT_RATES_ZERO(ahrs_impl.imu_rate); INT_RATES_ZERO(ahrs_impl.gyro_bias); INT_RATES_ZERO(ahrs_impl.rate_correction); INT_RATES_ZERO(ahrs_impl.high_rez_bias); #if AHRS_GRAVITY_UPDATE_COORDINATED_TURN ahrs_impl.correct_gravity = TRUE; #else ahrs_impl.correct_gravity = FALSE; #endif #if AHRS_GRAVITY_UPDATE_NORM_HEURISTIC ahrs_impl.use_gravity_heuristic = TRUE; #else ahrs_impl.use_gravity_heuristic = FALSE; #endif VECT3_ASSIGN(ahrs_impl.mag_h, MAG_BFP_OF_REAL(AHRS_H_X), MAG_BFP_OF_REAL(AHRS_H_Y), MAG_BFP_OF_REAL(AHRS_H_Z)); }
/* the following solver uses the Power Iteration * * It is rather simple: * 1. You choose a starting vektor x_0 (shouldn't be zero) * 2. apply it on the Matrix * x_(k+1) = A * x_k * 3. Repeat this very often. * * The vector converges to the dominat eigenvector, which belongs to the eigenvalue with the biggest absolute value. * * But there is a problem: * With every step, the norm of vector grows. Therefore it's necessary to scale it with every step. * * Important warnings: * I. This function does not converge if the Matrix is singular * II. Pay attention to the loop-condition! It does not end if it's close to the eigenvector! * It ends if the steps are getting too close to each other. * */ DoubleVect4 dominant_Eigenvector(struct DoubleMat44 A, unsigned int maximum_iterations, double precision, struct DoubleMat44 sigma_A, DoubleVect4 *sigma_x) { unsigned int k; DoubleVect4 x_k, x_kp1; double delta = 1, scale; FLOAT_QUAT_ZERO(x_k); //for(k=0; (k<maximum_iterations) && (delta>precision); k++){ for (k = 0; k < maximum_iterations; k++) { // Next step DOUBLE_MAT_VMULT4(x_kp1, A, x_k); // Scale the vector scale = 1 / INFTY_NORM4(x_kp1); QUAT_SMUL(x_kp1, x_kp1, scale); // Calculate the difference between to steps for the loop condition. Store temporarily in x_k QUAT_DIFF(x_k, x_k, x_kp1); delta = INFTY_NORM4(x_k); // Update the next step x_k = x_kp1; if (delta <= precision) { DOUBLE_MAT_VMULT4(*sigma_x, sigma_A, x_k); QUAT_SMUL(*sigma_x, *sigma_x, scale); break; } } #ifdef EKNAV_FROM_LOG_DEBUG printf("Number of iterations: %4i\n", k); #endif if (k == maximum_iterations) { printf("Orientation did not converge. Using maximum uncertainty\n"); //FLOAT_QUAT_ZERO(x_k); QUAT_ASSIGN(*sigma_x, 0, M_PI_2, M_PI_2, M_PI_2); } return x_k; }
static void print_estimator_state(double time) { #if FILTER_OUTPUT_IN_NED struct EcefCoor_d pos_ecef, cur_pos_ecef, cur_vel_ecef; struct NedCoor_d pos_ned, vel_ned; struct DoubleQuat q_ecef2body, q_ecef2enu, q_enu2body, q_ned2enu, q_ned2body; VECTOR_AS_VECT3(pos_ecef,pos_0_ecef); VECTOR_AS_VECT3(cur_pos_ecef,ins.avg_state.position); VECTOR_AS_VECT3(cur_vel_ecef,ins.avg_state.velocity); ned_of_ecef_point_d(&pos_ned, ¤t_ltp, &cur_pos_ecef); ned_of_ecef_vect_d(&vel_ned, ¤t_ltp, &cur_vel_ecef); int32_t xdd = 0; int32_t ydd = 0; int32_t zdd = 0; int32_t xd = vel_ned.x/0.0000019073; int32_t yd = vel_ned.y/0.0000019073; int32_t zd = vel_ned.z/0.0000019073; int32_t x = pos_ned.x/0.0039; int32_t y = pos_ned.y/0.0039; int32_t z = pos_ned.z/0.0039; fprintf(ins_logfile, "%f %d BOOZ2_INS2 %d %d %d %d %d %d %d %d %d\n", time, AC_ID, xdd, ydd, zdd, xd, yd, zd, x, y, z); #if 0 QUAT_ASSIGN(q_ecef2body, ins.avg_state.orientation.w(), -ins.avg_state.orientation.x(), -ins.avg_state.orientation.y(), -ins.avg_state.orientation.z()); QUAT_ASSIGN(q_ned2enu, 0, M_SQRT1_2, M_SQRT1_2, 0); FLOAT_QUAT_OF_RMAT(q_ecef2enu, current_ltp.ltp_of_ecef); FLOAT_QUAT_INV_COMP(q_enu2body, q_ecef2enu, q_ecef2body); // q_enu2body = q_ecef2body * (q_ecef2enu)^* FLOAT_QUAT_COMP(q_ned2body, q_ned2enu, q_enu2body); // q_ned2body = q_enu2body * q_ned2enu #else /* if 0 */ QUATERNIOND_AS_DOUBLEQUAT(q_ecef2body, ins.avg_state.orientation); DOUBLE_QUAT_OF_RMAT(q_ecef2enu, current_ltp.ltp_of_ecef); FLOAT_QUAT_INV_COMP(q_enu2body, q_ecef2enu, q_ecef2body); QUAT_ENU_FROM_TO_NED(q_enu2body, q_ned2body); #endif /* if 0 */ struct FloatEulers e; FLOAT_EULERS_OF_QUAT(e, q_ned2body); #if PRINT_EULER_NED printf("EULER % 6.1f % 6.1f % 6.1f\n", e.phi*180*M_1_PI, e.theta*180*M_1_PI, e.psi*180*M_1_PI); #endif /* PRINT_EULER_NED */ fprintf(ins_logfile, "%f %d AHRS_EULER %f %f %f\n", time, AC_ID, e.phi, e.theta, e.psi); fprintf(ins_logfile, "%f %d DEBUG_COVARIANCE %f %f %f %f %f %f %f %f %f %f %f %f\n", time, AC_ID, sqrt(ins.cov( 0, 0)), sqrt(ins.cov( 1, 1)), sqrt(ins.cov( 2, 2)), sqrt(ins.cov( 3, 3)), sqrt(ins.cov( 4, 4)), sqrt(ins.cov( 5, 5)), sqrt(ins.cov( 6, 6)), sqrt(ins.cov( 7, 7)), sqrt(ins.cov( 8, 8)), sqrt(ins.cov( 9, 9)), sqrt(ins.cov(10,10)), sqrt(ins.cov(11,11))); fprintf(ins_logfile, "%f %d BOOZ_SIM_GYRO_BIAS %f %f %f\n", time, AC_ID, ins.avg_state.gyro_bias(0), ins.avg_state.gyro_bias(1), ins.avg_state.gyro_bias(2)); #else /* FILTER_OUTPUT_IN_ECEF */ int32_t xdd = 0; int32_t ydd = 0; int32_t zdd = 0; int32_t xd = ins.avg_state.velocity(0)/0.0000019073; int32_t yd = ins.avg_state.velocity(1)/0.0000019073; int32_t zd = ins.avg_state.velocity(2)/0.0000019073; int32_t x = ins.avg_state.position(0)/0.0039; int32_t y = ins.avg_state.position(1)/0.0039; int32_t z = ins.avg_state.position(2)/0.0039; fprintf(ins_logfile, "%f %d BOOZ2_INS2 %d %d %d %d %d %d %d %d %d\n", time, AC_ID, xdd, ydd, zdd, xd, yd, zd, x, y, z); struct FloatQuat q_ecef2body; QUAT_ASSIGN(q_ecef2body, ins.avg_state.orientation.w(), ins.avg_state.orientation.x(), ins.avg_state.orientation.y(), ins.avg_state.orientation.z()); struct FloatEulers e_ecef2body; FLOAT_EULERS_OF_QUAT(e_ecef2body, q_ecef2body); fprintf(ins_logfile, "%f %d AHRS_EULER %f %f %f\n", time, AC_ID, e_ecef2body.phi, e_ecef2body.theta, e_ecef2body.psi); fprintf(ins_logfile, "%f %d DEBUG_COVARIANCE %f %f %f %f %f %f %f %f %f %f %f %f\n", time, AC_ID, sqrt(ins.cov( 0, 0)), sqrt(ins.cov( 1, 1)), sqrt(ins.cov( 2, 2)), sqrt(ins.cov( 3, 3)), sqrt(ins.cov( 4, 4)), sqrt(ins.cov( 5, 5)), sqrt(ins.cov( 6, 6)), sqrt(ins.cov( 7, 7)), sqrt(ins.cov( 8, 8)), sqrt(ins.cov( 9, 9)), sqrt(ins.cov(10,10)), sqrt(ins.cov(11,11))); fprintf(ins_logfile, "%f %d BOOZ_SIM_GYRO_BIAS %f %f %f\n", time, AC_ID, ins.avg_state.gyro_bias(0), ins.avg_state.gyro_bias(1), ins.avg_state.gyro_bias(2)); #endif /* FILTER_OUTPUT_IN_NED / ECEF */ }
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(); }
/* * Propagate our dynamic system in time * * Run the strapdown computation and the predict step of the filter * * * quat_dot = Wxq(pqr) * quat * bias_dot = 0 * * Wxq is the quaternion omega matrix: * * [ 0, -p, -q, -r ] * 1/2 * [ p, 0, r, -q ] * [ q, -r, 0, p ] * [ r, q, -p, 0 ] * */ void ahrs_propagate(void) { int i, j, k; ahrs_lowpass_accel(); /* compute unbiased rates */ RATES_FLOAT_OF_BFP(bafl_rates, imu.gyro); RATES_SUB(bafl_rates, bafl_bias); /* run strapdown computation * */ /* multiplicative quaternion update */ /* compute correction quaternion */ QUAT_ASSIGN(bafl_qr, 1., bafl_rates.p * BAFL_DT / 2, bafl_rates.q * BAFL_DT / 2, bafl_rates.r * BAFL_DT / 2); /* normalize it. maybe not necessary?? */ float q_sq; q_sq = (bafl_qr.qx * bafl_qr.qx +bafl_qr.qy * bafl_qr.qy + bafl_qr.qz * bafl_qr.qz) / 4; if (q_sq > 1) { /* this should actually never happen */ FLOAT_QUAT_SMUL(bafl_qr, bafl_qr, 1 / sqrtf(1 + q_sq)); } else { bafl_qr.qi = sqrtf(1 - q_sq); } /* propagate correction quaternion */ FLOAT_QUAT_COMP(bafl_qtemp, bafl_quat, bafl_qr); FLOAT_QUAT_COPY(bafl_quat, bafl_qtemp); bafl_qnorm = FLOAT_QUAT_NORM(bafl_quat); //TODO check if broot force normalization is good, use lagrange normalization? FLOAT_QUAT_NORMALISE(bafl_quat); /* * 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(); /* error KF-Filter * propagate only the error covariance matrix since error is corrected after each measurement * * F = [ 0 0 0 ] * [ 0 0 0 -Cbn ] * [ 0 0 0 ] * [ 0 0 0 0 0 0 ] * [ 0 0 0 0 0 0 ] * [ 0 0 0 0 0 0 ] * * T = e^(dt * F) * * T = [ 1 0 0 ] * [ 0 1 0 -Cbn*dt ] * [ 0 0 1 ] * [ 0 0 0 1 0 0 ] * [ 0 0 0 0 1 0 ] * [ 0 0 0 0 0 1 ] * * P_prio = T * P * T_T + Q * */ /* * compute state transition matrix T * * diagonal elements of T are always one */ for (i = 0; i < 3; i++) { for (j = 0; j < 3; j++) { bafl_T[i][j + 3] = -RMAT_ELMT(bafl_dcm, j, i); /* inverted bafl_dcm */ } } /* * estimate the a priori error covariance matrix P_k = T * P_k-1 * T_T + Q */ /* Temporary multiplication temp(6x6) = T(6x6) * P(6x6) */ for (i = 0; i < BAFL_SSIZE; i++) { for (j = 0; j < BAFL_SSIZE; j++) { bafl_tempP[i][j] = 0.; for (k = 0; k < BAFL_SSIZE; k++) { bafl_tempP[i][j] += bafl_T[i][k] * bafl_P[k][j]; } } } /* P_k(6x6) = temp(6x6) * T_T(6x6) + Q */ for (i = 0; i < BAFL_SSIZE; i++) { for (j = 0; j < BAFL_SSIZE; j++) { bafl_P[i][j] = 0.; for (k = 0; k < BAFL_SSIZE; k++) { bafl_P[i][j] += bafl_tempP[i][k] * bafl_T[j][k]; //T[j][k] = T_T[k][j] } } if (i<3) { bafl_P[i][i] += bafl_Q_att; } else { bafl_P[i][i] += bafl_Q_gyro; } } #ifdef LKF_PRINT_P printf("Pp ="); 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 }
void quat_from_earth_cmd_f(struct FloatQuat *quat, struct FloatVect2 *cmd, float heading) { /* cmd_x is positive to north = negative pitch * cmd_y is positive to east = positive roll * * orientation vector describing simultaneous rotation of roll/pitch */ const struct FloatVect3 ov = {cmd->y, -cmd->x, 0.0}; /* quaternion from that orientation vector */ struct FloatQuat q_rp; float_quat_of_orientation_vect(&q_rp, &ov); /* as rotation matrix */ struct FloatRMat R_rp; float_rmat_of_quat(&R_rp, &q_rp); /* body x-axis (before heading command) is first column */ struct FloatVect3 b_x; VECT3_ASSIGN(b_x, R_rp.m[0], R_rp.m[3], R_rp.m[6]); /* body z-axis (thrust vect) is last column */ struct FloatVect3 thrust_vect; VECT3_ASSIGN(thrust_vect, R_rp.m[2], R_rp.m[5], R_rp.m[8]); /// @todo optimize yaw angle calculation /* * Instead of using the psi setpoint angle to rotate around the body z-axis, * calculate the real angle needed to align the projection of the body x-axis * onto the horizontal plane with the psi setpoint. * * angle between two vectors a and b: * angle = atan2(norm(cross(a,b)), dot(a,b)) * sign(dot(cross(a,b), n)) * where the normal n is the thrust vector (i.e. both a and b lie in that plane) */ // desired heading vect in earth x-y plane const struct FloatVect3 psi_vect = {cosf(heading), sinf(heading), 0.0}; /* projection of desired heading onto body x-y plane * b = v - dot(v,n)*n */ float dot = VECT3_DOT_PRODUCT(psi_vect, thrust_vect); struct FloatVect3 dotn; VECT3_SMUL(dotn, thrust_vect, dot); // b = v - dot(v,n)*n struct FloatVect3 b; VECT3_DIFF(b, psi_vect, dotn); dot = VECT3_DOT_PRODUCT(b_x, b); struct FloatVect3 cross; VECT3_CROSS_PRODUCT(cross, b_x, b); // norm of the cross product float nc = FLOAT_VECT3_NORM(cross); // angle = atan2(norm(cross(a,b)), dot(a,b)) float yaw2 = atan2(nc, dot) / 2.0; // negative angle if needed // sign(dot(cross(a,b), n) float dot_cross_ab = VECT3_DOT_PRODUCT(cross, thrust_vect); if (dot_cross_ab < 0) { yaw2 = -yaw2; } /* quaternion with yaw command */ struct FloatQuat q_yaw; QUAT_ASSIGN(q_yaw, cosf(yaw2), 0.0, 0.0, sinf(yaw2)); /* final setpoint: apply roll/pitch, then yaw around resulting body z-axis */ float_quat_comp(quat, &q_rp, &q_yaw); float_quat_normalize(quat); float_quat_wrap_shortest(quat); }