1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16 package com.irurueta.navigation.inertial.calibration.intervals.thresholdfactor;
17
18 import com.irurueta.algebra.Matrix;
19 import com.irurueta.navigation.LockedException;
20 import com.irurueta.navigation.NotReadyException;
21 import com.irurueta.navigation.inertial.INSLooselyCoupledKalmanInitializerConfig;
22 import com.irurueta.navigation.inertial.INSTightlyCoupledKalmanInitializerConfig;
23 import com.irurueta.navigation.inertial.calibration.AccelerometerNoiseRootPsdSource;
24 import com.irurueta.navigation.inertial.calibration.BodyKinematicsSequence;
25 import com.irurueta.navigation.inertial.calibration.CalibrationException;
26 import com.irurueta.navigation.inertial.calibration.GyroscopeNoiseRootPsdSource;
27 import com.irurueta.navigation.inertial.calibration.StandardDeviationBodyKinematics;
28 import com.irurueta.navigation.inertial.calibration.StandardDeviationTimedBodyKinematics;
29 import com.irurueta.navigation.inertial.calibration.TimedBodyKinematics;
30 import com.irurueta.navigation.inertial.calibration.accelerometer.AccelerometerCalibratorMeasurementType;
31 import com.irurueta.navigation.inertial.calibration.accelerometer.AccelerometerNonLinearCalibrator;
32 import com.irurueta.navigation.inertial.calibration.accelerometer.KnownBiasAccelerometerCalibrator;
33 import com.irurueta.navigation.inertial.calibration.accelerometer.OrderedStandardDeviationBodyKinematicsAccelerometerCalibrator;
34 import com.irurueta.navigation.inertial.calibration.accelerometer.QualityScoredAccelerometerCalibrator;
35 import com.irurueta.navigation.inertial.calibration.accelerometer.UnknownBiasAccelerometerCalibrator;
36 import com.irurueta.navigation.inertial.calibration.accelerometer.UnorderedStandardDeviationBodyKinematicsAccelerometerCalibrator;
37 import com.irurueta.navigation.inertial.calibration.generators.AccelerometerAndGyroscopeMeasurementsGenerator;
38 import com.irurueta.navigation.inertial.calibration.generators.AccelerometerAndGyroscopeMeasurementsGeneratorListener;
39 import com.irurueta.navigation.inertial.calibration.gyroscope.AccelerometerDependentGyroscopeCalibrator;
40 import com.irurueta.navigation.inertial.calibration.gyroscope.GyroscopeCalibratorMeasurementOrSequenceType;
41 import com.irurueta.navigation.inertial.calibration.gyroscope.GyroscopeNonLinearCalibrator;
42 import com.irurueta.navigation.inertial.calibration.gyroscope.OrderedBodyKinematicsSequenceGyroscopeCalibrator;
43 import com.irurueta.navigation.inertial.calibration.gyroscope.QualityScoredGyroscopeCalibrator;
44 import com.irurueta.navigation.inertial.calibration.gyroscope.UnknownBiasGyroscopeCalibrator;
45 import com.irurueta.navigation.inertial.calibration.intervals.TriadStaticIntervalDetector;
46 import com.irurueta.units.Acceleration;
47 import com.irurueta.units.AccelerationUnit;
48 import com.irurueta.units.Time;
49
50 import java.util.ArrayList;
51 import java.util.List;
52
53
54
55
56
57
58
59
60
61
62
63
64
65 public abstract class AccelerometerAndGyroscopeIntervalDetectorThresholdFactorOptimizer extends
66 IntervalDetectorThresholdFactorOptimizer<TimedBodyKinematics,
67 AccelerometerAndGyroscopeIntervalDetectorThresholdFactorOptimizerDataSource> implements
68 AccelerometerNoiseRootPsdSource, GyroscopeNoiseRootPsdSource {
69
70
71
72
73 public static final double DEFAULT_MIN_THRESHOLD_FACTOR = 2.0;
74
75
76
77
78 public static final double DEFAULT_MAX_THRESHOLD_FACTOR = 10.0;
79
80
81
82
83 protected double minThresholdFactor = DEFAULT_MIN_THRESHOLD_FACTOR;
84
85
86
87
88 protected double maxThresholdFactor = DEFAULT_MAX_THRESHOLD_FACTOR;
89
90
91
92
93 private AccelerometerNonLinearCalibrator accelerometerCalibrator;
94
95
96
97
98 private GyroscopeNonLinearCalibrator gyroscopeCalibrator;
99
100
101
102
103 private AccelerometerAndGyroscopeMeasurementsGenerator generator;
104
105
106
107
108 private List<StandardDeviationBodyKinematics> measurements;
109
110
111
112
113 private List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences;
114
115
116
117
118
119 private QualityScoreMapper<StandardDeviationBodyKinematics> accelerometerQualityScoreMapper =
120 new DefaultAccelerometerQualityScoreMapper();
121
122
123
124
125
126 private QualityScoreMapper<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>>
127 gyroscopeQualityScoreMapper = new DefaultGyroscopeQualityScoreMapper();
128
129
130
131
132
133 private AccelerometerAndGyroscopeMseRule mseRule =
134 new DefaultAccelerometerAndGyroscopeMseRule();
135
136
137
138
139
140 private double angularSpeedNoiseRootPsd;
141
142
143
144
145
146
147
148
149 private double baseNoiseLevel;
150
151
152
153
154
155
156 private double threshold;
157
158
159
160
161 private Matrix estimatedAccelerometerCovariance;
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 private Matrix estimatedAccelerometerMa;
203
204
205
206
207
208 private double[] estimatedAccelerometerBiases;
209
210
211
212
213 private Matrix estimatedGyroscopeCovariance;
214
215
216
217
218
219 private double[] estimatedGyroscopeBiases;
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 private Matrix estimatedGyroscopeMg;
261
262
263
264
265
266
267 private Matrix estimatedGyroscopeGg;
268
269
270
271
272 protected AccelerometerAndGyroscopeIntervalDetectorThresholdFactorOptimizer() {
273 initialize();
274 }
275
276
277
278
279
280
281 protected AccelerometerAndGyroscopeIntervalDetectorThresholdFactorOptimizer(
282 final AccelerometerAndGyroscopeIntervalDetectorThresholdFactorOptimizerDataSource dataSource) {
283 super(dataSource);
284 initialize();
285 }
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300 protected AccelerometerAndGyroscopeIntervalDetectorThresholdFactorOptimizer(
301 final AccelerometerNonLinearCalibrator accelerometerCalibrator,
302 final GyroscopeNonLinearCalibrator gyroscopeCalibrator) {
303 try {
304 setAccelerometerCalibrator(accelerometerCalibrator);
305 setGyroscopeCalibrator(gyroscopeCalibrator);
306 } catch (final LockedException ignore) {
307
308 }
309 initialize();
310 }
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327 protected AccelerometerAndGyroscopeIntervalDetectorThresholdFactorOptimizer(
328 final AccelerometerAndGyroscopeIntervalDetectorThresholdFactorOptimizerDataSource dataSource,
329 final AccelerometerNonLinearCalibrator accelerometerCalibrator,
330 final GyroscopeNonLinearCalibrator gyroscopeCalibrator) {
331 super(dataSource);
332 try {
333 setAccelerometerCalibrator(accelerometerCalibrator);
334 setGyroscopeCalibrator(gyroscopeCalibrator);
335 } catch (final LockedException ignore) {
336
337 }
338 initialize();
339 }
340
341
342
343
344
345
346
347 public AccelerometerNonLinearCalibrator getAccelerometerCalibrator() {
348 return accelerometerCalibrator;
349 }
350
351
352
353
354
355
356
357
358
359 public void setAccelerometerCalibrator(
360 final AccelerometerNonLinearCalibrator accelerometerCalibrator) throws LockedException {
361 if (running) {
362 throw new LockedException();
363 }
364
365 if (accelerometerCalibrator != null && accelerometerCalibrator.getMeasurementType()
366 != AccelerometerCalibratorMeasurementType.STANDARD_DEVIATION_BODY_KINEMATICS) {
367 throw new IllegalArgumentException();
368 }
369
370 this.accelerometerCalibrator = accelerometerCalibrator;
371 }
372
373
374
375
376
377
378 public GyroscopeNonLinearCalibrator getGyroscopeCalibrator() {
379 return gyroscopeCalibrator;
380 }
381
382
383
384
385
386
387
388
389
390
391 public void setGyroscopeCalibrator(
392 final GyroscopeNonLinearCalibrator gyroscopeCalibrator) throws LockedException {
393 if (running) {
394 throw new LockedException();
395 }
396
397 if (gyroscopeCalibrator != null && gyroscopeCalibrator.getMeasurementOrSequenceType()
398 != GyroscopeCalibratorMeasurementOrSequenceType.BODY_KINEMATICS_SEQUENCE) {
399 throw new IllegalArgumentException();
400 }
401
402 this.gyroscopeCalibrator = gyroscopeCalibrator;
403 }
404
405
406
407
408
409
410
411 public QualityScoreMapper<StandardDeviationBodyKinematics> getAccelerometerQualityScoreMapper() {
412 return accelerometerQualityScoreMapper;
413 }
414
415
416
417
418
419
420
421
422
423 public void setAccelerometerQualityScoreMapper(
424 final QualityScoreMapper<StandardDeviationBodyKinematics> accelerometerQualityScoreMapper)
425 throws LockedException {
426 if (running) {
427 throw new LockedException();
428 }
429
430 this.accelerometerQualityScoreMapper = accelerometerQualityScoreMapper;
431 }
432
433
434
435
436
437
438
439 public QualityScoreMapper<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>>
440 getGyroscopeQualityScoreMapper() {
441 return gyroscopeQualityScoreMapper;
442 }
443
444
445
446
447
448
449
450
451
452 public void setGyroscopeQualityScoreMapper(
453 final QualityScoreMapper<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>>
454 gyroscopeQualityScoreMapper) throws LockedException {
455 if (running) {
456 throw new LockedException();
457 }
458
459 this.gyroscopeQualityScoreMapper = gyroscopeQualityScoreMapper;
460 }
461
462
463
464
465
466
467
468
469 public AccelerometerAndGyroscopeMseRule getMseRule() {
470 return mseRule;
471 }
472
473
474
475
476
477
478
479
480
481 public void setMseRule(final AccelerometerAndGyroscopeMseRule mseRule) throws LockedException {
482 if (running) {
483 throw new LockedException();
484 }
485
486 this.mseRule = mseRule;
487 }
488
489
490
491
492
493
494 public double getMinThresholdFactor() {
495 return minThresholdFactor;
496 }
497
498
499
500
501
502
503 public double getMaxThresholdFactor() {
504 return maxThresholdFactor;
505 }
506
507
508
509
510
511
512
513
514
515
516
517 public void setThresholdFactorRange(final double minThresholdFactor, final double maxThresholdFactor)
518 throws LockedException {
519 if (running) {
520 throw new LockedException();
521 }
522 if (minThresholdFactor < 0.0 || maxThresholdFactor < 0.0 || minThresholdFactor >= maxThresholdFactor) {
523 throw new IllegalArgumentException();
524 }
525
526 this.minThresholdFactor = minThresholdFactor;
527 this.maxThresholdFactor = maxThresholdFactor;
528 }
529
530
531
532
533
534
535 @Override
536 public boolean isReady() {
537 return super.isReady() && accelerometerCalibrator != null
538 && gyroscopeCalibrator != null
539 && accelerometerQualityScoreMapper != null
540 && gyroscopeQualityScoreMapper != null
541 && mseRule != null;
542 }
543
544
545
546
547
548
549
550 public double getTimeInterval() {
551 return generator.getTimeInterval();
552 }
553
554
555
556
557
558
559
560
561
562 public void setTimeInterval(final double timeInterval) throws LockedException {
563 if (running) {
564 throw new LockedException();
565 }
566
567 generator.setTimeInterval(timeInterval);
568 }
569
570
571
572
573
574
575
576 public Time getTimeIntervalAsTime() {
577 return generator.getTimeIntervalAsTime();
578 }
579
580
581
582
583
584
585
586 public void getTimeIntervalAsTime(final Time result) {
587 generator.getTimeIntervalAsTime(result);
588 }
589
590
591
592
593
594
595
596
597
598 public void setTimeInterval(final Time timeInterval) throws LockedException {
599 if (running) {
600 throw new LockedException();
601 }
602
603 generator.setTimeInterval(timeInterval);
604 }
605
606
607
608
609
610
611
612
613
614
615 public int getMinStaticSamples() {
616 return generator.getMinStaticSamples();
617 }
618
619
620
621
622
623
624
625
626
627
628
629
630 public void setMinStaticSamples(final int minStaticSamples) throws LockedException {
631 if (running) {
632 throw new LockedException();
633 }
634
635 generator.setMinStaticSamples(minStaticSamples);
636 }
637
638
639
640
641
642
643
644 public int getMaxDynamicSamples() {
645 return generator.getMaxDynamicSamples();
646 }
647
648
649
650
651
652
653
654
655
656
657 public void setMaxDynamicSamples(final int maxDynamicSamples) throws LockedException {
658 if (running) {
659 throw new LockedException();
660 }
661
662 generator.setMaxDynamicSamples(maxDynamicSamples);
663 }
664
665
666
667
668
669
670
671
672 public int getWindowSize() {
673 return generator.getWindowSize();
674 }
675
676
677
678
679
680
681
682
683
684
685
686
687 public void setWindowSize(final int windowSize) throws LockedException {
688 if (running) {
689 throw new LockedException();
690 }
691
692 generator.setWindowSize(windowSize);
693 }
694
695
696
697
698
699
700
701
702 public int getInitialStaticSamples() {
703 return generator.getInitialStaticSamples();
704 }
705
706
707
708
709
710
711
712
713
714
715
716 public void setInitialStaticSamples(final int initialStaticSamples) throws LockedException {
717 if (running) {
718 throw new LockedException();
719 }
720
721 generator.setInitialStaticSamples(initialStaticSamples);
722 }
723
724
725
726
727
728
729
730
731
732 public double getInstantaneousNoiseLevelFactor() {
733 return generator.getInstantaneousNoiseLevelFactor();
734 }
735
736
737
738
739
740
741
742
743
744
745
746
747
748 public void setInstantaneousNoiseLevelFactor(final double instantaneousNoiseLevelFactor) throws LockedException {
749 if (running) {
750 throw new LockedException();
751 }
752
753 generator.setInstantaneousNoiseLevelFactor(instantaneousNoiseLevelFactor);
754 }
755
756
757
758
759
760
761
762
763
764 public double getBaseNoiseLevelAbsoluteThreshold() {
765 return generator.getBaseNoiseLevelAbsoluteThreshold();
766 }
767
768
769
770
771
772
773
774
775
776
777
778
779 public void setBaseNoiseLevelAbsoluteThreshold(final double baseNoiseLevelAbsoluteThreshold)
780 throws LockedException {
781 if (running) {
782 throw new LockedException();
783 }
784
785 generator.setBaseNoiseLevelAbsoluteThreshold(baseNoiseLevelAbsoluteThreshold);
786 }
787
788
789
790
791
792
793
794
795 public Acceleration getBaseNoiseLevelAbsoluteThresholdAsMeasurement() {
796 return generator.getBaseNoiseLevelAbsoluteThresholdAsMeasurement();
797 }
798
799
800
801
802
803
804
805 public void getBaseNoiseLevelAbsoluteThresholdAsMeasurement(final Acceleration result) {
806 generator.getBaseNoiseLevelAbsoluteThresholdAsMeasurement(result);
807 }
808
809
810
811
812
813
814
815
816
817
818
819 public void setBaseNoiseLevelAbsoluteThreshold(final Acceleration baseNoiseLevelAbsoluteThreshold)
820 throws LockedException {
821 if (running) {
822 throw new LockedException();
823 }
824
825 generator.setBaseNoiseLevelAbsoluteThreshold(baseNoiseLevelAbsoluteThreshold);
826 }
827
828
829
830
831
832
833
834
835
836
837
838 public double getAccelerometerBaseNoiseLevel() {
839 return baseNoiseLevel;
840 }
841
842
843
844
845
846
847
848
849
850
851 public Acceleration getAccelerometerBaseNoiseLevelAsMeasurement() {
852 return createMeasurement(baseNoiseLevel, getDefaultUnit());
853 }
854
855
856
857
858
859
860
861
862
863 public void getAccelerometerBaseNoiseLevelAsMeasurement(final Acceleration result) {
864 result.setValue(baseNoiseLevel);
865 result.setUnit(getDefaultUnit());
866 }
867
868
869
870
871
872
873
874 public double getGyroscopeBaseNoiseLevelPsd() {
875 return angularSpeedNoiseRootPsd * angularSpeedNoiseRootPsd;
876 }
877
878
879
880
881
882
883
884 @Override
885 public double getGyroscopeBaseNoiseLevelRootPsd() {
886 return angularSpeedNoiseRootPsd;
887 }
888
889
890
891
892
893
894
895 public double getAccelerometerBaseNoiseLevelPsd() {
896 return baseNoiseLevel * baseNoiseLevel * getTimeInterval();
897 }
898
899
900
901
902
903
904
905 @Override
906 public double getAccelerometerBaseNoiseLevelRootPsd() {
907 return baseNoiseLevel * Math.sqrt(getTimeInterval());
908 }
909
910
911
912
913
914
915
916
917
918 public double getThreshold() {
919 return threshold;
920 }
921
922
923
924
925
926
927
928
929 public Acceleration getThresholdAsMeasurement() {
930 return createMeasurement(threshold, getDefaultUnit());
931 }
932
933
934
935
936
937
938
939 public void getThresholdAsMeasurement(final Acceleration result) {
940 result.setValue(threshold);
941 result.setUnit(getDefaultUnit());
942 }
943
944
945
946
947
948
949
950
951
952
953 public Double getEstimatedAccelerometerBiasStandardDeviationNorm() {
954 return estimatedAccelerometerCovariance != null
955 ? Math.sqrt(getEstimatedAccelerometerBiasFxVariance()
956 + getEstimatedAccelerometerBiasFyVariance()
957 + getEstimatedAccelerometerBiasFzVariance())
958 : null;
959 }
960
961
962
963
964
965
966 public Double getEstimatedAccelerometerBiasFxVariance() {
967 return estimatedAccelerometerCovariance != null
968 ? estimatedAccelerometerCovariance.getElementAt(0, 0) : null;
969 }
970
971
972
973
974
975
976 public Double getEstimatedAccelerometerBiasFyVariance() {
977 return estimatedAccelerometerCovariance != null
978 ? estimatedAccelerometerCovariance.getElementAt(1, 1) : null;
979 }
980
981
982
983
984
985
986 public Double getEstimatedAccelerometerBiasFzVariance() {
987 return estimatedAccelerometerCovariance != null
988 ? estimatedAccelerometerCovariance.getElementAt(2, 2) : null;
989 }
990
991
992
993
994
995
996
997 public double[] getEstimatedAccelerometerBiases() {
998 return estimatedAccelerometerBiases;
999 }
1000
1001
1002
1003
1004
1005
1006
1007
1008
1009
1010
1011
1012
1013
1014
1015
1016
1017
1018
1019
1020
1021
1022
1023
1024
1025
1026
1027
1028
1029
1030
1031
1032
1033
1034
1035
1036
1037
1038
1039
1040
1041
1042
1043 public Matrix getEstimatedAccelerometerMa() {
1044 return estimatedAccelerometerMa;
1045 }
1046
1047
1048
1049
1050
1051
1052
1053
1054
1055
1056 public Double getEstimatedGyroscopeBiasStandardDeviationNorm() {
1057 return estimatedGyroscopeCovariance != null
1058 ? Math.sqrt(getEstimatedGyroscopeBiasXVariance()
1059 + getEstimatedGyroscopeBiasYVariance()
1060 + getEstimatedGyroscopeBiasZVariance())
1061 : null;
1062 }
1063
1064
1065
1066
1067
1068
1069 public Double getEstimatedGyroscopeBiasXVariance() {
1070 return estimatedGyroscopeCovariance != null
1071 ? estimatedGyroscopeCovariance.getElementAt(0, 0) : null;
1072 }
1073
1074
1075
1076
1077
1078
1079 public Double getEstimatedGyroscopeBiasYVariance() {
1080 return estimatedGyroscopeCovariance != null
1081 ? estimatedGyroscopeCovariance.getElementAt(1, 1) : null;
1082 }
1083
1084
1085
1086
1087
1088
1089 public Double getEstimatedGyroscopeBiasZVariance() {
1090 return estimatedGyroscopeCovariance != null
1091 ? estimatedGyroscopeCovariance.getElementAt(2, 2) : null;
1092 }
1093
1094
1095
1096
1097
1098
1099
1100 public double[] getEstimatedGyroscopeBiases() {
1101 return estimatedGyroscopeBiases;
1102 }
1103
1104
1105
1106
1107
1108
1109
1110
1111
1112
1113
1114
1115
1116
1117
1118
1119
1120
1121
1122
1123
1124
1125
1126
1127
1128
1129
1130
1131
1132
1133
1134
1135
1136
1137
1138
1139
1140
1141
1142
1143
1144
1145 public Matrix getEstimatedGyroscopeMg() {
1146 return estimatedGyroscopeMg;
1147 }
1148
1149
1150
1151
1152
1153
1154
1155 public Matrix getEstimatedGyroscopeGg() {
1156 return estimatedGyroscopeGg;
1157 }
1158
1159
1160
1161
1162
1163
1164
1165
1166
1167
1168
1169
1170
1171 protected double evaluateForThresholdFactor(final double thresholdFactor) throws LockedException,
1172 CalibrationException, NotReadyException, IntervalDetectorThresholdFactorOptimizerException {
1173 if (measurements == null) {
1174 measurements = new ArrayList<>();
1175 } else {
1176 measurements.clear();
1177 }
1178
1179 if (sequences == null) {
1180 sequences = new ArrayList<>();
1181 } else {
1182 sequences.clear();
1183 }
1184
1185 generator.reset();
1186 generator.setThresholdFactor(thresholdFactor);
1187
1188 var count = dataSource.count();
1189 var failed = false;
1190 for (var i = 0; i < count; i++) {
1191 final var timedBodyKinematics = dataSource.getAt(i);
1192 if (!generator.process(timedBodyKinematics)) {
1193 failed = true;
1194 break;
1195 }
1196 }
1197
1198 if (failed || generator.getStatus() == TriadStaticIntervalDetector.Status.FAILED) {
1199
1200 return Double.MAX_VALUE;
1201 }
1202
1203
1204 if (measurements.size() < accelerometerCalibrator.getMinimumRequiredMeasurements()
1205 || sequences.size() < gyroscopeCalibrator.getMinimumRequiredMeasurementsOrSequences()) {
1206 return Double.MAX_VALUE;
1207 }
1208
1209
1210 switch (accelerometerCalibrator.getMeasurementType()) {
1211 case STANDARD_DEVIATION_BODY_KINEMATICS:
1212 if (accelerometerCalibrator.isOrderedMeasurementsRequired()) {
1213 final var calibrator =
1214 (OrderedStandardDeviationBodyKinematicsAccelerometerCalibrator) accelerometerCalibrator;
1215
1216 calibrator.setMeasurements(measurements);
1217
1218 } else {
1219 final var calibrator =
1220 (UnorderedStandardDeviationBodyKinematicsAccelerometerCalibrator) accelerometerCalibrator;
1221
1222 calibrator.setMeasurements(measurements);
1223 }
1224
1225 if (accelerometerCalibrator.isQualityScoresRequired()) {
1226 final var calibrator = (QualityScoredAccelerometerCalibrator) accelerometerCalibrator;
1227
1228 final var size = measurements.size();
1229 final var qualityScores = new double[size];
1230 for (var i = 0; i < size; i++) {
1231 qualityScores[i] = accelerometerQualityScoreMapper.map(measurements.get(i));
1232 }
1233 calibrator.setQualityScores(qualityScores);
1234 }
1235 break;
1236 case FRAME_BODY_KINEMATICS, STANDARD_DEVIATION_FRAME_BODY_KINEMATICS:
1237
1238 default:
1239 throw new IntervalDetectorThresholdFactorOptimizerException();
1240 }
1241
1242 if (gyroscopeCalibrator.getMeasurementOrSequenceType()
1243 == GyroscopeCalibratorMeasurementOrSequenceType.BODY_KINEMATICS_SEQUENCE) {
1244 final var calibrator = (OrderedBodyKinematicsSequenceGyroscopeCalibrator) gyroscopeCalibrator;
1245
1246 calibrator.setSequences(sequences);
1247 } else {
1248 throw new IntervalDetectorThresholdFactorOptimizerException();
1249 }
1250
1251 if (gyroscopeCalibrator.isQualityScoresRequired()) {
1252 final var calibrator = (QualityScoredGyroscopeCalibrator) gyroscopeCalibrator;
1253
1254 final var size = sequences.size();
1255 final var qualityScores = new double[size];
1256 for (var i = 0; i < size; i++) {
1257 qualityScores[i] = gyroscopeQualityScoreMapper.map(sequences.get(i));
1258 }
1259 calibrator.setQualityScores(qualityScores);
1260 }
1261
1262 accelerometerCalibrator.calibrate();
1263
1264
1265
1266 if (gyroscopeCalibrator instanceof AccelerometerDependentGyroscopeCalibrator accelGyroCalibrator) {
1267
1268 final double[] bias;
1269 if (accelerometerCalibrator instanceof UnknownBiasAccelerometerCalibrator unknownBiasAccelerometerCalibrator) {
1270 bias = unknownBiasAccelerometerCalibrator.getEstimatedBiases();
1271
1272 } else if (accelerometerCalibrator instanceof KnownBiasAccelerometerCalibrator knownBiasAccelerometerCalibrator) {
1273 bias = knownBiasAccelerometerCalibrator.getBias();
1274 } else {
1275 bias = null;
1276 }
1277
1278 if (bias != null) {
1279 accelGyroCalibrator.setAccelerometerBias(bias);
1280 accelGyroCalibrator.setAccelerometerMa(accelerometerCalibrator.getEstimatedMa());
1281 }
1282 }
1283
1284 gyroscopeCalibrator.calibrate();
1285
1286 final var accelerometerMse = accelerometerCalibrator.getEstimatedMse();
1287 final var gyroscopeMse = gyroscopeCalibrator.getEstimatedMse();
1288
1289
1290 final var mse = mseRule.evaluate(accelerometerMse, gyroscopeMse);
1291 if (mse < minMse) {
1292 keepBestResult(mse, thresholdFactor);
1293 }
1294 return mse;
1295 }
1296
1297
1298
1299
1300
1301
1302 private void initialize() {
1303 final var generatorListener = new AccelerometerAndGyroscopeMeasurementsGeneratorListener() {
1304 @Override
1305 public void onInitializationStarted(final AccelerometerAndGyroscopeMeasurementsGenerator generator) {
1306
1307 }
1308
1309 @Override
1310 public void onInitializationCompleted(
1311 final AccelerometerAndGyroscopeMeasurementsGenerator generator,
1312 final double accelerometerBaseNoiseLevel) {
1313
1314 }
1315
1316 @Override
1317 public void onError(
1318 final AccelerometerAndGyroscopeMeasurementsGenerator generator,
1319 final TriadStaticIntervalDetector.ErrorReason reason) {
1320
1321 }
1322
1323 @Override
1324 public void onStaticIntervalDetected(final AccelerometerAndGyroscopeMeasurementsGenerator generator) {
1325
1326 }
1327
1328 @Override
1329 public void onDynamicIntervalDetected(final AccelerometerAndGyroscopeMeasurementsGenerator generator) {
1330
1331 }
1332
1333 @Override
1334 public void onStaticIntervalSkipped(final AccelerometerAndGyroscopeMeasurementsGenerator generator) {
1335
1336 }
1337
1338 @Override
1339 public void onDynamicIntervalSkipped(final AccelerometerAndGyroscopeMeasurementsGenerator generator) {
1340
1341 }
1342
1343 @Override
1344 public void onGeneratedAccelerometerMeasurement(
1345 final AccelerometerAndGyroscopeMeasurementsGenerator generator,
1346 final StandardDeviationBodyKinematics measurement) {
1347 measurements.add(measurement);
1348 }
1349
1350 @Override
1351 public void onGeneratedGyroscopeMeasurement(
1352 final AccelerometerAndGyroscopeMeasurementsGenerator generator,
1353 final BodyKinematicsSequence<StandardDeviationTimedBodyKinematics> sequence) {
1354 sequences.add(sequence);
1355 }
1356
1357 @Override
1358 public void onReset(final AccelerometerAndGyroscopeMeasurementsGenerator generator) {
1359
1360 }
1361 };
1362
1363 generator = new AccelerometerAndGyroscopeMeasurementsGenerator(generatorListener);
1364 }
1365
1366
1367
1368
1369
1370
1371
1372 private void keepBestResult(final double mse, final double thresholdFactor) {
1373 minMse = mse;
1374 optimalThresholdFactor = thresholdFactor;
1375
1376 angularSpeedNoiseRootPsd = generator.getGyroscopeBaseNoiseLevelRootPsd();
1377 baseNoiseLevel = generator.getAccelerometerBaseNoiseLevel();
1378 threshold = generator.getThreshold();
1379
1380 if (estimatedAccelerometerCovariance == null) {
1381 estimatedAccelerometerCovariance = new Matrix(accelerometerCalibrator.getEstimatedCovariance());
1382 } else {
1383 estimatedAccelerometerCovariance.copyFrom(accelerometerCalibrator.getEstimatedCovariance());
1384 }
1385 if (estimatedAccelerometerMa == null) {
1386 estimatedAccelerometerMa = new Matrix(accelerometerCalibrator.getEstimatedMa());
1387 } else {
1388 estimatedAccelerometerMa.copyFrom(accelerometerCalibrator.getEstimatedMa());
1389 }
1390 if (accelerometerCalibrator instanceof UnknownBiasAccelerometerCalibrator unknownBiasAccelerometerCalibrator) {
1391 estimatedAccelerometerBiases = unknownBiasAccelerometerCalibrator.getEstimatedBiases();
1392 } else if (accelerometerCalibrator instanceof
1393 KnownBiasAccelerometerCalibrator knownBiasAccelerometerCalibrator) {
1394 estimatedAccelerometerBiases = knownBiasAccelerometerCalibrator.getBias();
1395 }
1396
1397 if (estimatedGyroscopeCovariance == null) {
1398 estimatedGyroscopeCovariance = new Matrix(gyroscopeCalibrator.getEstimatedCovariance());
1399 } else {
1400 estimatedGyroscopeCovariance.copyFrom(gyroscopeCalibrator.getEstimatedCovariance());
1401 }
1402 if (estimatedGyroscopeMg == null) {
1403 estimatedGyroscopeMg = new Matrix(gyroscopeCalibrator.getEstimatedMg());
1404 } else {
1405 estimatedGyroscopeMg.copyFrom(gyroscopeCalibrator.getEstimatedMg());
1406 }
1407 if (estimatedGyroscopeGg == null) {
1408 estimatedGyroscopeGg = new Matrix(gyroscopeCalibrator.getEstimatedGg());
1409 } else {
1410 estimatedGyroscopeGg.copyFrom(gyroscopeCalibrator.getEstimatedGg());
1411 }
1412 if (gyroscopeCalibrator instanceof UnknownBiasGyroscopeCalibrator unknownBiasGyroscopeCalibrator) {
1413 estimatedGyroscopeBiases = unknownBiasGyroscopeCalibrator.getEstimatedBiases();
1414 } else if (gyroscopeCalibrator instanceof KnownBiasAccelerometerCalibrator knownBiasAccelerometerCalibrator) {
1415 estimatedGyroscopeBiases = knownBiasAccelerometerCalibrator.getBias();
1416 }
1417 }
1418
1419
1420
1421
1422
1423
1424
1425
1426 private Acceleration createMeasurement(final double value, final AccelerationUnit unit) {
1427 return new Acceleration(value, unit);
1428 }
1429
1430
1431
1432
1433
1434
1435
1436 private AccelerationUnit getDefaultUnit() {
1437 return AccelerationUnit.METERS_PER_SQUARED_SECOND;
1438 }
1439 }