hotfix: allow arming in Stabilized 4,5,6
[librepilot.git] / flight / libraries / insgps13state.c
blobb65aa2bde636fc48e30627a9944a2f359794a949
1 /**
2 ******************************************************************************
3 * @addtogroup AHRS
4 * @{
5 * @addtogroup INSGPS
6 * @{
7 * @brief INSGPS is a joint attitude and position estimation EKF
9 * @file insgps.c
10 * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
11 * @brief An INS/GPS algorithm implemented with an EKF.
13 * @see The GNU Public License (GPL) Version 3
15 *****************************************************************************/
17 * This program is free software; you can redistribute it and/or modify
18 * it under the terms of the GNU General Public License as published by
19 * the Free Software Foundation; either version 3 of the License, or
20 * (at your option) any later version.
22 * This program is distributed in the hope that it will be useful, but
23 * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
24 * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
25 * for more details.
27 * You should have received a copy of the GNU General Public License along
28 * with this program; if not, write to the Free Software Foundation, Inc.,
29 * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
32 #include "insgps.h"
33 #include <math.h>
34 #include <stdint.h>
35 #include <pios_math.h>
37 // constants/macros/typdefs
38 #define NUMX 13 // number of states, X is the state vector
39 #define NUMW 9 // number of plant noise inputs, w is disturbance noise vector
40 #define NUMV 10 // number of measurements, v is the measurement noise vector
41 #define NUMU 6 // number of deterministic inputs, U is the input vector
43 // Private functions
44 void CovariancePrediction(float F[NUMX][NUMX], float G[NUMX][NUMW],
45 float Q[NUMW], float dT, float P[NUMX][NUMX]);
46 void SerialUpdate(float H[NUMV][NUMX], float R[NUMV], float Z[NUMV],
47 float Y[NUMV], float P[NUMX][NUMX], float X[NUMX],
48 uint16_t SensorsUsed);
49 void RungeKutta(float X[NUMX], float U[NUMU], float dT);
50 void StateEq(float X[NUMX], float U[NUMU], float Xdot[NUMX]);
51 void LinearizeFG(float X[NUMX], float U[NUMU], float F[NUMX][NUMX],
52 float G[NUMX][NUMW]);
53 void MeasurementEq(float X[NUMX], float Be[3], float Y[NUMV]);
54 void LinearizeH(float X[NUMX], float Be[3], float H[NUMV][NUMX]);
56 // Private variables
58 // speed optimizations, describe matrix sparsity
59 // derived from state equations in
60 // LinearizeFG() and LinearizeH():
62 // usage F: usage G: usage H:
63 // 0123456789abc 012345678 0123456789abc
64 // 0...X......... ......... X............
65 // 1....X........ ......... .X...........
66 // 2.....X....... ......... ..X..........
67 // 3......XXXX... ...XXX... ...X.........
68 // 4......XXXX... ...XXX... ....X........
69 // 5......XXXX... ...XXX... .....X.......
70 // 6.......XXXXXX XXX...... ......XXXX...
71 // 7......X.XXXXX XXX...... ......XXXX...
72 // 8......XX.XXXX XXX...... ......XXXX...
73 // 9......XXX.XXX XXX...... ..X..........
74 // a............. ......X..
75 // b............. .......X.
76 // c............. ........X
78 static const int8_t FrowMin[NUMX] = { 3, 4, 5, 6, 6, 6, 7, 6, 6, 6, 13, 13, 13 };
79 static const int8_t FrowMax[NUMX] = { 3, 4, 5, 9, 9, 9, 12, 12, 12, 12, -1, -1, -1 };
81 static const int8_t GrowMin[NUMX] = { 9, 9, 9, 3, 3, 3, 0, 0, 0, 0, 6, 7, 8 };
82 static const int8_t GrowMax[NUMX] = { -1, -1, -1, 5, 5, 5, 2, 2, 2, 2, 6, 7, 8 };
84 static const int8_t HrowMin[NUMV] = { 0, 1, 2, 3, 4, 5, 6, 6, 6, 2 };
85 static const int8_t HrowMax[NUMV] = { 0, 1, 2, 3, 4, 5, 9, 9, 9, 2 };
87 static struct EKFData {
88 // linearized system matrices
89 float F[NUMX][NUMX];
90 float G[NUMX][NUMW];
91 float H[NUMV][NUMX];
92 // local magnetic unit vector in NED frame
93 float Be[3];
94 // local gravity vector
95 float g_e;
96 // covariance matrix and state vector
97 float P[NUMX][NUMX];
98 float X[NUMX];
99 // input noise and measurement noise variances
100 float Q[NUMW];
101 float R[NUMV];
102 } ekf;
104 // Global variables
105 struct NavStruct Nav;
107 // ************* Exposed Functions ****************
108 // *************************************************
110 uint16_t ins_get_num_states()
112 return NUMX;
115 void INSGPSInit() // pretty much just a place holder for now
117 ekf.Be[0] = 1.0f;
118 ekf.Be[1] = 0.0f;
119 ekf.Be[2] = 0.0f; // local magnetic unit vector
121 for (int i = 0; i < NUMX; i++) {
122 for (int j = 0; j < NUMX; j++) {
123 ekf.P[i][j] = 0.0f; // zero all terms
124 ekf.F[i][j] = 0.0f;
127 for (int j = 0; j < NUMW; j++) {
128 ekf.G[i][j] = 0.0f;
131 for (int j = 0; j < NUMV; j++) {
132 ekf.H[j][i] = 0.0f;
135 ekf.X[i] = 0.0f;
137 for (int i = 0; i < NUMW; i++) {
138 ekf.Q[i] = 0.0f;
140 for (int i = 0; i < NUMV; i++) {
141 ekf.R[i] = 0.0f;
145 ekf.P[0][0] = ekf.P[1][1] = ekf.P[2][2] = 25.0f; // initial position variance (m^2)
146 ekf.P[3][3] = ekf.P[4][4] = ekf.P[5][5] = 5.0f; // initial velocity variance (m/s)^2
147 ekf.P[6][6] = ekf.P[7][7] = ekf.P[8][8] = ekf.P[9][9] = 1e-5f; // initial quaternion variance
148 ekf.P[10][10] = ekf.P[11][11] = ekf.P[12][12] = 1e-9f; // initial gyro bias variance (rad/s)^2
150 ekf.X[0] = ekf.X[1] = ekf.X[2] = ekf.X[3] = ekf.X[4] = ekf.X[5] = 0.0f; // initial pos and vel (m)
151 ekf.X[6] = 1.0f;
152 ekf.X[7] = ekf.X[8] = ekf.X[9] = 0.0f; // initial quaternion (level and North) (m/s)
153 ekf.X[10] = ekf.X[11] = ekf.X[12] = 0.0f; // initial gyro bias (rad/s)
155 ekf.Q[0] = ekf.Q[1] = ekf.Q[2] = 50e-4f; // gyro noise variance (rad/s)^2
156 ekf.Q[3] = ekf.Q[4] = ekf.Q[5] = 0.00001f; // accelerometer noise variance (m/s^2)^2
157 ekf.Q[6] = ekf.Q[7] = ekf.Q[8] = 2e-8f; // gyro bias random walk variance (rad/s^2)^2
159 ekf.R[0] = ekf.R[1] = 0.004f; // High freq GPS horizontal position noise variance (m^2)
160 ekf.R[2] = 0.036f; // High freq GPS vertical position noise variance (m^2)
161 ekf.R[3] = ekf.R[4] = 0.004f; // High freq GPS horizontal velocity noise variance (m/s)^2
162 ekf.R[5] = 100.0f; // High freq GPS vertical velocity noise variance (m/s)^2
163 ekf.R[6] = ekf.R[7] = ekf.R[8] = 0.005f; // magnetometer unit vector noise variance
164 ekf.R[9] = .25f; // High freq altimeter noise variance (m^2)
167 void INSResetP(float PDiag[NUMX])
169 uint8_t i, j;
171 // if PDiag[i] nonzero then clear row and column and set diagonal element
172 for (i = 0; i < NUMX; i++) {
173 if (PDiag != 0) {
174 for (j = 0; j < NUMX; j++) {
175 ekf.P[i][j] = ekf.P[j][i] = 0.0f;
177 ekf.P[i][i] = PDiag[i];
182 void INSGetP(float PDiag[NUMX])
184 uint8_t i;
186 // retrieve diagonal elements (aka state variance)
187 for (i = 0; i < NUMX; i++) {
188 if (PDiag != 0) {
189 PDiag[i] = ekf.P[i][i];
194 void INSSetState(float pos[3], float vel[3], float q[4], float gyro_bias[3], __attribute__((unused)) float accel_bias[3])
196 /* Note: accel_bias not used in 13 state INS */
197 ekf.X[0] = pos[0];
198 ekf.X[1] = pos[1];
199 ekf.X[2] = pos[2];
200 ekf.X[3] = vel[0];
201 ekf.X[4] = vel[1];
202 ekf.X[5] = vel[2];
203 ekf.X[6] = q[0];
204 ekf.X[7] = q[1];
205 ekf.X[8] = q[2];
206 ekf.X[9] = q[3];
207 ekf.X[10] = gyro_bias[0];
208 ekf.X[11] = gyro_bias[1];
209 ekf.X[12] = gyro_bias[2];
212 void INSPosVelReset(float pos[3], float vel[3])
214 for (int i = 0; i < 6; i++) {
215 for (int j = i; j < NUMX; j++) {
216 ekf.P[i][j] = 0; // zero the first 6 rows and columns
217 ekf.P[j][i] = 0;
221 ekf.P[0][0] = ekf.P[1][1] = ekf.P[2][2] = 25; // initial position variance (m^2)
222 ekf.P[3][3] = ekf.P[4][4] = ekf.P[5][5] = 5; // initial velocity variance (m/s)^2
224 ekf.X[0] = pos[0];
225 ekf.X[1] = pos[1];
226 ekf.X[2] = pos[2];
227 ekf.X[3] = vel[0];
228 ekf.X[4] = vel[1];
229 ekf.X[5] = vel[2];
232 void INSSetPosVelVar(float PosVar[3], float VelVar[3])
234 ekf.R[0] = PosVar[0];
235 ekf.R[1] = PosVar[1];
236 ekf.R[2] = PosVar[2];
237 ekf.R[3] = VelVar[0];
238 ekf.R[4] = VelVar[1];
239 ekf.R[5] = VelVar[2];
242 void INSSetGyroBias(float gyro_bias[3])
244 ekf.X[10] = gyro_bias[0];
245 ekf.X[11] = gyro_bias[1];
246 ekf.X[12] = gyro_bias[2];
249 void INSSetAccelVar(float accel_var[3])
251 ekf.Q[3] = accel_var[0];
252 ekf.Q[4] = accel_var[1];
253 ekf.Q[5] = accel_var[2];
256 void INSSetGyroVar(float gyro_var[3])
258 ekf.Q[0] = gyro_var[0];
259 ekf.Q[1] = gyro_var[1];
260 ekf.Q[2] = gyro_var[2];
263 void INSSetGyroBiasVar(float gyro_bias_var[3])
265 ekf.Q[6] = gyro_bias_var[0];
266 ekf.Q[7] = gyro_bias_var[1];
267 ekf.Q[8] = gyro_bias_var[2];
270 void INSSetMagVar(float scaled_mag_var[3])
272 ekf.R[6] = scaled_mag_var[0];
273 ekf.R[7] = scaled_mag_var[1];
274 ekf.R[8] = scaled_mag_var[2];
277 void INSSetBaroVar(float baro_var)
279 ekf.R[9] = baro_var;
282 void INSSetMagNorth(float B[3])
284 float mag = sqrtf(B[0] * B[0] + B[1] * B[1] + B[2] * B[2]);
286 ekf.Be[0] = B[0] / mag;
287 ekf.Be[1] = B[1] / mag;
288 ekf.Be[2] = B[2] / mag;
291 void INSSetG(float g_e)
293 ekf.g_e = g_e;
296 void INSStatePrediction(float gyro_data[3], float accel_data[3], float dT)
298 float U[6];
299 float qmag;
301 // rate gyro inputs in units of rad/s
302 U[0] = gyro_data[0];
303 U[1] = gyro_data[1];
304 U[2] = gyro_data[2];
306 // accelerometer inputs in units of m/s
307 U[3] = accel_data[0];
308 U[4] = accel_data[1];
309 U[5] = accel_data[2];
311 // EKF prediction step
312 LinearizeFG(ekf.X, U, ekf.F, ekf.G);
313 RungeKutta(ekf.X, U, dT);
314 qmag = sqrtf(ekf.X[6] * ekf.X[6] + ekf.X[7] * ekf.X[7] + ekf.X[8] * ekf.X[8] + ekf.X[9] * ekf.X[9]);
315 ekf.X[6] /= qmag;
316 ekf.X[7] /= qmag;
317 ekf.X[8] /= qmag;
318 ekf.X[9] /= qmag;
319 // CovariancePrediction(ekf.F,ekf.G,ekf.Q,dT,ekf.P);
321 // Update Nav solution structure
322 Nav.Pos[0] = ekf.X[0];
323 Nav.Pos[1] = ekf.X[1];
324 Nav.Pos[2] = ekf.X[2];
325 Nav.Vel[0] = ekf.X[3];
326 Nav.Vel[1] = ekf.X[4];
327 Nav.Vel[2] = ekf.X[5];
328 Nav.q[0] = ekf.X[6];
329 Nav.q[1] = ekf.X[7];
330 Nav.q[2] = ekf.X[8];
331 Nav.q[3] = ekf.X[9];
332 Nav.gyro_bias[0] = ekf.X[10];
333 Nav.gyro_bias[1] = ekf.X[11];
334 Nav.gyro_bias[2] = ekf.X[12];
337 void INSCovariancePrediction(float dT)
339 CovariancePrediction(ekf.F, ekf.G, ekf.Q, dT, ekf.P);
342 float zeros[3] = { 0, 0, 0 };
344 void MagCorrection(float mag_data[3])
346 INSCorrection(mag_data, zeros, zeros, zeros[0], MAG_SENSORS);
349 void MagVelBaroCorrection(float mag_data[3], float Vel[3], float BaroAlt)
351 INSCorrection(mag_data, zeros, Vel, BaroAlt,
352 MAG_SENSORS | HORIZ_SENSORS | VERT_SENSORS |
353 BARO_SENSOR);
356 void GpsBaroCorrection(float Pos[3], float Vel[3], float BaroAlt)
358 INSCorrection(zeros, Pos, Vel, BaroAlt,
359 HORIZ_SENSORS | VERT_SENSORS | BARO_SENSOR);
362 void FullCorrection(float mag_data[3], float Pos[3], float Vel[3],
363 float BaroAlt)
365 INSCorrection(mag_data, Pos, Vel, BaroAlt, FULL_SENSORS);
368 void GpsMagCorrection(float mag_data[3], float Pos[3], float Vel[3])
370 INSCorrection(mag_data, Pos, Vel, zeros[0],
371 POS_SENSORS | HORIZ_SENSORS | MAG_SENSORS);
374 void VelBaroCorrection(float Vel[3], float BaroAlt)
376 INSCorrection(zeros, zeros, Vel, BaroAlt,
377 HORIZ_SENSORS | VERT_SENSORS | BARO_SENSOR);
380 void INSCorrection(float mag_data[3], float Pos[3], float Vel[3],
381 float BaroAlt, uint16_t SensorsUsed)
383 float Z[10], Y[10];
384 float Bmag, qmag;
386 // GPS Position in meters and in local NED frame
387 Z[0] = Pos[0];
388 Z[1] = Pos[1];
389 Z[2] = Pos[2];
391 // GPS Velocity in meters and in local NED frame
392 Z[3] = Vel[0];
393 Z[4] = Vel[1];
394 Z[5] = Vel[2];
396 // magnetometer data in any units (use unit vector) and in body frame
397 Bmag =
398 sqrtf(mag_data[0] * mag_data[0] + mag_data[1] * mag_data[1] +
399 mag_data[2] * mag_data[2]);
400 Z[6] = mag_data[0] / Bmag;
401 Z[7] = mag_data[1] / Bmag;
402 Z[8] = mag_data[2] / Bmag;
404 // barometric altimeter in meters and in local NED frame
405 Z[9] = BaroAlt;
407 // EKF correction step
408 LinearizeH(ekf.X, ekf.Be, ekf.H);
409 MeasurementEq(ekf.X, ekf.Be, Y);
410 SerialUpdate(ekf.H, ekf.R, Z, Y, ekf.P, ekf.X, SensorsUsed);
411 qmag = sqrtf(ekf.X[6] * ekf.X[6] + ekf.X[7] * ekf.X[7] + ekf.X[8] * ekf.X[8] + ekf.X[9] * ekf.X[9]);
412 ekf.X[6] /= qmag;
413 ekf.X[7] /= qmag;
414 ekf.X[8] /= qmag;
415 ekf.X[9] /= qmag;
417 // Update Nav solution structure
418 Nav.Pos[0] = ekf.X[0];
419 Nav.Pos[1] = ekf.X[1];
420 Nav.Pos[2] = ekf.X[2];
421 Nav.Vel[0] = ekf.X[3];
422 Nav.Vel[1] = ekf.X[4];
423 Nav.Vel[2] = ekf.X[5];
424 Nav.q[0] = ekf.X[6];
425 Nav.q[1] = ekf.X[7];
426 Nav.q[2] = ekf.X[8];
427 Nav.q[3] = ekf.X[9];
428 Nav.gyro_bias[0] = ekf.X[10];
429 Nav.gyro_bias[1] = ekf.X[11];
430 Nav.gyro_bias[2] = ekf.X[12];
433 // ************* CovariancePrediction *************
434 // Does the prediction step of the Kalman filter for the covariance matrix
435 // Output, Pnew, overwrites P, the input covariance
436 // Pnew = (I+F*T)*P*(I+F*T)' + T^2*G*Q*G'
437 // Q is the discrete time covariance of process noise
438 // Q is vector of the diagonal for a square matrix with
439 // dimensions equal to the number of disturbance noise variables
440 // The General Method is very inefficient,not taking advantage of the sparse F and G
441 // The first Method is very specific to this implementation
442 // ************************************************
444 __attribute__((optimize("O3")))
445 void CovariancePrediction(float F[NUMX][NUMX], float G[NUMX][NUMW],
446 float Q[NUMW], float dT, float P[NUMX][NUMX])
448 // Pnew = (I+F*T)*P*(I+F*T)' + (T^2)*G*Q*G' = (T^2)[(P/T + F*P)*(I/T + F') + G*Q*G')]
450 float dT1 = 1.0f / dT; // multiplication is faster than division on fpu.
451 float dTsq = dT * dT;
453 float Dummy[NUMX][NUMX];
454 int8_t i;
456 for (i = 0; i < NUMX; i++) { // Calculate Dummy = (P/T +F*P)
457 float *Firow = F[i];
458 float *Pirow = P[i];
459 float *Dirow = Dummy[i];
460 int8_t Fistart = FrowMin[i];
461 int8_t Fiend = FrowMax[i];
462 int8_t j;
463 for (j = 0; j < NUMX; j++) {
464 Dirow[j] = Pirow[j] * dT1; // Dummy = P / T ...
465 int8_t k;
466 for (k = Fistart; k <= Fiend; k++) {
467 Dirow[j] += Firow[k] * P[k][j]; // [] + F * P
471 for (i = 0; i < NUMX; i++) { // Calculate Pnew = (T^2) [Dummy/T + Dummy*F' + G*Qw*G']
472 float *Dirow = Dummy[i];
473 float *Girow = G[i];
474 float *Pirow = P[i];
475 int8_t Gistart = GrowMin[i];
476 int8_t Giend = GrowMax[i];
477 int8_t j;
478 for (j = i; j < NUMX; j++) { // Use symmetry, ie only find upper triangular
479 float Ptmp = Dirow[j] * dT1; // Pnew = Dummy / T ...
482 float *Fjrow = F[j];
483 int8_t Fjstart = FrowMin[j];
484 int8_t Fjend = FrowMax[j];
485 int8_t k;
486 for (k = Fjstart; k <= Fjend; k++) {
487 Ptmp += Dirow[k] * Fjrow[k]; // [] + Dummy*F' ...
492 float *Gjrow = G[j];
493 int8_t Gjstart = MAX(Gistart, GrowMin[j]);
494 int8_t Gjend = MIN(Giend, GrowMax[j]);
495 int8_t k;
496 for (k = Gjstart; k <= Gjend; k++) {
497 Ptmp += Q[k] * Girow[k] * Gjrow[k]; // [] + G*Q*G' ...
501 P[j][i] = Pirow[j] = Ptmp * dTsq; // [] * (T^2)
506 // ************* SerialUpdate *******************
507 // Does the update step of the Kalman filter for the covariance and estimate
508 // Outputs are Xnew & Pnew, and are written over P and X
509 // Z is actual measurement, Y is predicted measurement
510 // Xnew = X + K*(Z-Y), Pnew=(I-K*H)*P,
511 // where K=P*H'*inv[H*P*H'+R]
512 // NOTE the algorithm assumes R (measurement covariance matrix) is diagonal
513 // i.e. the measurment noises are uncorrelated.
514 // It therefore uses a serial update that requires no matrix inversion by
515 // processing the measurements one at a time.
516 // Algorithm - see Grewal and Andrews, "Kalman Filtering,2nd Ed" p.121 & p.253
517 // - or see Simon, "Optimal State Estimation," 1st Ed, p.150
518 // The SensorsUsed variable is a bitwise mask indicating which sensors
519 // should be used in the update.
520 // ************************************************
522 void SerialUpdate(float H[NUMV][NUMX], float R[NUMV], float Z[NUMV],
523 float Y[NUMV], float P[NUMX][NUMX], float X[NUMX],
524 uint16_t SensorsUsed)
526 float HP[NUMX], HPHR, Error;
527 uint8_t i, j, k, m;
528 float Km[NUMX];
530 for (m = 0; m < NUMV; m++) {
531 if (SensorsUsed & (0x01 << m)) { // use this sensor for update
532 for (j = 0; j < NUMX; j++) { // Find Hp = H*P
533 HP[j] = 0;
534 for (k = HrowMin[m]; k <= HrowMax[m]; k++) {
535 HP[j] += H[m][k] * P[k][j];
538 HPHR = R[m]; // Find HPHR = H*P*H' + R
539 for (k = HrowMin[m]; k <= HrowMax[m]; k++) {
540 HPHR += HP[k] * H[m][k];
543 for (k = 0; k < NUMX; k++) {
544 Km[k] = HP[k] / HPHR; // find K = HP/HPHR
546 for (i = 0; i < NUMX; i++) { // Find P(m)= P(m-1) + K*HP
547 for (j = i; j < NUMX; j++) {
548 P[i][j] = P[j][i] =
549 P[i][j] - Km[i] * HP[j];
553 Error = Z[m] - Y[m];
554 for (i = 0; i < NUMX; i++) { // Find X(m)= X(m-1) + K*Error
555 X[i] = X[i] + Km[i] * Error;
561 // ************* RungeKutta **********************
562 // Does a 4th order Runge Kutta numerical integration step
563 // Output, Xnew, is written over X
564 // NOTE the algorithm assumes time invariant state equations and
565 // constant inputs over integration step
566 // ************************************************
568 void RungeKutta(float X[NUMX], float U[NUMU], float dT)
570 float dT2 =
571 dT / 2.0f, K1[NUMX], K2[NUMX], K3[NUMX], K4[NUMX], Xlast[NUMX];
572 uint8_t i;
574 for (i = 0; i < NUMX; i++) {
575 Xlast[i] = X[i]; // make a working copy
577 StateEq(X, U, K1); // k1 = f(x,u)
578 for (i = 0; i < NUMX; i++) {
579 X[i] = Xlast[i] + dT2 * K1[i];
581 StateEq(X, U, K2); // k2 = f(x+0.5*dT*k1,u)
582 for (i = 0; i < NUMX; i++) {
583 X[i] = Xlast[i] + dT2 * K2[i];
585 StateEq(X, U, K3); // k3 = f(x+0.5*dT*k2,u)
586 for (i = 0; i < NUMX; i++) {
587 X[i] = Xlast[i] + dT * K3[i];
589 StateEq(X, U, K4); // k4 = f(x+dT*k3,u)
591 // Xnew = X + dT*(k1+2*k2+2*k3+k4)/6
592 for (i = 0; i < NUMX; i++) {
593 X[i] =
594 Xlast[i] + dT * (K1[i] + 2.0f * K2[i] + 2.0f * K3[i] +
595 K4[i]) / 6.0f;
599 // ************* Model Specific Stuff ***************************
600 // *** StateEq, MeasurementEq, LinerizeFG, and LinearizeH ********
602 // State Variables = [Pos Vel Quaternion GyroBias NO-AccelBias]
603 // Deterministic Inputs = [AngularVel Accel]
604 // Disturbance Noise = [GyroNoise AccelNoise GyroRandomWalkNoise NO-AccelRandomWalkNoise]
606 // Measurement Variables = [Pos Vel BodyFrameMagField Altimeter]
607 // Inputs to Measurement = [EarthFrameMagField]
609 // Notes: Pos and Vel in earth frame
610 // AngularVel and Accel in body frame
611 // MagFields are unit vectors
612 // Xdot is output of StateEq()
613 // F and G are outputs of LinearizeFG(), all elements not set should be zero
614 // y is output of OutputEq()
615 // H is output of LinearizeH(), all elements not set should be zero
616 // ************************************************
618 void StateEq(float X[NUMX], float U[NUMU], float Xdot[NUMX])
620 float ax, ay, az, wx, wy, wz, q0, q1, q2, q3;
622 // ax=U[3]-X[13]; ay=U[4]-X[14]; az=U[5]-X[15]; // subtract the biases on accels
623 ax = U[3];
624 ay = U[4];
625 az = U[5]; // NO BIAS STATES ON ACCELS
626 wx = U[0] - X[10];
627 wy = U[1] - X[11];
628 wz = U[2] - X[12]; // subtract the biases on gyros
629 q0 = X[6];
630 q1 = X[7];
631 q2 = X[8];
632 q3 = X[9];
634 // Pdot = V
635 Xdot[0] = X[3];
636 Xdot[1] = X[4];
637 Xdot[2] = X[5];
639 // Vdot = Reb*a
640 Xdot[3] =
641 (q0 * q0 + q1 * q1 - q2 * q2 - q3 * q3) * ax + 2.0f * (q1 * q2 -
642 q0 * q3) *
643 ay + 2.0f * (q1 * q3 + q0 * q2) * az;
644 Xdot[4] =
645 2.0f * (q1 * q2 + q0 * q3) * ax + (q0 * q0 - q1 * q1 + q2 * q2 -
646 q3 * q3) * ay + 2 * (q2 * q3 -
647 q0 * q1) *
649 Xdot[5] =
650 2.0f * (q1 * q3 - q0 * q2) * ax + 2 * (q2 * q3 + q0 * q1) * ay +
651 (q0 * q0 - q1 * q1 - q2 * q2 + q3 * q3) * az + ekf.g_e;
653 // qdot = Q*w
654 Xdot[6] = (-q1 * wx - q2 * wy - q3 * wz) / 2.0f;
655 Xdot[7] = (q0 * wx - q3 * wy + q2 * wz) / 2.0f;
656 Xdot[8] = (q3 * wx + q0 * wy - q1 * wz) / 2.0f;
657 Xdot[9] = (-q2 * wx + q1 * wy + q0 * wz) / 2.0f;
659 // best guess is that bias stays constant
660 Xdot[10] = Xdot[11] = Xdot[12] = 0;
663 void LinearizeFG(float X[NUMX], float U[NUMU], float F[NUMX][NUMX],
664 float G[NUMX][NUMW])
666 float ax, ay, az, wx, wy, wz, q0, q1, q2, q3;
668 // ax=U[3]-X[13]; ay=U[4]-X[14]; az=U[5]-X[15]; // subtract the biases on accels
669 ax = U[3];
670 ay = U[4];
671 az = U[5]; // NO BIAS STATES ON ACCELS
672 wx = U[0] - X[10];
673 wy = U[1] - X[11];
674 wz = U[2] - X[12]; // subtract the biases on gyros
675 q0 = X[6];
676 q1 = X[7];
677 q2 = X[8];
678 q3 = X[9];
680 // Pdot = V
681 F[0][3] = F[1][4] = F[2][5] = 1.0f;
683 // dVdot/dq
684 F[3][6] = 2.0f * (q0 * ax - q3 * ay + q2 * az);
685 F[3][7] = 2.0f * (q1 * ax + q2 * ay + q3 * az);
686 F[3][8] = 2.0f * (-q2 * ax + q1 * ay + q0 * az);
687 F[3][9] = 2.0f * (-q3 * ax - q0 * ay + q1 * az);
688 F[4][6] = 2.0f * (q3 * ax + q0 * ay - q1 * az);
689 F[4][7] = 2.0f * (q2 * ax - q1 * ay - q0 * az);
690 F[4][8] = 2.0f * (q1 * ax + q2 * ay + q3 * az);
691 F[4][9] = 2.0f * (q0 * ax - q3 * ay + q2 * az);
692 F[5][6] = 2.0f * (-q2 * ax + q1 * ay + q0 * az);
693 F[5][7] = 2.0f * (q3 * ax + q0 * ay - q1 * az);
694 F[5][8] = 2.0f * (-q0 * ax + q3 * ay - q2 * az);
695 F[5][9] = 2.0f * (q1 * ax + q2 * ay + q3 * az);
697 // dVdot/dabias & dVdot/dna - NO BIAS STATES ON ACCELS - S0 REPEAT FOR G BELOW
698 // F[3][13]=G[3][3]=-q0*q0-q1*q1+q2*q2+q3*q3; F[3][14]=G[3][4]=2*(-q1*q2+q0*q3); F[3][15]=G[3][5]=-2*(q1*q3+q0*q2);
699 // F[4][13]=G[4][3]=-2*(q1*q2+q0*q3); F[4][14]=G[4][4]=-q0*q0+q1*q1-q2*q2+q3*q3; F[4][15]=G[4][5]=2*(-q2*q3+q0*q1);
700 // F[5][13]=G[5][3]=2*(-q1*q3+q0*q2); F[5][14]=G[5][4]=-2*(q2*q3+q0*q1); F[5][15]=G[5][5]=-q0*q0+q1*q1+q2*q2-q3*q3;
702 // dqdot/dq
703 F[6][6] = 0;
704 F[6][7] = -wx / 2.0f;
705 F[6][8] = -wy / 2.0f;
706 F[6][9] = -wz / 2.0f;
707 F[7][6] = wx / 2.0f;
708 F[7][7] = 0;
709 F[7][8] = wz / 2.0f;
710 F[7][9] = -wy / 2.0f;
711 F[8][6] = wy / 2.0f;
712 F[8][7] = -wz / 2.0f;
713 F[8][8] = 0;
714 F[8][9] = wx / 2.0f;
715 F[9][6] = wz / 2.0f;
716 F[9][7] = wy / 2.0f;
717 F[9][8] = -wx / 2.0f;
718 F[9][9] = 0;
720 // dqdot/dwbias
721 F[6][10] = q1 / 2.0f;
722 F[6][11] = q2 / 2.0f;
723 F[6][12] = q3 / 2.0f;
724 F[7][10] = -q0 / 2.0f;
725 F[7][11] = q3 / 2.0f;
726 F[7][12] = -q2 / 2.0f;
727 F[8][10] = -q3 / 2.0f;
728 F[8][11] = -q0 / 2.0f;
729 F[8][12] = q1 / 2.0f;
730 F[9][10] = q2 / 2.0f;
731 F[9][11] = -q1 / 2.0f;
732 F[9][12] = -q0 / 2.0f;
734 // dVdot/dna - NO BIAS STATES ON ACCELS - S0 REPEAT FOR G HERE
735 G[3][3] = -q0 * q0 - q1 * q1 + q2 * q2 + q3 * q3;
736 G[3][4] = 2.0f * (-q1 * q2 + q0 * q3);
737 G[3][5] = -2.0f * (q1 * q3 + q0 * q2);
738 G[4][3] = -2.0f * (q1 * q2 + q0 * q3);
739 G[4][4] = -q0 * q0 + q1 * q1 - q2 * q2 + q3 * q3;
740 G[4][5] = 2.0f * (-q2 * q3 + q0 * q1);
741 G[5][3] = 2.0f * (-q1 * q3 + q0 * q2);
742 G[5][4] = -2.0f * (q2 * q3 + q0 * q1);
743 G[5][5] = -q0 * q0 + q1 * q1 + q2 * q2 - q3 * q3;
745 // dqdot/dnw
746 G[6][0] = q1 / 2.0f;
747 G[6][1] = q2 / 2.0f;
748 G[6][2] = q3 / 2.0f;
749 G[7][0] = -q0 / 2.0f;
750 G[7][1] = q3 / 2.0f;
751 G[7][2] = -q2 / 2.0f;
752 G[8][0] = -q3 / 2.0f;
753 G[8][1] = -q0 / 2.0f;
754 G[8][2] = q1 / 2.0f;
755 G[9][0] = q2 / 2.0f;
756 G[9][1] = -q1 / 2.0f;
757 G[9][2] = -q0 / 2.0f;
759 // dwbias = random walk noise
760 G[10][6] = G[11][7] = G[12][8] = 1.0f;
761 // dabias = random walk noise
762 // G[13][9]=G[14][10]=G[15][11]=1; // NO BIAS STATES ON ACCELS
765 void MeasurementEq(float X[NUMX], float Be[3], float Y[NUMV])
767 float q0, q1, q2, q3;
769 q0 = X[6];
770 q1 = X[7];
771 q2 = X[8];
772 q3 = X[9];
774 // first six outputs are P and V
775 Y[0] = X[0];
776 Y[1] = X[1];
777 Y[2] = X[2];
778 Y[3] = X[3];
779 Y[4] = X[4];
780 Y[5] = X[5];
782 // Bb=Rbe*Be
783 Y[6] =
784 (q0 * q0 + q1 * q1 - q2 * q2 - q3 * q3) * Be[0] +
785 2.0f * (q1 * q2 + q0 * q3) * Be[1] + 2.0f * (q1 * q3 -
786 q0 * q2) * Be[2];
787 Y[7] =
788 2.0f * (q1 * q2 - q0 * q3) * Be[0] + (q0 * q0 - q1 * q1 +
789 q2 * q2 - q3 * q3) * Be[1] +
790 2.0f * (q2 * q3 + q0 * q1) * Be[2];
791 Y[8] =
792 2.0f * (q1 * q3 + q0 * q2) * Be[0] + 2.0f * (q2 * q3 -
793 q0 * q1) * Be[1] +
794 (q0 * q0 - q1 * q1 - q2 * q2 + q3 * q3) * Be[2];
796 // Alt = -Pz
797 Y[9] = -1.0f * X[2];
800 void LinearizeH(float X[NUMX], float Be[3], float H[NUMV][NUMX])
802 float q0, q1, q2, q3;
804 q0 = X[6];
805 q1 = X[7];
806 q2 = X[8];
807 q3 = X[9];
809 // dP/dP=I;
810 H[0][0] = H[1][1] = H[2][2] = 1.0f;
811 // dV/dV=I;
812 H[3][3] = H[4][4] = H[5][5] = 1.0f;
814 // dBb/dq
815 H[6][6] = 2.0f * (q0 * Be[0] + q3 * Be[1] - q2 * Be[2]);
816 H[6][7] = 2.0f * (q1 * Be[0] + q2 * Be[1] + q3 * Be[2]);
817 H[6][8] = 2.0f * (-q2 * Be[0] + q1 * Be[1] - q0 * Be[2]);
818 H[6][9] = 2.0f * (-q3 * Be[0] + q0 * Be[1] + q1 * Be[2]);
819 H[7][6] = 2.0f * (-q3 * Be[0] + q0 * Be[1] + q1 * Be[2]);
820 H[7][7] = 2.0f * (q2 * Be[0] - q1 * Be[1] + q0 * Be[2]);
821 H[7][8] = 2.0f * (q1 * Be[0] + q2 * Be[1] + q3 * Be[2]);
822 H[7][9] = 2.0f * (-q0 * Be[0] - q3 * Be[1] + q2 * Be[2]);
823 H[8][6] = 2.0f * (q2 * Be[0] - q1 * Be[1] + q0 * Be[2]);
824 H[8][7] = 2.0f * (q3 * Be[0] - q0 * Be[1] - q1 * Be[2]);
825 H[8][8] = 2.0f * (q0 * Be[0] + q3 * Be[1] - q2 * Be[2]);
826 H[8][9] = 2.0f * (q1 * Be[0] + q2 * Be[1] + q3 * Be[2]);
828 // dAlt/dPz = -1
829 H[9][2] = -1.0f;
833 * @}
834 * @}