/** ****************************************************************************** * @addtogroup AHRS * @{ * @addtogroup INSGPS * @{ * @brief INSGPS is a joint attitude and position estimation EKF * * @file insgps.c * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @brief An INS/GPS algorithm implemented with an EKF. * * @see The GNU Public License (GPL) Version 3 * *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by * the Free Software Foundation; either version 3 of the License, or * (at your option) any later version. * * This program is distributed in the hope that it will be useful, but * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License * for more details. * * You should have received a copy of the GNU General Public License along * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ #include "insgps.h" #include #include // constants/macros/typdefs #define NUMX 13 // number of states, X is the state vector #define NUMW 9 // number of plant noise inputs, w is disturbance noise vector #define NUMV 10 // number of measurements, v is the measurement noise vector #define NUMU 6 // number of deterministic inputs, U is the input vector #if defined(GENERAL_COV) // This might trick people so I have a note here. There is a slower but bigger version of the // code here but won't fit when debugging disabled (requires -Os) #define COVARIANCE_PREDICTION_GENERAL #endif // Private functions void CovariancePrediction(float F[NUMX][NUMX], float G[NUMX][NUMW], float Q[NUMW], float dT, float P[NUMX][NUMX]); void SerialUpdate(float H[NUMV][NUMX], float R[NUMV], float Z[NUMV], float Y[NUMV], float P[NUMX][NUMX], float X[NUMX], uint16_t SensorsUsed); void RungeKutta(float X[NUMX], float U[NUMU], float dT); void StateEq(float X[NUMX], float U[NUMU], float Xdot[NUMX]); void LinearizeFG(float X[NUMX], float U[NUMU], float F[NUMX][NUMX], float G[NUMX][NUMW]); void MeasurementEq(float X[NUMX], float Be[3], float Y[NUMV]); void LinearizeH(float X[NUMX], float Be[3], float H[NUMV][NUMX]); // Private variables float F[NUMX][NUMX], G[NUMX][NUMW], H[NUMV][NUMX]; // linearized system matrices // global to init to zero and maintain zero elements float Be[3]; // local magnetic unit vector in NED frame float P[NUMX][NUMX], X[NUMX]; // covariance matrix and state vector float Q[NUMW], R[NUMV]; // input noise and measurement noise variances float K[NUMX][NUMV]; // feedback gain matrix // ************* Exposed Functions **************** // ************************************************* uint16_t ins_get_num_states() { return NUMX; } void INSGPSInit() //pretty much just a place holder for now { Be[0] = 1.0f; Be[1] = 0.0f; Be[2] = 0.0f; // local magnetic unit vector for (int i = 0; i < NUMX; i++) { for (int j = 0; j < NUMX; j++) { P[i][j] = 0.0f; // zero all terms F[i][j] = 0.0f; } for (int j = 0; j < NUMW; j++) G[i][j] = 0.0f; for (int j = 0; j < NUMV; j++) { H[j][i] = 0.0f; K[i][j] = 0.0f; } X[i] = 0.0f; } for (int i = 0; i < NUMW; i++) Q[i] = 0.0f; for (int i = 0; i < NUMV; i++) R[i] = 0.0f; P[0][0] = P[1][1] = P[2][2] = 25.0f; // initial position variance (m^2) P[3][3] = P[4][4] = P[5][5] = 5.0f; // initial velocity variance (m/s)^2 P[6][6] = P[7][7] = P[8][8] = P[9][9] = 1e-5f; // initial quaternion variance P[10][10] = P[11][11] = P[12][12] = 1e-9f; // initial gyro bias variance (rad/s)^2 X[0] = X[1] = X[2] = X[3] = X[4] = X[5] = 0.0f; // initial pos and vel (m) X[6] = 1.0f; X[7] = X[8] = X[9] = 0.0f; // initial quaternion (level and North) (m/s) X[10] = X[11] = X[12] = 0.0f; // initial gyro bias (rad/s) Q[0] = Q[1] = Q[2] = 50e-4f; // gyro noise variance (rad/s)^2 Q[3] = Q[4] = Q[5] = 0.00001f; // accelerometer noise variance (m/s^2)^2 Q[6] = Q[7] = Q[8] = 2e-8f; // gyro bias random walk variance (rad/s^2)^2 R[0] = R[1] = 0.004f; // High freq GPS horizontal position noise variance (m^2) R[2] = 0.036f; // High freq GPS vertical position noise variance (m^2) R[3] = R[4] = 0.004f; // High freq GPS horizontal velocity noise variance (m/s)^2 R[5] = 100.0f; // High freq GPS vertical velocity noise variance (m/s)^2 R[6] = R[7] = R[8] = 0.005f; // magnetometer unit vector noise variance R[9] = .05f; // High freq altimeter noise variance (m^2) } void INSResetP(float PDiag[NUMX]) { uint8_t i,j; // if PDiag[i] nonzero then clear row and column and set diagonal element for (i=0;i