2 ******************************************************************************
7 * @brief INSGPS is a joint attitude and position estimation EKF
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
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
35 #include <pios_math.h>
38 // constants/macros/typdefs
39 #define NUMX 13 // number of states, X is the state vector
40 #define NUMW 9 // number of plant noise inputs, w is disturbance noise vector
41 #define NUMV 10 // number of measurements, v is the measurement noise vector
42 #define NUMU 6 // number of deterministic inputs, U is the input vector
43 #pragma GCC optimize "O3"
45 void CovariancePrediction(float F
[NUMX
][NUMX
], float G
[NUMX
][NUMW
],
46 float Q
[NUMW
], float dT
, float P
[NUMX
][NUMX
]);
47 static void SerialUpdate(float H
[NUMV
][NUMX
], float R
[NUMV
], float Z
[NUMV
],
48 float Y
[NUMV
], float P
[NUMX
][NUMX
], float X
[NUMX
],
49 uint16_t SensorsUsed
);
50 static void RungeKutta(float X
[NUMX
], float U
[NUMU
], float dT
);
51 static void StateEq(float X
[NUMX
], float U
[NUMU
], float Xdot
[NUMX
]);
52 static void LinearizeFG(float X
[NUMX
], float U
[NUMU
], float F
[NUMX
][NUMX
],
54 static void MeasurementEq(float X
[NUMX
], float Be
[3], float Y
[NUMV
]);
55 static void LinearizeH(float X
[NUMX
], float Be
[3], float H
[NUMV
][NUMX
]);
59 // speed optimizations, describe matrix sparsity
60 // derived from state equations in
61 // LinearizeFG() and LinearizeH():
63 // usage F: usage G: usage H:
64 // -0123456789abc 012345678 0123456789abc
65 // 0...X......... ......... X............
66 // 1....X........ ......... .X...........
67 // 2.....X....... ......... ..X..........
68 // 3......XXXX... ...XXX... ...X.........
69 // 4......XXXX... ...XXX... ....X........
70 // 5......XXXX... ...XXX... .....X.......
71 // 6.....ooXXXXXX XXX...... ......XXXX...
72 // 7.....oXoXXXXX XXX...... ......XXXX...
73 // 8.....oXXoXXXX XXX...... ......XXXX...
74 // 9.....oXXXoXXX XXX...... ..X..........
75 // a............. ......Xoo
76 // b............. ......oXo
77 // c............. ......ooX
79 static int8_t FrowMin
[NUMX
] = { 3, 4, 5, 6, 6, 6, 5, 5, 5, 5, 13, 13, 13 };
80 static int8_t FrowMax
[NUMX
] = { 3, 4, 5, 9, 9, 9, 12, 12, 12, 12, -1, -1, -1 };
82 static int8_t GrowMin
[NUMX
] = { 9, 9, 9, 3, 3, 3, 0, 0, 0, 0, 6, 7, 8 };
83 static int8_t GrowMax
[NUMX
] = { -1, -1, -1, 5, 5, 5, 2, 2, 2, 2, 6, 7, 8 };
85 static int8_t HrowMin
[NUMV
] = { 0, 1, 2, 3, 4, 5, 6, 6, 6, 2 };
86 static int8_t HrowMax
[NUMV
] = { 0, 1, 2, 3, 4, 5, 9, 9, 9, 2 };
88 static struct EKFData
{
89 // linearized system matrices
93 // local magnetic unit vector in NED frame
96 // covariance matrix and state vector
99 // input noise and measurement noise variances
105 struct NavStruct Nav
;
107 // ************* Exposed Functions ****************
108 // *************************************************
110 uint16_t ins_get_num_states()
115 void INSGPSInit() // pretty much just a place holder for now
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
127 for (int j
= 0; j
< NUMW
; j
++) {
131 for (int j
= 0; j
< NUMV
; j
++) {
137 for (int i
= 0; i
< NUMW
; i
++) {
140 for (int i
= 0; i
< NUMV
; i
++) {
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)
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 // ! Set the current flight state
168 void INSSetArmed(bool armed
)
172 // Speed up convergence of accel and gyro bias when not armed
182 void INSResetP(const float PDiag
[NUMX
])
186 // if PDiag[i] nonzero then clear row and column and set diagonal element
187 for (i
= 0; i
< NUMX
; i
++) {
189 for (j
= 0; j
< NUMX
; j
++) {
190 ekf
.P
[i
][j
] = ekf
.P
[j
][i
] = 0.0f
;
192 ekf
.P
[i
][i
] = PDiag
[i
];
197 void INSGetVariance(float PDiag
[NUMX
])
201 // retrieve diagonal elements (aka state variance)
203 for (i
= 0; i
< NUMX
; i
++) {
204 PDiag
[i
] = ekf
.P
[i
][i
];
208 void INSSetState(const float pos
[3], const float vel
[3], const float q
[4], const float gyro_bias
[3], __attribute__((unused
)) const float accel_bias
[3])
210 /* Note: accel_bias not used in 13 state INS */
221 ekf
.X
[10] = gyro_bias
[0];
222 ekf
.X
[11] = gyro_bias
[1];
223 ekf
.X
[12] = gyro_bias
[2];
226 void INSPosVelReset(const float pos
[3], const float vel
[3])
228 for (int i
= 0; i
< 6; i
++) {
229 for (int j
= i
; j
< NUMX
; j
++) {
230 ekf
.P
[i
][j
] = 0; // zero the first 6 rows and columns
235 ekf
.P
[0][0] = ekf
.P
[1][1] = ekf
.P
[2][2] = 25; // initial position variance (m^2)
236 ekf
.P
[3][3] = ekf
.P
[4][4] = ekf
.P
[5][5] = 5; // initial velocity variance (m/s)^2
246 void INSSetPosVelVar(const float PosVar
[3], const float VelVar
[3])
248 ekf
.R
[0] = PosVar
[0];
249 ekf
.R
[1] = PosVar
[1];
250 ekf
.R
[2] = PosVar
[2];
251 ekf
.R
[3] = VelVar
[0];
252 ekf
.R
[4] = VelVar
[1];
253 ekf
.R
[5] = VelVar
[2];
256 void INSSetGyroBias(const float gyro_bias
[3])
258 ekf
.X
[10] = gyro_bias
[0];
259 ekf
.X
[11] = gyro_bias
[1];
260 ekf
.X
[12] = gyro_bias
[2];
263 void INSSetAccelVar(const float accel_var
[3])
265 ekf
.Q
[3] = accel_var
[0];
266 ekf
.Q
[4] = accel_var
[1];
267 ekf
.Q
[5] = accel_var
[2];
270 void INSSetGyroVar(const float gyro_var
[3])
272 ekf
.Q
[0] = gyro_var
[0];
273 ekf
.Q
[1] = gyro_var
[1];
274 ekf
.Q
[2] = gyro_var
[2];
277 void INSSetGyroBiasVar(const float gyro_bias_var
[3])
279 ekf
.Q
[6] = gyro_bias_var
[0];
280 ekf
.Q
[7] = gyro_bias_var
[1];
281 ekf
.Q
[8] = gyro_bias_var
[2];
284 // must be called AFTER SetMagNorth
285 void INSSetMagVar(const float mag_var
[3])
287 ekf
.R
[6] = mag_var
[0] * ekf
.BeScaleFactor
;
288 ekf
.R
[7] = mag_var
[1] * ekf
.BeScaleFactor
;
289 ekf
.R
[8] = mag_var
[2] * ekf
.BeScaleFactor
;
292 void INSSetBaroVar(float baro_var
)
297 void INSSetMagNorth(const float B
[3])
299 ekf
.BeScaleFactor
= invsqrtf(B
[0] * B
[0] + B
[1] * B
[1] + B
[2] * B
[2]);
301 ekf
.Be
[0] = B
[0] * ekf
.BeScaleFactor
;
302 ekf
.Be
[1] = B
[1] * ekf
.BeScaleFactor
;
303 ekf
.Be
[2] = B
[2] * ekf
.BeScaleFactor
;
306 void INSStatePrediction(const float gyro_data
[3], const float accel_data
[3], float dT
)
311 // rate gyro inputs in units of rad/s
316 // accelerometer inputs in units of m/s
317 U
[3] = accel_data
[0];
318 U
[4] = accel_data
[1];
319 U
[5] = accel_data
[2];
321 // EKF prediction step
322 LinearizeFG(ekf
.X
, U
, ekf
.F
, ekf
.G
);
323 RungeKutta(ekf
.X
, U
, dT
);
324 invqmag
= invsqrtf(ekf
.X
[6] * ekf
.X
[6] + ekf
.X
[7] * ekf
.X
[7] + ekf
.X
[8] * ekf
.X
[8] + ekf
.X
[9] * ekf
.X
[9]);
329 // CovariancePrediction(ekf.F,ekf.G,ekf.Q,dT,ekf.P);
331 // Update Nav solution structure
332 Nav
.Pos
[0] = ekf
.X
[0];
333 Nav
.Pos
[1] = ekf
.X
[1];
334 Nav
.Pos
[2] = ekf
.X
[2];
335 Nav
.Vel
[0] = ekf
.X
[3];
336 Nav
.Vel
[1] = ekf
.X
[4];
337 Nav
.Vel
[2] = ekf
.X
[5];
342 Nav
.gyro_bias
[0] = ekf
.X
[10];
343 Nav
.gyro_bias
[1] = ekf
.X
[11];
344 Nav
.gyro_bias
[2] = ekf
.X
[12];
347 void INSCovariancePrediction(float dT
)
349 CovariancePrediction(ekf
.F
, ekf
.G
, ekf
.Q
, dT
, ekf
.P
);
352 float zeros
[3] = { 0, 0, 0 };
354 void MagCorrection(float mag_data
[3])
356 INSCorrection(mag_data
, zeros
, zeros
, zeros
[0], MAG_SENSORS
);
359 void MagVelBaroCorrection(float mag_data
[3], float Vel
[3], float BaroAlt
)
361 INSCorrection(mag_data
, zeros
, Vel
, BaroAlt
,
362 MAG_SENSORS
| HORIZ_SENSORS
| VERT_SENSORS
|
366 void GpsBaroCorrection(float Pos
[3], float Vel
[3], float BaroAlt
)
368 INSCorrection(zeros
, Pos
, Vel
, BaroAlt
,
369 HORIZ_SENSORS
| VERT_SENSORS
| BARO_SENSOR
);
372 void FullCorrection(float mag_data
[3], float Pos
[3], float Vel
[3],
375 INSCorrection(mag_data
, Pos
, Vel
, BaroAlt
, FULL_SENSORS
);
378 void GpsMagCorrection(float mag_data
[3], float Pos
[3], float Vel
[3])
380 INSCorrection(mag_data
, Pos
, Vel
, zeros
[0],
381 POS_SENSORS
| HORIZ_SENSORS
| MAG_SENSORS
);
384 void VelBaroCorrection(float Vel
[3], float BaroAlt
)
386 INSCorrection(zeros
, zeros
, Vel
, BaroAlt
,
387 HORIZ_SENSORS
| VERT_SENSORS
| BARO_SENSOR
);
390 void INSCorrection(const float mag_data
[3], const float Pos
[3], const float Vel
[3],
391 const float BaroAlt
, uint16_t SensorsUsed
)
396 // GPS Position in meters and in local NED frame
401 // GPS Velocity in meters and in local NED frame
405 // magnetometer data in any units (use unit vector) and in body frame
408 if (SensorsUsed
& MAG_SENSORS
) {
409 // magnetometer data in any units (use unit vector) and in body frame
410 float invBmag
= invsqrtf(mag_data
[0] * mag_data
[0] + mag_data
[1] * mag_data
[1] + mag_data
[2] * mag_data
[2]);
411 Z
[6] = mag_data
[0] * invBmag
;
412 Z
[7] = mag_data
[1] * invBmag
;
413 Z
[8] = mag_data
[2] * invBmag
;
416 // barometric altimeter in meters and in local NED frame
419 // EKF correction step
420 LinearizeH(ekf
.X
, ekf
.Be
, ekf
.H
);
421 MeasurementEq(ekf
.X
, ekf
.Be
, Y
);
422 SerialUpdate(ekf
.H
, ekf
.R
, Z
, Y
, ekf
.P
, ekf
.X
, SensorsUsed
);
424 float invqmag
= invsqrtf(ekf
.X
[6] * ekf
.X
[6] + ekf
.X
[7] * ekf
.X
[7] + ekf
.X
[8] * ekf
.X
[8] + ekf
.X
[9] * ekf
.X
[9]);
429 // Update Nav solution structure
430 Nav
.Pos
[0] = ekf
.X
[0];
431 Nav
.Pos
[1] = ekf
.X
[1];
432 Nav
.Pos
[2] = ekf
.X
[2];
433 Nav
.Vel
[0] = ekf
.X
[3];
434 Nav
.Vel
[1] = ekf
.X
[4];
435 Nav
.Vel
[2] = ekf
.X
[5];
440 Nav
.gyro_bias
[0] = ekf
.X
[10];
441 Nav
.gyro_bias
[1] = ekf
.X
[11];
442 Nav
.gyro_bias
[2] = ekf
.X
[12];
445 // ************* CovariancePrediction *************
446 // Does the prediction step of the Kalman filter for the covariance matrix
447 // Output, Pnew, overwrites P, the input covariance
448 // Pnew = (I+F*T)*P*(I+F*T)' + T^2*G*Q*G'
449 // Q is the discrete time covariance of process noise
450 // Q is vector of the diagonal for a square matrix with
451 // dimensions equal to the number of disturbance noise variables
452 // The General Method is very inefficient,not taking advantage of the sparse F and G
453 // The first Method is very specific to this implementation
454 // ************************************************
456 void CovariancePrediction(float F
[NUMX
][NUMX
], float G
[NUMX
][NUMW
],
457 float Q
[NUMW
], float dT
, float P
[NUMX
][NUMX
])
459 // 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')]
461 const float dT1
= 1.0f
/ dT
; // multiplication is faster than division on fpu.
462 const float dTsq
= dT
* dT
;
464 float Dummy
[NUMX
][NUMX
];
468 for (i
= 0; i
< NUMX
; i
++) { // Calculate Dummy = (P/T +F*P)
471 float *Dirow
= Dummy
[i
];
472 const int8_t Fistart
= FrowMin
[i
];
473 const int8_t Fiend
= FrowMax
[i
];
476 for (j
= 0; j
< NUMX
; j
++) {
477 Dirow
[j
] = Pirow
[j
] * dT1
; // Dummy = P / T ...
479 for (k
= Fistart
; k
<= Fiend
; k
++) {
480 for (j
= 0; j
< NUMX
; j
++) {
481 Dirow
[j
] += Firow
[k
] * P
[k
][j
]; // [] + F * P
485 for (i
= 0; i
< NUMX
; i
++) { // Calculate Pnew = (T^2) [Dummy/T + Dummy*F' + G*Qw*G']
486 float *Dirow
= Dummy
[i
];
489 const int8_t Gistart
= GrowMin
[i
];
490 const int8_t Giend
= GrowMax
[i
];
494 for (j
= i
; j
< NUMX
; j
++) { // Use symmetry, ie only find upper triangular
495 float Ptmp
= Dirow
[j
] * dT1
; // Pnew = Dummy / T ...
497 const float *Fjrow
= F
[j
];
498 int8_t Fjstart
= FrowMin
[j
];
499 int8_t Fjend
= FrowMax
[j
];
502 while (k
<= Fjend
- 3) {
503 Ptmp
+= Dirow
[k
] * Fjrow
[k
]; // [] + Dummy*F' ...
504 Ptmp
+= Dirow
[k
+ 1] * Fjrow
[k
+ 1];
505 Ptmp
+= Dirow
[k
+ 2] * Fjrow
[k
+ 2];
506 Ptmp
+= Dirow
[k
+ 3] * Fjrow
[k
+ 3];
510 Ptmp
+= Dirow
[k
] * Fjrow
[k
];
515 const int8_t Gjstart
= MAX(Gistart
, GrowMin
[j
]);
516 const int8_t Gjend
= MIN(Giend
, GrowMax
[j
]);
518 while (k
<= Gjend
- 2) {
519 Ptmp
+= Q
[k
] * Girow
[k
] * Gjrow
[k
]; // [] + G*Q*G' ...
520 Ptmp
+= Q
[k
+ 1] * Girow
[k
+ 1] * Gjrow
[k
+ 1];
521 Ptmp
+= Q
[k
+ 2] * Girow
[k
+ 2] * Gjrow
[k
+ 2];
525 Ptmp
+= Q
[k
] * Girow
[k
] * Gjrow
[k
];
526 if (k
<= Gjend
- 1) {
527 Ptmp
+= Q
[k
+ 1] * Girow
[k
+ 1] * Gjrow
[k
+ 1];
531 P
[j
][i
] = Pirow
[j
] = Ptmp
* dTsq
; // [] * (T^2)
536 // ************* SerialUpdate *******************
537 // Does the update step of the Kalman filter for the covariance and estimate
538 // Outputs are Xnew & Pnew, and are written over P and X
539 // Z is actual measurement, Y is predicted measurement
540 // Xnew = X + K*(Z-Y), Pnew=(I-K*H)*P,
541 // where K=P*H'*inv[H*P*H'+R]
542 // NOTE the algorithm assumes R (measurement covariance matrix) is diagonal
543 // i.e. the measurment noises are uncorrelated.
544 // It therefore uses a serial update that requires no matrix inversion by
545 // processing the measurements one at a time.
546 // Algorithm - see Grewal and Andrews, "Kalman Filtering,2nd Ed" p.121 & p.253
547 // - or see Simon, "Optimal State Estimation," 1st Ed, p.150
548 // The SensorsUsed variable is a bitwise mask indicating which sensors
549 // should be used in the update.
550 // ************************************************
551 void SerialUpdate(float H
[NUMV
][NUMX
], float R
[NUMV
], float Z
[NUMV
],
552 float Y
[NUMV
], float P
[NUMX
][NUMX
], float X
[NUMX
],
553 uint16_t SensorsUsed
)
555 float HP
[NUMX
], HPHR
, Error
;
559 for (m
= 0; m
< NUMV
; m
++) {
560 if (SensorsUsed
& (0x01 << m
)) { // use this sensor for update
561 for (j
= 0; j
< NUMX
; j
++) { // Find Hp = H*P
565 for (k
= HrowMin
[m
]; k
<= HrowMax
[m
]; k
++) {
566 for (j
= 0; j
< NUMX
; j
++) { // Find Hp = H*P
567 HP
[j
] += H
[m
][k
] * P
[k
][j
];
570 HPHR
= R
[m
]; // Find HPHR = H*P*H' + R
571 for (k
= HrowMin
[m
]; k
<= HrowMax
[m
]; k
++) {
572 HPHR
+= HP
[k
] * H
[m
][k
];
574 float invHPHR
= 1.0f
/ HPHR
;
575 for (k
= 0; k
< NUMX
; k
++) {
576 Km
[k
] = HP
[k
] * invHPHR
; // find K = HP/HPHR
578 for (i
= 0; i
< NUMX
; i
++) { // Find P(m)= P(m-1) + K*HP
579 for (j
= i
; j
< NUMX
; j
++) {
580 P
[i
][j
] = P
[j
][i
] = P
[i
][j
] - Km
[i
] * HP
[j
];
585 for (i
= 0; i
< NUMX
; i
++) { // Find X(m)= X(m-1) + K*Error
586 X
[i
] = X
[i
] + Km
[i
] * Error
;
592 // ************* RungeKutta **********************
593 // Does a 4th order Runge Kutta numerical integration step
594 // Output, Xnew, is written over X
595 // NOTE the algorithm assumes time invariant state equations and
596 // constant inputs over integration step
597 // ************************************************
599 void RungeKutta(float X
[NUMX
], float U
[NUMU
], float dT
)
601 const float dT2
= dT
/ 2.0f
;
602 float K1
[NUMX
], K2
[NUMX
], K3
[NUMX
], K4
[NUMX
], Xlast
[NUMX
];
605 for (i
= 0; i
< NUMX
; i
++) {
606 Xlast
[i
] = X
[i
]; // make a working copy
608 StateEq(X
, U
, K1
); // k1 = f(x,u)
609 for (i
= 0; i
< NUMX
; i
++) {
610 X
[i
] = Xlast
[i
] + dT2
* K1
[i
];
612 StateEq(X
, U
, K2
); // k2 = f(x+0.5*dT*k1,u)
613 for (i
= 0; i
< NUMX
; i
++) {
614 X
[i
] = Xlast
[i
] + dT2
* K2
[i
];
616 StateEq(X
, U
, K3
); // k3 = f(x+0.5*dT*k2,u)
617 for (i
= 0; i
< NUMX
; i
++) {
618 X
[i
] = Xlast
[i
] + dT
* K3
[i
];
620 StateEq(X
, U
, K4
); // k4 = f(x+dT*k3,u)
622 // Xnew = X + dT*(k1+2*k2+2*k3+k4)/6
623 for (i
= 0; i
< NUMX
; i
++) {
625 Xlast
[i
] + dT
* (K1
[i
] + 2.0f
* K2
[i
] + 2.0f
* K3
[i
] +
626 K4
[i
]) * (1.0f
/ 6.0f
);
630 // ************* Model Specific Stuff ***************************
631 // *** StateEq, MeasurementEq, LinerizeFG, and LinearizeH ********
633 // State Variables = [Pos Vel Quaternion GyroBias NO-AccelBias]
634 // Deterministic Inputs = [AngularVel Accel]
635 // Disturbance Noise = [GyroNoise AccelNoise GyroRandomWalkNoise NO-AccelRandomWalkNoise]
637 // Measurement Variables = [Pos Vel BodyFrameMagField Altimeter]
638 // Inputs to Measurement = [EarthFrameMagField]
640 // Notes: Pos and Vel in earth frame
641 // AngularVel and Accel in body frame
642 // MagFields are unit vectors
643 // Xdot is output of StateEq()
644 // F and G are outputs of LinearizeFG(), all elements not set should be zero
645 // y is output of OutputEq()
646 // H is output of LinearizeH(), all elements not set should be zero
647 // ************************************************
649 static void StateEq(float X
[NUMX
], float U
[NUMU
], float Xdot
[NUMX
])
651 float ax
, ay
, az
, wx
, wy
, wz
, q0
, q1
, q2
, q3
;
653 // ax=U[3]-X[13]; ay=U[4]-X[14]; az=U[5]-X[15]; // subtract the biases on accels
656 az
= U
[5]; // NO BIAS STATES ON ACCELS
659 wz
= U
[2] - X
[12]; // subtract the biases on gyros
672 (q0
* q0
+ q1
* q1
- q2
* q2
- q3
* q3
) * ax
+ 2.0f
* (q1
* q2
-
674 ay
+ 2.0f
* (q1
* q3
+ q0
* q2
) * az
;
676 2.0f
* (q1
* q2
+ q0
* q3
) * ax
+ (q0
* q0
- q1
* q1
+ q2
* q2
-
677 q3
* q3
) * ay
+ 2 * (q2
* q3
-
681 2.0f
* (q1
* q3
- q0
* q2
) * ax
+ 2 * (q2
* q3
+ q0
* q1
) * ay
+
682 (q0
* q0
- q1
* q1
- q2
* q2
+ q3
* q3
) * az
+ 9.81f
;
685 Xdot
[6] = (-q1
* wx
- q2
* wy
- q3
* wz
) / 2.0f
;
686 Xdot
[7] = (q0
* wx
- q3
* wy
+ q2
* wz
) / 2.0f
;
687 Xdot
[8] = (q3
* wx
+ q0
* wy
- q1
* wz
) / 2.0f
;
688 Xdot
[9] = (-q2
* wx
+ q1
* wy
+ q0
* wz
) / 2.0f
;
690 // best guess is that bias stays constant
691 Xdot
[10] = Xdot
[11] = Xdot
[12] = 0;
694 void LinearizeFG(float X
[NUMX
], float U
[NUMU
], float F
[NUMX
][NUMX
],
697 float ax
, ay
, az
, wx
, wy
, wz
, q0
, q1
, q2
, q3
;
699 // ax=U[3]-X[13]; ay=U[4]-X[14]; az=U[5]-X[15]; // subtract the biases on accels
702 az
= U
[5]; // NO BIAS STATES ON ACCELS
705 wz
= U
[2] - X
[12]; // subtract the biases on gyros
712 F
[0][3] = F
[1][4] = F
[2][5] = 1.0f
;
715 F
[3][6] = 2.0f
* (q0
* ax
- q3
* ay
+ q2
* az
);
716 F
[3][7] = 2.0f
* (q1
* ax
+ q2
* ay
+ q3
* az
);
717 F
[3][8] = 2.0f
* (-q2
* ax
+ q1
* ay
+ q0
* az
);
718 F
[3][9] = 2.0f
* (-q3
* ax
- q0
* ay
+ q1
* az
);
719 F
[4][6] = 2.0f
* (q3
* ax
+ q0
* ay
- q1
* az
);
720 F
[4][7] = 2.0f
* (q2
* ax
- q1
* ay
- q0
* az
);
721 F
[4][8] = 2.0f
* (q1
* ax
+ q2
* ay
+ q3
* az
);
722 F
[4][9] = 2.0f
* (q0
* ax
- q3
* ay
+ q2
* az
);
723 F
[5][6] = 2.0f
* (-q2
* ax
+ q1
* ay
+ q0
* az
);
724 F
[5][7] = 2.0f
* (q3
* ax
+ q0
* ay
- q1
* az
);
725 F
[5][8] = 2.0f
* (-q0
* ax
+ q3
* ay
- q2
* az
);
726 F
[5][9] = 2.0f
* (q1
* ax
+ q2
* ay
+ q3
* az
);
728 // dVdot/dabias & dVdot/dna - NO BIAS STATES ON ACCELS - S0 REPEAT FOR G BELOW
729 // 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);
730 // 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);
731 // 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;
735 F
[6][7] = -wx
/ 2.0f
;
736 F
[6][8] = -wy
/ 2.0f
;
737 F
[6][9] = -wz
/ 2.0f
;
741 F
[7][9] = -wy
/ 2.0f
;
743 F
[8][7] = -wz
/ 2.0f
;
748 F
[9][8] = -wx
/ 2.0f
;
752 F
[6][10] = q1
/ 2.0f
;
753 F
[6][11] = q2
/ 2.0f
;
754 F
[6][12] = q3
/ 2.0f
;
755 F
[7][10] = -q0
/ 2.0f
;
756 F
[7][11] = q3
/ 2.0f
;
757 F
[7][12] = -q2
/ 2.0f
;
758 F
[8][10] = -q3
/ 2.0f
;
759 F
[8][11] = -q0
/ 2.0f
;
760 F
[8][12] = q1
/ 2.0f
;
761 F
[9][10] = q2
/ 2.0f
;
762 F
[9][11] = -q1
/ 2.0f
;
763 F
[9][12] = -q0
/ 2.0f
;
765 // dVdot/dna - NO BIAS STATES ON ACCELS - S0 REPEAT FOR G HERE
766 G
[3][3] = -q0
* q0
- q1
* q1
+ q2
* q2
+ q3
* q3
;
767 G
[3][4] = 2.0f
* (-q1
* q2
+ q0
* q3
);
768 G
[3][5] = -2.0f
* (q1
* q3
+ q0
* q2
);
769 G
[4][3] = -2.0f
* (q1
* q2
+ q0
* q3
);
770 G
[4][4] = -q0
* q0
+ q1
* q1
- q2
* q2
+ q3
* q3
;
771 G
[4][5] = 2.0f
* (-q2
* q3
+ q0
* q1
);
772 G
[5][3] = 2.0f
* (-q1
* q3
+ q0
* q2
);
773 G
[5][4] = -2.0f
* (q2
* q3
+ q0
* q1
);
774 G
[5][5] = -q0
* q0
+ q1
* q1
+ q2
* q2
- q3
* q3
;
780 G
[7][0] = -q0
/ 2.0f
;
782 G
[7][2] = -q2
/ 2.0f
;
783 G
[8][0] = -q3
/ 2.0f
;
784 G
[8][1] = -q0
/ 2.0f
;
787 G
[9][1] = -q1
/ 2.0f
;
788 G
[9][2] = -q0
/ 2.0f
;
790 // dwbias = random walk noise
791 G
[10][6] = G
[11][7] = G
[12][8] = 1.0f
;
792 // dabias = random walk noise
793 // G[13][9]=G[14][10]=G[15][11]=1; // NO BIAS STATES ON ACCELS
796 void MeasurementEq(float X
[NUMX
], float Be
[3], float Y
[NUMV
])
798 float q0
, q1
, q2
, q3
;
805 // first six outputs are P and V
815 (q0
* q0
+ q1
* q1
- q2
* q2
- q3
* q3
) * Be
[0] +
816 2.0f
* (q1
* q2
+ q0
* q3
) * Be
[1] + 2.0f
* (q1
* q3
-
819 2.0f
* (q1
* q2
- q0
* q3
) * Be
[0] + (q0
* q0
- q1
* q1
+
820 q2
* q2
- q3
* q3
) * Be
[1] +
821 2.0f
* (q2
* q3
+ q0
* q1
) * Be
[2];
823 2.0f
* (q1
* q3
+ q0
* q2
) * Be
[0] + 2.0f
* (q2
* q3
-
825 (q0
* q0
- q1
* q1
- q2
* q2
+ q3
* q3
) * Be
[2];
831 void LinearizeH(float X
[NUMX
], float Be
[3], float H
[NUMV
][NUMX
])
833 float q0
, q1
, q2
, q3
;
841 H
[0][0] = H
[1][1] = H
[2][2] = 1.0f
;
843 H
[3][3] = H
[4][4] = H
[5][5] = 1.0f
;
846 H
[6][6] = 2.0f
* (q0
* Be
[0] + q3
* Be
[1] - q2
* Be
[2]);
847 H
[6][7] = 2.0f
* (q1
* Be
[0] + q2
* Be
[1] + q3
* Be
[2]);
848 H
[6][8] = 2.0f
* (-q2
* Be
[0] + q1
* Be
[1] - q0
* Be
[2]);
849 H
[6][9] = 2.0f
* (-q3
* Be
[0] + q0
* Be
[1] + q1
* Be
[2]);
850 H
[7][6] = 2.0f
* (-q3
* Be
[0] + q0
* Be
[1] + q1
* Be
[2]);
851 H
[7][7] = 2.0f
* (q2
* Be
[0] - q1
* Be
[1] + q0
* Be
[2]);
852 H
[7][8] = 2.0f
* (q1
* Be
[0] + q2
* Be
[1] + q3
* Be
[2]);
853 H
[7][9] = 2.0f
* (-q0
* Be
[0] - q3
* Be
[1] + q2
* Be
[2]);
854 H
[8][6] = 2.0f
* (q2
* Be
[0] - q1
* Be
[1] + q0
* Be
[2]);
855 H
[8][7] = 2.0f
* (q3
* Be
[0] - q0
* Be
[1] - q1
* Be
[2]);
856 H
[8][8] = 2.0f
* (q0
* Be
[0] + q3
* Be
[1] - q2
* Be
[2]);
857 H
[8][9] = 2.0f
* (q1
* Be
[0] + q2
* Be
[1] + q3
* Be
[2]);