-
Notifications
You must be signed in to change notification settings - Fork 56
/
fusion.c
1495 lines (1259 loc) · 54.6 KB
/
fusion.c
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
// Copyright (c) 2014, Freescale Semiconductor, Inc.
// All rights reserved.
// vim: set ts=4:
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of Freescale Semiconductor, Inc. nor the
// names of its contributors may be used to endorse or promote products
// derived from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
// DISCLAIMED. IN NO EVENT SHALL FREESCALE SEMICONDUCTOR, INC. BE LIABLE FOR ANY
// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
// This is the file that contains the fusion routines. It is STRONGLY RECOMMENDED
// that the casual developer NOT TOUCH THIS FILE. The mathematics behind this file
// is extremely complex, and it will be very easy (almost inevitable) that you screw
// it up.
//
#include "imuread.h"
#ifdef USE_NXP_FUSION
// kalman filter noise variances
#define FQVA_9DOF_GBY_KALMAN 2E-6F // accelerometer noise g^2 so 1.4mg RMS
#define FQVM_9DOF_GBY_KALMAN 0.1F // magnetometer noise uT^2
#define FQVG_9DOF_GBY_KALMAN 0.3F // gyro noise (deg/s)^2
#define FQWB_9DOF_GBY_KALMAN 1E-9F // gyro offset drift (deg/s)^2: 1E-9 implies 0.09deg/s max at 50Hz
#define FQWA_9DOF_GBY_KALMAN 1E-4F // linear acceleration drift g^2 (increase slows convergence to g but reduces sensitivity to shake)
#define FQWD_9DOF_GBY_KALMAN 0.5F // magnetic disturbance drift uT^2 (increase slows convergence to B but reduces sensitivity to magnet)
// initialization of Qw covariance matrix
#define FQWINITTHTH_9DOF_GBY_KALMAN 2000E-5F // th_e * th_e terms
#define FQWINITBB_9DOF_GBY_KALMAN 250E-3F // b_e * b_e terms
#define FQWINITTHB_9DOF_GBY_KALMAN 0.0F // th_e * b_e terms
#define FQWINITAA_9DOF_GBY_KALMAN 10E-5F // a_e * a_e terms (increase slows convergence to g but reduces sensitivity to shake)
#define FQWINITDD_9DOF_GBY_KALMAN 600E-3F // d_e * d_e terms (increase slows convergence to B but reduces sensitivity to magnet)
// linear acceleration and magnetic disturbance time constants
#define FCA_9DOF_GBY_KALMAN 0.5F // linear acceleration decay factor
#define FCD_9DOF_GBY_KALMAN 0.5F // magnetic disturbance decay factor
// maximum geomagnetic inclination angle tracked by Kalman filter
#define SINDELTAMAX 0.9063078F // sin of max +ve geomagnetic inclination angle: here 65.0 deg
#define COSDELTAMAX 0.4226183F // cos of max +ve geomagnetic inclination angle: here 65.0 deg
#define DEFAULTB 50.0F // default geomagnetic field (uT)
#define X 0 // vector components
#define Y 1
#define Z 2
#define FDEGTORAD 0.01745329251994F // degrees to radians conversion = pi / 180
#define FRADTODEG 57.2957795130823F // radians to degrees conversion = 180 / pi
#define ONEOVER48 0.02083333333F // 1 / 48
#define ONEOVER3840 0.0002604166667F // 1 / 3840
static void fqAeq1(Quaternion_t *pqA);
static void feCompassNED(float fR[][3], float *pfDelta, const float fBc[], const float fGp[]);
static void fNEDAnglesDegFromRotationMatrix(float R[][3], float *pfPhiDeg,
float *pfTheDeg, float *pfPsiDeg, float *pfRhoDeg, float *pfChiDeg);
static void fQuaternionFromRotationMatrix(float R[][3], Quaternion_t *pq);
static void fQuaternionFromRotationVectorDeg(Quaternion_t *pq, const float rvecdeg[], float fscaling);
static void fRotationMatrixFromQuaternion(float R[][3], const Quaternion_t *pq);
static void fRotationVectorDegFromQuaternion(Quaternion_t *pq, float rvecdeg[]);
static void qAeqAxB(Quaternion_t *pqA, const Quaternion_t *pqB);
static void qAeqBxC(Quaternion_t *pqA, const Quaternion_t *pqB, const Quaternion_t *pqC);
//static Quaternion_t qconjgAxB(const Quaternion_t *pqA, const Quaternion_t *pqB);
static void fqAeqNormqA(Quaternion_t *pqA);
static float fasin_deg(float x);
static float facos_deg(float x);
static float fatan_deg(float x);
static float fatan2_deg(float y, float x);
static float fatan_15deg(float x);
// 9DOF Kalman filter accelerometer, magnetometer and gyroscope state vector structure
typedef struct
{
// start: elements common to all motion state vectors
// Euler angles
float PhiPl; // roll (deg)
float ThePl; // pitch (deg)
float PsiPl; // yaw (deg)
float RhoPl; // compass (deg)
float ChiPl; // tilt from vertical (deg)
// orientation matrix, quaternion and rotation vector
float RPl[3][3]; // a posteriori orientation matrix
Quaternion_t qPl; // a posteriori orientation quaternion
float RVecPl[3]; // rotation vector
// angular velocity
float Omega[3]; // angular velocity (deg/s)
// systick timer for benchmarking
int32_t systick; // systick timer;
// end: elements common to all motion state vectors
// elements transmitted over bluetooth in kalman packet
float bPl[3]; // gyro offset (deg/s)
float ThErrPl[3]; // orientation error (deg)
float bErrPl[3]; // gyro offset error (deg/s)
// end elements transmitted in kalman packet
float dErrGlPl[3]; // magnetic disturbance error (uT, global frame)
float dErrSePl[3]; // magnetic disturbance error (uT, sensor frame)
float aErrSePl[3]; // linear acceleration error (g, sensor frame)
float aSeMi[3]; // linear acceleration (g, sensor frame)
float DeltaPl; // inclination angle (deg)
float aSePl[3]; // linear acceleration (g, sensor frame)
float aGlPl[3]; // linear acceleration (g, global frame)
float gErrSeMi[3]; // difference (g, sensor frame) of gravity vector (accel) and gravity vector (gyro)
float mErrSeMi[3]; // difference (uT, sensor frame) of geomagnetic vector (magnetometer) and geomagnetic vector (gyro)
float gSeGyMi[3]; // gravity vector (g, sensor frame) measurement from gyro
float mSeGyMi[3]; // geomagnetic vector (uT, sensor frame) measurement from gyro
float mGl[3]; // geomagnetic vector (uT, global frame)
float QvAA; // accelerometer terms of Qv
float QvMM; // magnetometer terms of Qv
float PPlus12x12[12][12]; // covariance matrix P+
float K12x6[12][6]; // kalman filter gain matrix K
float Qw12x12[12][12]; // covariance matrix Qw
float C6x12[6][12]; // measurement matrix C
float RMi[3][3]; // a priori orientation matrix
Quaternion_t Deltaq; // delta quaternion
Quaternion_t qMi; // a priori orientation quaternion
float casq; // FCA * FCA;
float cdsq; // FCD * FCD;
float Fastdeltat; // sensor sampling interval (s) = 1 / SENSORFS
float deltat; // kalman filter sampling interval (s) = OVERSAMPLE_RATIO / SENSORFS
float deltatsq; // fdeltat * fdeltat
float QwbplusQvG; // FQWB + FQVG
int16_t FirstOrientationLock; // denotes that 9DOF orientation has locked to 6DOF
int8_t resetflag; // flag to request re-initialization on next pass
} SV_9DOF_GBY_KALMAN_t;
SV_9DOF_GBY_KALMAN_t fusionstate;
void fInit_9DOF_GBY_KALMAN(SV_9DOF_GBY_KALMAN_t *SV);
void fRun_9DOF_GBY_KALMAN(SV_9DOF_GBY_KALMAN_t *SV,
const AccelSensor_t *Accel, const MagSensor_t *Mag, const GyroSensor_t *Gyro,
const MagCalibration_t *MagCal);
void fusion_init(void)
{
fInit_9DOF_GBY_KALMAN(&fusionstate);
}
void fusion_update(const AccelSensor_t *Accel, const MagSensor_t *Mag, const GyroSensor_t *Gyro,
const MagCalibration_t *MagCal)
{
fRun_9DOF_GBY_KALMAN(&fusionstate, Accel, Mag, Gyro, MagCal);
}
void fusion_read(Quaternion_t *q)
{
memcpy(q, &(fusionstate.qPl), sizeof(Quaternion_t));
}
// function initializes the 9DOF Kalman filter
void fInit_9DOF_GBY_KALMAN(SV_9DOF_GBY_KALMAN_t *SV)
{
int8_t i, j; // loop counters
// reset the flag denoting that a first 9DOF orientation lock has been achieved
SV->FirstOrientationLock = 0;
// compute and store useful product terms to save floating point calculations later
SV->Fastdeltat = 1.0F / (float)SENSORFS;
SV->deltat = (float)OVERSAMPLE_RATIO * SV->Fastdeltat;
SV->deltatsq = SV->deltat * SV->deltat;
SV->casq = FCA_9DOF_GBY_KALMAN * FCA_9DOF_GBY_KALMAN;
SV->cdsq = FCD_9DOF_GBY_KALMAN * FCD_9DOF_GBY_KALMAN;
SV->QwbplusQvG = FQWB_9DOF_GBY_KALMAN + FQVG_9DOF_GBY_KALMAN;
// initialize the fixed entries in the measurement matrix C
for (i = 0; i < 6; i++) {
for (j = 0; j < 12; j++) {
SV->C6x12[i][j]= 0.0F;
}
}
SV->C6x12[0][6] = SV->C6x12[1][7] = SV->C6x12[2][8] = 1.0F;
SV->C6x12[3][9] = SV->C6x12[4][10] = SV->C6x12[5][11] = -1.0F;
// zero a posteriori orientation, error vector xe+ (thetae+, be+, de+, ae+) and b+ and inertial
f3x3matrixAeqI(SV->RPl);
fqAeq1(&(SV->qPl));
for (i = X; i <= Z; i++) {
SV->ThErrPl[i] = SV->bErrPl[i] = SV->aErrSePl[i] = SV->dErrSePl[i] = SV->bPl[i] = 0.0F;
}
// initialize the reference geomagnetic vector (uT, global frame)
SV->DeltaPl = 0.0F;
// initialize NED geomagnetic vector to zero degrees inclination
SV->mGl[X] = DEFAULTB;
SV->mGl[Y] = 0.0F;
SV->mGl[Z] = 0.0F;
// initialize noise variances for Qv and Qw matrix updates
SV->QvAA = FQVA_9DOF_GBY_KALMAN + FQWA_9DOF_GBY_KALMAN + FDEGTORAD * FDEGTORAD * SV->deltatsq * (FQWB_9DOF_GBY_KALMAN + FQVG_9DOF_GBY_KALMAN);
SV->QvMM = FQVM_9DOF_GBY_KALMAN + FQWD_9DOF_GBY_KALMAN + FDEGTORAD * FDEGTORAD * SV->deltatsq * DEFAULTB * DEFAULTB * (FQWB_9DOF_GBY_KALMAN + FQVG_9DOF_GBY_KALMAN);
// initialize the 12x12 noise covariance matrix Qw of the a priori error vector xe-
// Qw is then recursively updated as P+ = (1 - K * C) * P- = (1 - K * C) * Qw and Qw
// updated from P+
// zero the matrix Qw
for (i = 0; i < 12; i++) {
for (j = 0; j < 12; j++) {
SV->Qw12x12[i][j] = 0.0F;
}
}
// loop over non-zero values
for (i = 0; i < 3; i++) {
// theta_e * theta_e terms
SV->Qw12x12[i][i] = FQWINITTHTH_9DOF_GBY_KALMAN;
// b_e * b_e terms
SV->Qw12x12[i + 3][i + 3] = FQWINITBB_9DOF_GBY_KALMAN;
// th_e * b_e terms
SV->Qw12x12[i][i + 3] = SV->Qw12x12[i + 3][i] = FQWINITTHB_9DOF_GBY_KALMAN;
// a_e * a_e terms
SV->Qw12x12[i + 6][i + 6] = FQWINITAA_9DOF_GBY_KALMAN;
// d_e * d_e terms
SV->Qw12x12[i + 9][i + 9] = FQWINITDD_9DOF_GBY_KALMAN;
}
// clear the reset flag
SV->resetflag = 0;
}
// 9DOF orientation function implemented using a 12 element Kalman filter
void fRun_9DOF_GBY_KALMAN(SV_9DOF_GBY_KALMAN_t *SV,
const AccelSensor_t *Accel, const MagSensor_t *Mag, const GyroSensor_t *Gyro,
const MagCalibration_t *MagCal)
{
// local scalars and arrays
float fopp, fadj, fhyp; // opposite, adjacent and hypoteneuse
float fsindelta, fcosdelta; // sin and cos of inclination angle delta
float rvec[3]; // rotation vector
float ftmp; // scratch variable
float ftmpA12x6[12][6]; // scratch array
int8_t i, j, k; // loop counters
int8_t iMagJamming; // magnetic jamming flag
// assorted array pointers
float *pfPPlus12x12ij;
float *pfPPlus12x12kj;
float *pfQw12x12ij;
float *pfQw12x12ik;
float *pfQw12x12kj;
float *pfK12x6ij;
float *pfK12x6ik;
float *pftmpA12x6ik;
float *pftmpA12x6kj;
float *pftmpA12x6ij;
float *pfC6x12ik;
float *pfC6x12jk;
// working arrays for 6x6 matrix inversion
float *pfRows[6];
int8_t iColInd[6];
int8_t iRowInd[6];
int8_t iPivot[6];
// do a reset and return if requested
if (SV->resetflag) {
fInit_9DOF_GBY_KALMAN(SV);
return;
}
// *********************************************************************************
// initial orientation lock to accelerometer and magnetometer eCompass orientation
// *********************************************************************************
// do a once-only orientation lock after the first valid magnetic calibration
if (MagCal->ValidMagCal && !SV->FirstOrientationLock) {
// get the 6DOF orientation matrix and initial inclination angle
feCompassNED(SV->RPl, &(SV->DeltaPl), Mag->BcFast, Accel->GpFast);
// get the orientation quaternion from the orientation matrix
fQuaternionFromRotationMatrix(SV->RPl, &(SV->qPl));
// set the orientation lock flag so this initial alignment is only performed once
SV->FirstOrientationLock = 1;
}
// *********************************************************************************
// calculate a priori rotation matrix
// *********************************************************************************
// compute the angular velocity from the averaged high frequency gyro reading.
// omega[k] = yG[k] - b-[k] = yG[k] - b+[k-1] (deg/s)
SV->Omega[X] = Gyro->Yp[X] - SV->bPl[X];
SV->Omega[Y] = Gyro->Yp[Y] - SV->bPl[Y];
SV->Omega[Z] = Gyro->Yp[Z] - SV->bPl[Z];
// initialize the a priori orientation quaternion to the previous a posteriori estimate
SV->qMi = SV->qPl;
// integrate the buffered high frequency (typically 200Hz) gyro readings
for (j = 0; j < OVERSAMPLE_RATIO; j++) {
// compute the incremental fast (typically 200Hz) rotation vector rvec (deg)
for (i = X; i <= Z; i++) {
rvec[i] = (Gyro->YpFast[j][i] - SV->bPl[i]) * SV->Fastdeltat;
}
// compute the incremental quaternion fDeltaq from the rotation vector
fQuaternionFromRotationVectorDeg(&(SV->Deltaq), rvec, 1.0F);
// incrementally rotate the a priori orientation quaternion fqMi
// the a posteriori quaternion fqPl is re-normalized later so this update is stable
qAeqAxB(&(SV->qMi), &(SV->Deltaq));
}
// get the a priori rotation matrix from the a priori quaternion
fRotationMatrixFromQuaternion(SV->RMi, &(SV->qMi));
// *********************************************************************************
// calculate a priori gyro, accelerometer and magnetometer estimates
// of the gravity and geomagnetic vectors and errors
// the most recent 'Fast' measurements are used to reduce phase errors
// *********************************************************************************
for (i = X; i <= Z; i++) {
// compute the a priori gyro estimate of the gravitational vector (g, sensor frame)
// using an absolute rotation of the global frame gravity vector (with magnitude 1g)
// NED gravity is along positive z axis
SV->gSeGyMi[i] = SV->RMi[i][Z];
// compute a priori acceleration (a-) (g, sensor frame) from decayed a
// posteriori estimate (g, sensor frame)
SV->aSeMi[i] = FCA_9DOF_GBY_KALMAN * SV->aSePl[i];
// compute the a priori gravity error vector (accelerometer minus gyro estimates)
// (g, sensor frame)
// NED and Windows 8 have positive sign for gravity: y = g - a and g = y + a
SV->gErrSeMi[i] = Accel->GpFast[i] + SV->aSeMi[i] - SV->gSeGyMi[i];
// compute the a priori gyro estimate of the geomagnetic vector (uT, sensor frame)
// using an absolute rotation of the global frame geomagnetic vector (with magnitude B uT)
// NED y component of geomagnetic vector in global frame is zero
SV->mSeGyMi[i] = SV->RMi[i][X] * SV->mGl[X] + SV->RMi[i][Z] * SV->mGl[Z];
// compute the a priori geomagnetic error vector (magnetometer minus gyro estimates)
// (g, sensor frame)
SV->mErrSeMi[i] = Mag->BcFast[i] - SV->mSeGyMi[i];
}
// *********************************************************************************
// update variable elements of measurement matrix C
// *********************************************************************************
// update measurement matrix C with -alpha(g-)x and -alpha(m-)x from gyro (g, uT, sensor frame)
SV->C6x12[0][1] = FDEGTORAD * SV->gSeGyMi[Z];
SV->C6x12[0][2] = -FDEGTORAD * SV->gSeGyMi[Y];
SV->C6x12[1][2] = FDEGTORAD * SV->gSeGyMi[X];
SV->C6x12[1][0] = -SV->C6x12[0][1];
SV->C6x12[2][0] = -SV->C6x12[0][2];
SV->C6x12[2][1] = -SV->C6x12[1][2];
SV->C6x12[3][1] = FDEGTORAD * SV->mSeGyMi[Z];
SV->C6x12[3][2] = -FDEGTORAD * SV->mSeGyMi[Y];
SV->C6x12[4][2] = FDEGTORAD * SV->mSeGyMi[X];
SV->C6x12[4][0] = -SV->C6x12[3][1];
SV->C6x12[5][0] = -SV->C6x12[3][2];
SV->C6x12[5][1] = -SV->C6x12[4][2];
SV->C6x12[0][4] = -SV->deltat * SV->C6x12[0][1];
SV->C6x12[0][5] = -SV->deltat * SV->C6x12[0][2];
SV->C6x12[1][5] = -SV->deltat * SV->C6x12[1][2];
SV->C6x12[1][3]= -SV->C6x12[0][4];
SV->C6x12[2][3]= -SV->C6x12[0][5];
SV->C6x12[2][4]= -SV->C6x12[1][5];
SV->C6x12[3][4] = -SV->deltat * SV->C6x12[3][1];
SV->C6x12[3][5] = -SV->deltat * SV->C6x12[3][2];
SV->C6x12[4][5] = -SV->deltat * SV->C6x12[4][2];
SV->C6x12[4][3] = -SV->C6x12[3][4];
SV->C6x12[5][3] = -SV->C6x12[3][5];
SV->C6x12[5][4] = -SV->C6x12[4][5];
// *********************************************************************************
// calculate the Kalman gain matrix K
// K = P- * C^T * inv(C * P- * C^T + Qv) = Qw * C^T * inv(C * Qw * C^T + Qv)
// Qw is used as a proxy for P- throughout the code
// P+ is used here as a working array to reduce RAM usage and is re-computed later
// *********************************************************************************
// set ftmpA12x6 = P- * C^T = Qw * C^T where Qw and C are both sparse
// C also has a significant number of +1 and -1 entries
// ftmpA12x6 is also sparse but not symmetric
for (i = 0; i < 12; i++) { // loop over rows of ftmpA12x6
// initialize pftmpA12x6ij for current i, j=0
pftmpA12x6ij = ftmpA12x6[i];
for (j = 0; j < 6; j++) { // loop over columns of ftmpA12x6
// zero ftmpA12x6[i][j]
*pftmpA12x6ij = 0.0F;
// initialize pfC6x12jk for current j, k=0
pfC6x12jk = SV->C6x12[j];
// initialize pfQw12x12ik for current i, k=0
pfQw12x12ik = SV->Qw12x12[i];
// sum matrix products over inner loop over k
for (k = 0; k < 12; k++) {
if ((*pfQw12x12ik != 0.0F) && (*pfC6x12jk != 0.0F)) {
if (*pfC6x12jk == 1.0F)
*pftmpA12x6ij += *pfQw12x12ik;
else if (*pfC6x12jk == -1.0F)
*pftmpA12x6ij -= *pfQw12x12ik;
else
*pftmpA12x6ij += *pfQw12x12ik * *pfC6x12jk;
}
// increment pfC6x12jk and pfQw12x12ik for next iteration of k
pfC6x12jk++;
pfQw12x12ik++;
}
// increment pftmpA12x6ij for next iteration of j
pftmpA12x6ij++;
}
}
// set symmetric P+ (6x6 scratch sub-matrix) to C * P- * C^T + Qv
// = C * (Qw * C^T) + Qv = C * ftmpA12x6 + Qv
// both C and ftmpA12x6 are sparse but not symmetric
for (i = 0; i < 6; i++) { // loop over rows of P+
// initialize pfPPlus12x12ij for current i, j=i
pfPPlus12x12ij = SV->PPlus12x12[i] + i;
for (j = i; j < 6; j++) { // loop over above diagonal columns of P+
// zero P+[i][j]
*pfPPlus12x12ij = 0.0F;
// initialize pfC6x12ik for current i, k=0
pfC6x12ik = SV->C6x12[i];
// initialize pftmpA12x6kj for current j, k=0
pftmpA12x6kj = *ftmpA12x6 + j;
// sum matrix products over inner loop over k
for (k = 0; k < 12; k++) {
if ((*pfC6x12ik != 0.0F) && (*pftmpA12x6kj != 0.0F)) {
if (*pfC6x12ik == 1.0F)
*pfPPlus12x12ij += *pftmpA12x6kj;
else if (*pfC6x12ik == -1.0F)
*pfPPlus12x12ij -= *pftmpA12x6kj;
else
*pfPPlus12x12ij += *pfC6x12ik * *pftmpA12x6kj;
}
// update pfC6x12ik and pftmpA12x6kj for next iteration of k
pfC6x12ik++;
pftmpA12x6kj += 6;
}
// increment pfPPlus12x12ij for next iteration of j
pfPPlus12x12ij++;
}
}
// add in noise covariance terms to the diagonal
SV->PPlus12x12[0][0] += SV->QvAA;
SV->PPlus12x12[1][1] += SV->QvAA;
SV->PPlus12x12[2][2] += SV->QvAA;
SV->PPlus12x12[3][3] += SV->QvMM;
SV->PPlus12x12[4][4] += SV->QvMM;
SV->PPlus12x12[5][5] += SV->QvMM;
// copy above diagonal elements of P+ (6x6 scratch sub-matrix) to below diagonal
for (i = 1; i < 6; i++)
for (j = 0; j < i; j++)
SV->PPlus12x12[i][j] = SV->PPlus12x12[j][i];
// calculate inverse of P+ (6x6 scratch sub-matrix) = inv(C * P- * C^T + Qv) = inv(C * Qw * C^T + Qv)
for (i = 0; i < 6; i++) {
pfRows[i] = SV->PPlus12x12[i];
}
fmatrixAeqInvA(pfRows, iColInd, iRowInd, iPivot, 3);
// set K = P- * C^T * inv(C * P- * C^T + Qv) = Qw * C^T * inv(C * Qw * C^T + Qv)
// = ftmpA12x6 * P+ (6x6 sub-matrix)
// ftmpA12x6 = Qw * C^T is sparse but P+ (6x6 sub-matrix) is not
// K is not symmetric because C is not symmetric
for (i = 0; i < 12; i++) { // loop over rows of K12x6
// initialize pfK12x6ij for current i, j=0
pfK12x6ij = SV->K12x6[i];
for (j = 0; j < 6; j++) { // loop over columns of K12x6
// zero the matrix element fK12x6[i][j]
*pfK12x6ij = 0.0F;
// initialize pftmpA12x6ik for current i, k=0
pftmpA12x6ik = ftmpA12x6[i];
// initialize pfPPlus12x12kj for current j, k=0
pfPPlus12x12kj = *SV->PPlus12x12 + j;
// sum matrix products over inner loop over k
for (k = 0; k < 6; k++) {
if (*pftmpA12x6ik != 0.0F) {
*pfK12x6ij += *pftmpA12x6ik * *pfPPlus12x12kj;
}
// increment pftmpA12x6ik and pfPPlus12x12kj for next iteration of k
pftmpA12x6ik++;
pfPPlus12x12kj += 12;
}
// increment pfK12x6ij for the next iteration of j
pfK12x6ij++;
}
}
// *********************************************************************************
// calculate a posteriori error estimate: xe+ = K * ze-
// *********************************************************************************
// first calculate all four error vector components using accelerometer error component only
// for fThErrPl, fbErrPl, faErrSePl but also magnetometer for fdErrSePl
for (i = X; i <= Z; i++) {
SV->ThErrPl[i] = SV->K12x6[i][0] * SV->gErrSeMi[X] +
SV->K12x6[i][1] * SV->gErrSeMi[Y] +
SV->K12x6[i][2] * SV->gErrSeMi[Z];
SV->bErrPl[i] = SV->K12x6[i + 3][0] * SV->gErrSeMi[X] +
SV->K12x6[i + 3][1] * SV->gErrSeMi[Y] +
SV->K12x6[i + 3][2] * SV->gErrSeMi[Z];
SV->aErrSePl[i] = SV->K12x6[i + 6][0] * SV->gErrSeMi[X] +
SV->K12x6[i + 6][1] * SV->gErrSeMi[Y] +
SV->K12x6[i + 6][2] * SV->gErrSeMi[Z];
SV->dErrSePl[i] = SV->K12x6[i + 9][0] * SV->gErrSeMi[X] +
SV->K12x6[i + 9][1] * SV->gErrSeMi[Y] +
SV->K12x6[i + 9][2] * SV->gErrSeMi[Z] +
SV->K12x6[i + 9][3] * SV->mErrSeMi[X] +
SV->K12x6[i + 9][4] * SV->mErrSeMi[Y] +
SV->K12x6[i + 9][5] * SV->mErrSeMi[Z];
}
// set the magnetic jamming flag if there is a significant magnetic error power after calibration
ftmp = SV->dErrSePl[X] * SV->dErrSePl[X] + SV->dErrSePl[Y] * SV->dErrSePl[Y] +
SV->dErrSePl[Z] * SV->dErrSePl[Z];
iMagJamming = (MagCal->ValidMagCal) && (ftmp > MagCal->FourBsq);
// add the remaining magnetic error terms if there is calibration and no magnetic jamming
if (MagCal->ValidMagCal && !iMagJamming) {
for (i = X; i <= Z; i++) {
SV->ThErrPl[i] += SV->K12x6[i][3] * SV->mErrSeMi[X] +
SV->K12x6[i][4] * SV->mErrSeMi[Y] +
SV->K12x6[i][5] * SV->mErrSeMi[Z];
SV->bErrPl[i] += SV->K12x6[i + 3][3] * SV->mErrSeMi[X] +
SV->K12x6[i + 3][4] * SV->mErrSeMi[Y] +
SV->K12x6[i + 3][5] * SV->mErrSeMi[Z];
SV->aErrSePl[i] += SV->K12x6[i + 6][3] * SV->mErrSeMi[X] +
SV->K12x6[i + 6][4] * SV->mErrSeMi[Y] +
SV->K12x6[i + 6][5] * SV->mErrSeMi[Z];
}
}
// *********************************************************************************
// apply the a posteriori error corrections to the a posteriori state vector
// *********************************************************************************
// get the a posteriori delta quaternion
fQuaternionFromRotationVectorDeg(&(SV->Deltaq), SV->ThErrPl, -1.0F);
// compute the a posteriori orientation quaternion fqPl = fqMi * Deltaq(-thetae+)
// the resulting quaternion may have negative scalar component q0
qAeqBxC(&(SV->qPl), &(SV->qMi), &(SV->Deltaq));
// normalize the a posteriori orientation quaternion to stop error propagation
// the renormalization function ensures that the scalar component q0 is non-negative
fqAeqNormqA(&(SV->qPl));
// compute the a posteriori rotation matrix from the a posteriori quaternion
fRotationMatrixFromQuaternion(SV->RPl, &(SV->qPl));
// compute the rotation vector from the a posteriori quaternion
fRotationVectorDegFromQuaternion(&(SV->qPl), SV->RVecPl);
// update the a posteriori gyro offset vector b+ and
// assign the entire linear acceleration error vector to update the linear acceleration
for (i = X; i <= Z; i++) {
// b+[k] = b-[k] - be+[k] = b+[k] - be+[k] (deg/s)
SV->bPl[i] -= SV->bErrPl[i];
// a+ = a- - ae+ (g, sensor frame)
SV->aSePl[i] = SV->aSeMi[i] - SV->aErrSePl[i];
}
// compute the linear acceleration in the global frame from the accelerometer measurement (sensor frame).
// de-rotate the accelerometer measurement from the sensor to global frame using the inverse (transpose)
// of the a posteriori rotation matrix
SV->aGlPl[X] = SV->RPl[X][X] * Accel->GpFast[X] + SV->RPl[Y][X] * Accel->GpFast[Y] +
SV->RPl[Z][X] * Accel->GpFast[Z];
SV->aGlPl[Y] = SV->RPl[X][Y] * Accel->GpFast[X] + SV->RPl[Y][Y] * Accel->GpFast[Y] +
SV->RPl[Z][Y] * Accel->GpFast[Z];
SV->aGlPl[Z] = SV->RPl[X][Z] * Accel->GpFast[X] + SV->RPl[Y][Z] * Accel->GpFast[Y] +
SV->RPl[Z][Z] * Accel->GpFast[Z];
// remove gravity and correct the sign if the coordinate system is gravity positive / acceleration negative
// gravity positive NED
SV->aGlPl[X] = -SV->aGlPl[X];
SV->aGlPl[Y] = -SV->aGlPl[Y];
SV->aGlPl[Z] = -(SV->aGlPl[Z] - 1.0F);
// update the reference geomagnetic vector using magnetic disturbance error if valid calibration and no jamming
if (MagCal->ValidMagCal && !iMagJamming) {
// de-rotate the NED magnetic disturbance error de+ from the sensor to the global reference frame
// using the inverse (transpose) of the a posteriori rotation matrix
SV->dErrGlPl[X] = SV->RPl[X][X] * SV->dErrSePl[X] +
SV->RPl[Y][X] * SV->dErrSePl[Y] +
SV->RPl[Z][X] * SV->dErrSePl[Z];
SV->dErrGlPl[Z] = SV->RPl[X][Z] * SV->dErrSePl[X] +
SV->RPl[Y][Z] * SV->dErrSePl[Y] +
SV->RPl[Z][Z] * SV->dErrSePl[Z];
// compute components of the new geomagnetic vector
// the north pointing component fadj must always be non-negative
fopp = SV->mGl[Z] - SV->dErrGlPl[Z];
fadj = SV->mGl[X] - SV->dErrGlPl[X];
if (fadj < 0.0F) {
fadj = 0.0F;
}
fhyp = sqrtf(fopp * fopp + fadj * fadj);
// check for the pathological condition of zero geomagnetic field
if (fhyp != 0.0F) {
// compute the sine and cosine of the new geomagnetic vector
ftmp = 1.0F / fhyp;
fsindelta = fopp * ftmp;
fcosdelta = fadj * ftmp;
// limit the inclination angle between limits to prevent runaway
if (fsindelta > SINDELTAMAX) {
fsindelta = SINDELTAMAX;
fcosdelta = COSDELTAMAX;
} else if (fsindelta < -SINDELTAMAX) {
fsindelta = -SINDELTAMAX;
fcosdelta = COSDELTAMAX;
}
// compute the new geomagnetic vector (always north pointing)
SV->DeltaPl = fasin_deg(fsindelta);
SV->mGl[X] = MagCal->B * fcosdelta;
SV->mGl[Z] = MagCal->B * fsindelta;
} // end hyp == 0.0F
} // end ValidMagCal
// *********************************************************************************
// compute the a posteriori Euler angles from the orientation matrix
// *********************************************************************************
// calculate the NED Euler angles
fNEDAnglesDegFromRotationMatrix(SV->RPl, &(SV->PhiPl), &(SV->ThePl), &(SV->PsiPl),
&(SV->RhoPl), &(SV->ChiPl));
// ***********************************************************************************
// calculate (symmetric) a posteriori error covariance matrix P+
// P+ = (I12 - K * C) * P- = (I12 - K * C) * Qw = Qw - K * (C * Qw)
// both Qw and P+ are used as working arrays in this section
// at the end of this section, P+ is valid but Qw is over-written
// ***********************************************************************************
// set P+ (6x12 scratch sub-matrix) to the product C (6x12) * Qw (12x12)
// where both C and Qw are sparse and C has a significant number of +1 and -1 entries
// the resulting matrix is sparse but not symmetric
for (i = 0; i < 6; i++) {
// initialize pfPPlus12x12ij for current i, j=0
pfPPlus12x12ij = SV->PPlus12x12[i];
for (j = 0; j < 12; j++) {
// zero P+[i][j]
*pfPPlus12x12ij = 0.0F;
// initialize pfC6x12ik for current i, k=0
pfC6x12ik = SV->C6x12[i];
// initialize pfQw12x12kj for current j, k=0
pfQw12x12kj = &SV->Qw12x12[0][j];
// sum matrix products over inner loop over k
for (k = 0; k < 12; k++) {
if ((*pfC6x12ik != 0.0F) && (*pfQw12x12kj != 0.0F)) {
if (*pfC6x12ik == 1.0F)
*pfPPlus12x12ij += *pfQw12x12kj;
else if (*pfC6x12ik == -1.0F)
*pfPPlus12x12ij -= *pfQw12x12kj;
else
*pfPPlus12x12ij += *pfC6x12ik * *pfQw12x12kj;
}
// update pfC6x12ik and pfQw12x12kj for next iteration of k
pfC6x12ik++;
pfQw12x12kj += 12;
}
// increment pfPPlus12x12ij for next iteration of j
pfPPlus12x12ij++;
}
}
// compute P+ = (I12 - K * C) * Qw = Qw - K * (C * Qw) = Qw - K * P+ (6x12 sub-matrix)
// storing result P+ in Qw and over-writing Qw which is OK since Qw is later computed from P+
// where working array P+ (6x12 sub-matrix) is sparse but K is not sparse
// only on and above diagonal terms of P+ are computed since P+ is symmetric
for (i = 0; i < 12; i++) {
// initialize pfQw12x12ij for current i, j=i
pfQw12x12ij = SV->Qw12x12[i] + i;
for (j = i; j < 12; j++) {
// initialize pfK12x6ik for current i, k=0
pfK12x6ik = SV->K12x6[i];
// initialize pfPPlus12x12kj for current j, k=0
pfPPlus12x12kj = *SV->PPlus12x12 + j;
// compute on and above diagonal matrix entry
for (k = 0; k < 6; k++) {
// check for non-zero values since P+ (6x12 scratch sub-matrix) is sparse
if (*pfPPlus12x12kj != 0.0F) {
*pfQw12x12ij -= *pfK12x6ik * *pfPPlus12x12kj;
}
// increment pfK12x6ik and pfPPlus12x12kj for next iteration of k
pfK12x6ik++;
pfPPlus12x12kj += 12;
}
// increment pfQw12x12ij for next iteration of j
pfQw12x12ij++;
}
}
// Qw now holds the on and above diagonal elements of P+
// so perform a simple copy to the all elements of P+
// after execution of this code P+ is valid but Qw remains invalid
for (i = 0; i < 12; i++) {
// initialize pfPPlus12x12ij and pfQw12x12ij for current i, j=i
pfPPlus12x12ij = SV->PPlus12x12[i] + i;
pfQw12x12ij = SV->Qw12x12[i] + i;
// copy the on-diagonal elements and increment pointers to enter loop at j=i+1
*(pfPPlus12x12ij++) = *(pfQw12x12ij++);
// loop over above diagonal columns j copying to below-diagonal elements
for (j = i + 1; j < 12; j++) {
*(pfPPlus12x12ij++)= SV->PPlus12x12[j][i] = *(pfQw12x12ij++);
}
}
// *********************************************************************************
// re-create the noise covariance matrix Qw=fn(P+) for the next iteration
// using the elements of P+ which are now valid
// Qw was over-written earlier but is here recomputed (all elements)
// *********************************************************************************
// zero the matrix Qw
for (i = 0; i < 12; i++) {
for (j = 0; j < 12; j++) {
SV->Qw12x12[i][j] = 0.0F;
}
}
// update the covariance matrix components
for (i = 0; i < 3; i++) {
// Qw[th-th-] = Qw[0-2][0-2] = E[th-(th-)^T] = Q[th+th+] + deltat^2 * (Q[b+b+] + (Qwb + QvG) * I)
SV->Qw12x12[i][i] = SV->PPlus12x12[i][i] + SV->deltatsq * (SV->PPlus12x12[i + 3][i + 3] + SV->QwbplusQvG);
// Qw[b-b-] = Qw[3-5][3-5] = E[b-(b-)^T] = Q[b+b+] + Qwb * I
SV->Qw12x12[i + 3][i + 3] = SV->PPlus12x12[i + 3][i + 3] + FQWB_9DOF_GBY_KALMAN;
// Qw[th-b-] = Qw[0-2][3-5] = E[th-(b-)^T] = -deltat * (Q[b+b+] + Qwb * I) = -deltat * Qw[b-b-]
SV->Qw12x12[i][i + 3] = SV->Qw12x12[i + 3][i] = -SV->deltat * SV->Qw12x12[i + 3][i + 3];
// Qw[a-a-] = Qw[6-8][6-8] = E[a-(a-)^T] = ca^2 * Q[a+a+] + Qwa * I
SV->Qw12x12[i + 6][i + 6] = SV->casq * SV->PPlus12x12[i + 6][i + 6] + FQWA_9DOF_GBY_KALMAN;
// Qw[d-d-] = Qw[9-11][9-11] = E[d-(d-)^T] = cd^2 * Q[d+d+] + Qwd * I
SV->Qw12x12[i + 9][i + 9] = SV->cdsq * SV->PPlus12x12[i + 9][i + 9] + FQWD_9DOF_GBY_KALMAN;
}
}
// compile time constants that are private to this file
#define SMALLQ0 0.01F // limit of quaternion scalar component requiring special algorithm
#define CORRUPTQUAT 0.001F // threshold for deciding rotation quaternion is corrupt
#define SMALLMODULUS 0.01F // limit where rounding errors may appear
// Aerospace NED accelerometer 3DOF tilt function computing rotation matrix fR
void f3DOFTiltNED(float fR[][3], float fGp[])
{
// the NED self-consistency twist occurs at 90 deg pitch
// local variables
int16_t i; // counter
float fmodGxyz; // modulus of the x, y, z accelerometer readings
float fmodGyz; // modulus of the y, z accelerometer readings
float frecipmodGxyz; // reciprocal of modulus
float ftmp; // scratch variable
// compute the accelerometer squared magnitudes
fmodGyz = fGp[Y] * fGp[Y] + fGp[Z] * fGp[Z];
fmodGxyz = fmodGyz + fGp[X] * fGp[X];
// check for freefall special case where no solution is possible
if (fmodGxyz == 0.0F) {
f3x3matrixAeqI(fR);
return;
}
// check for vertical up or down gimbal lock case
if (fmodGyz == 0.0F) {
f3x3matrixAeqScalar(fR, 0.0F);
fR[Y][Y] = 1.0F;
if (fGp[X] >= 0.0F) {
fR[X][Z] = 1.0F;
fR[Z][X] = -1.0F;
} else {
fR[X][Z] = -1.0F;
fR[Z][X] = 1.0F;
}
return;
}
// compute moduli for the general case
fmodGyz = sqrtf(fmodGyz);
fmodGxyz = sqrtf(fmodGxyz);
frecipmodGxyz = 1.0F / fmodGxyz;
ftmp = fmodGxyz / fmodGyz;
// normalize the accelerometer reading into the z column
for (i = X; i <= Z; i++) {
fR[i][Z] = fGp[i] * frecipmodGxyz;
}
// construct x column of orientation matrix
fR[X][X] = fmodGyz * frecipmodGxyz;
fR[Y][X] = -fR[X][Z] * fR[Y][Z] * ftmp;
fR[Z][X] = -fR[X][Z] * fR[Z][Z] * ftmp;
// // construct y column of orientation matrix
fR[X][Y] = 0.0F;
fR[Y][Y] = fR[Z][Z] * ftmp;
fR[Z][Y] = -fR[Y][Z] * ftmp;
}
// Aerospace NED magnetometer 3DOF flat eCompass function computing rotation matrix fR
void f3DOFMagnetometerMatrixNED(float fR[][3], float fBc[])
{
// local variables
float fmodBxy; // modulus of the x, y magnetometer readings
// compute the magnitude of the horizontal (x and y) magnetometer reading
fmodBxy = sqrtf(fBc[X] * fBc[X] + fBc[Y] * fBc[Y]);
// check for zero field special case where no solution is possible
if (fmodBxy == 0.0F) {
f3x3matrixAeqI(fR);
return;
}
// define the fixed entries in the z row and column
fR[Z][X] = fR[Z][Y] = fR[X][Z] = fR[Y][Z] = 0.0F;
fR[Z][Z] = 1.0F;
// define the remaining entries
fR[X][X] = fR[Y][Y] = fBc[X] / fmodBxy;
fR[Y][X] = fBc[Y] / fmodBxy;
fR[X][Y] = -fR[Y][X];
}
// NED: 6DOF e-Compass function computing rotation matrix fR
static void feCompassNED(float fR[][3], float *pfDelta, const float fBc[], const float fGp[])
{
// local variables
float fmod[3]; // column moduli
float fmodBc; // modulus of Bc
float fGdotBc; // dot product of vectors G.Bc
float ftmp; // scratch variable
int8_t i, j; // loop counters
// set the inclination angle to zero in case it is not computed later
*pfDelta = 0.0F;
// place the un-normalized gravity and geomagnetic vectors into the rotation matrix z and x axes
for (i = X; i <= Z; i++) {
fR[i][Z] = fGp[i];
fR[i][X] = fBc[i];
}
// set y vector to vector product of z and x vectors
fR[X][Y] = fR[Y][Z] * fR[Z][X] - fR[Z][Z] * fR[Y][X];
fR[Y][Y] = fR[Z][Z] * fR[X][X] - fR[X][Z] * fR[Z][X];
fR[Z][Y] = fR[X][Z] * fR[Y][X] - fR[Y][Z] * fR[X][X];
// set x vector to vector product of y and z vectors
fR[X][X] = fR[Y][Y] * fR[Z][Z] - fR[Z][Y] * fR[Y][Z];
fR[Y][X] = fR[Z][Y] * fR[X][Z] - fR[X][Y] * fR[Z][Z];
fR[Z][X] = fR[X][Y] * fR[Y][Z] - fR[Y][Y] * fR[X][Z];
// calculate the rotation matrix column moduli
fmod[X] = sqrtf(fR[X][X] * fR[X][X] + fR[Y][X] * fR[Y][X] + fR[Z][X] * fR[Z][X]);
fmod[Y] = sqrtf(fR[X][Y] * fR[X][Y] + fR[Y][Y] * fR[Y][Y] + fR[Z][Y] * fR[Z][Y]);
fmod[Z] = sqrtf(fR[X][Z] * fR[X][Z] + fR[Y][Z] * fR[Y][Z] + fR[Z][Z] * fR[Z][Z]);
// normalize the rotation matrix columns
if (!((fmod[X] == 0.0F) || (fmod[Y] == 0.0F) || (fmod[Z] == 0.0F))) {
// loop over columns j
for (j = X; j <= Z; j++) {
ftmp = 1.0F / fmod[j];
// loop over rows i
for (i = X; i <= Z; i++) {
// normalize by the column modulus
fR[i][j] *= ftmp;
}
}
} else {
// no solution is possible to set rotation to identity matrix
f3x3matrixAeqI(fR);
return;
}
// compute the geomagnetic inclination angle
fmodBc = sqrtf(fBc[X] * fBc[X] + fBc[Y] * fBc[Y] + fBc[Z] * fBc[Z]);
fGdotBc = fGp[X] * fBc[X] + fGp[Y] * fBc[Y] + fGp[Z] * fBc[Z];
if (!((fmod[Z] == 0.0F) || (fmodBc == 0.0F))) {
*pfDelta = fasin_deg(fGdotBc / (fmod[Z] * fmodBc));
}
}
// extract the NED angles in degrees from the NED rotation matrix
static void fNEDAnglesDegFromRotationMatrix(float R[][3], float *pfPhiDeg,
float *pfTheDeg, float *pfPsiDeg, float *pfRhoDeg, float *pfChiDeg)
{
// calculate the pitch angle -90.0 <= Theta <= 90.0 deg
*pfTheDeg = fasin_deg(-R[X][Z]);
// calculate the roll angle range -180.0 <= Phi < 180.0 deg
*pfPhiDeg = fatan2_deg(R[Y][Z], R[Z][Z]);
// map +180 roll onto the functionally equivalent -180 deg roll
if (*pfPhiDeg == 180.0F) {
*pfPhiDeg = -180.0F;
}
// calculate the yaw (compass) angle 0.0 <= Psi < 360.0 deg
if (*pfTheDeg == 90.0F) {
// vertical upwards gimbal lock case
*pfPsiDeg = fatan2_deg(R[Z][Y], R[Y][Y]) + *pfPhiDeg;
} else if (*pfTheDeg == -90.0F) {
// vertical downwards gimbal lock case
*pfPsiDeg = fatan2_deg(-R[Z][Y], R[Y][Y]) - *pfPhiDeg;
} else {
// general case
*pfPsiDeg = fatan2_deg(R[X][Y], R[X][X]);
}
// map yaw angle Psi onto range 0.0 <= Psi < 360.0 deg
if (*pfPsiDeg < 0.0F) {
*pfPsiDeg += 360.0F;
}
// check for rounding errors mapping small negative angle to 360 deg
if (*pfPsiDeg >= 360.0F) {
*pfPsiDeg = 0.0F;
}
// for NED, the compass heading Rho equals the yaw angle Psi
*pfRhoDeg = *pfPsiDeg;
// calculate the tilt angle from vertical Chi (0 <= Chi <= 180 deg)
*pfChiDeg = facos_deg(R[Z][Z]);
return;
}
// computes normalized rotation quaternion from a rotation vector (deg)