View Javadoc
1   /*
2    * Copyright (C) 2021 Alberto Irurueta Carro (alberto@irurueta.com)
3    *
4    * Licensed under the Apache License, Version 2.0 (the "License");
5    * you may not use this file except in compliance with the License.
6    * You may obtain a copy of the License at
7    *
8    *         http://www.apache.org/licenses/LICENSE-2.0
9    *
10   * Unless required by applicable law or agreed to in writing, software
11   * distributed under the License is distributed on an "AS IS" BASIS,
12   * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13   * See the License for the specific language governing permissions and
14   * limitations under the License.
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   * Optimizes the threshold factor for interval detection of accelerometer and gyroscope
55   * data based on results of calibration.
56   * Implementations of this class will attempt to find the best threshold factor
57   * between the provided range of values.
58   * Only accelerometer calibrators based on unknown orientation are supported (in other terms,
59   * calibrators must be {@link AccelerometerNonLinearCalibrator} and must support
60   * {@link AccelerometerCalibratorMeasurementType#STANDARD_DEVIATION_BODY_KINEMATICS}).
61   * Only gyroscope calibrators based on unknown orientation are supported (in other terms,
62   * calibrators must be {@link GyroscopeNonLinearCalibrator} and must support
63   * {@link GyroscopeCalibratorMeasurementOrSequenceType#BODY_KINEMATICS_SEQUENCE}).
64   */
65  public abstract class AccelerometerAndGyroscopeIntervalDetectorThresholdFactorOptimizer extends
66          IntervalDetectorThresholdFactorOptimizer<TimedBodyKinematics,
67                  AccelerometerAndGyroscopeIntervalDetectorThresholdFactorOptimizerDataSource> implements
68          AccelerometerNoiseRootPsdSource, GyroscopeNoiseRootPsdSource {
69  
70      /**
71       * Default minimum threshold factor.
72       */
73      public static final double DEFAULT_MIN_THRESHOLD_FACTOR = 2.0;
74  
75      /**
76       * Default maximum threshold factor.
77       */
78      public static final double DEFAULT_MAX_THRESHOLD_FACTOR = 10.0;
79  
80      /**
81       * Minimum threshold factor.
82       */
83      protected double minThresholdFactor = DEFAULT_MIN_THRESHOLD_FACTOR;
84  
85      /**
86       * Maximum threshold factor.
87       */
88      protected double maxThresholdFactor = DEFAULT_MAX_THRESHOLD_FACTOR;
89  
90      /**
91       * Accelerometer calibrator.
92       */
93      private AccelerometerNonLinearCalibrator accelerometerCalibrator;
94  
95      /**
96       * Gyroscope calibrator.
97       */
98      private GyroscopeNonLinearCalibrator gyroscopeCalibrator;
99  
100     /**
101      * A measurement generator for accelerometer and gyroscope calibrators.
102      */
103     private AccelerometerAndGyroscopeMeasurementsGenerator generator;
104 
105     /**
106      * Generated measurements to be used for accelerometer calibration.
107      */
108     private List<StandardDeviationBodyKinematics> measurements;
109 
110     /**
111      * Generated sequences to be used for gyroscope calibration.
112      */
113     private List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences;
114 
115     /**
116      * Mapper to convert {@link StandardDeviationBodyKinematics} measurements into
117      * quality scores.
118      */
119     private QualityScoreMapper<StandardDeviationBodyKinematics> accelerometerQualityScoreMapper =
120             new DefaultAccelerometerQualityScoreMapper();
121 
122     /**
123      * Mapper to convert {@link BodyKinematicsSequence} sequences of {@link StandardDeviationTimedBodyKinematics}
124      * into quality scores.
125      */
126     private QualityScoreMapper<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>>
127             gyroscopeQualityScoreMapper = new DefaultGyroscopeQualityScoreMapper();
128 
129     /**
130      * Rule to convert accelerometer and gyroscope MSE values into a single global
131      * MSE value.
132      */
133     private AccelerometerAndGyroscopeMseRule mseRule =
134             new DefaultAccelerometerAndGyroscopeMseRule();
135 
136     /**
137      * Estimated norm of gyroscope noise root PSD (Power Spectral Density)
138      * expressed as (rad * s^-0.5).
139      */
140     private double angularSpeedNoiseRootPsd;
141 
142     /**
143      * Accelerometer base noise level that has been detected during
144      * initialization of the best solution that has been found expressed in
145      * meters per squared second (m/s^2).
146      * This is equal to the standard deviation of the accelerometer measurements
147      * during the initialization phase.
148      */
149     private double baseNoiseLevel;
150 
151     /**
152      * Threshold to determine static/dynamic period changes expressed in
153      * meters per squared second (m/s^2) for the best calibration solution that
154      * has been found.
155      */
156     private double threshold;
157 
158     /**
159      * Estimated covariance matrix for estimated accelerometer parameters.
160      */
161     private Matrix estimatedAccelerometerCovariance;
162 
163     /**
164      * Estimated accelerometer scale factors and cross-coupling errors.
165      * This is the product of matrix Ta containing cross-coupling errors and Ka
166      * containing scaling factors.
167      * So that:
168      * <pre>
169      *     Ma = [sx    mxy  mxz] = Ta*Ka
170      *          [myx   sy   myz]
171      *          [mzx   mzy  sz ]
172      * </pre>
173      * Where:
174      * <pre>
175      *     Ka = [sx 0   0 ]
176      *          [0  sy  0 ]
177      *          [0  0   sz]
178      * </pre>
179      * and
180      * <pre>
181      *     Ta = [1          -alphaXy    alphaXz ]
182      *          [alphaYx    1           -alphaYz]
183      *          [-alphaZx   alphaZy     1       ]
184      * </pre>
185      * Hence:
186      * <pre>
187      *     Ma = [sx    mxy  mxz] = Ta*Ka =  [sx             -sy * alphaXy   sz * alphaXz ]
188      *          [myx   sy   myz]            [sx * alphaYx   sy              -sz * alphaYz]
189      *          [mzx   mzy  sz ]            [-sx * alphaZx  sy * alphaZy    sz           ]
190      * </pre>
191      * This instance allows any 3x3 matrix. However, typically alphaYx, alphaZx and alphaZy
192      * are considered to be zero if the accelerometer z-axis is assumed to be the same
193      * as the body z-axis. When this is assumed, myx = mzx = mzy = 0 and the Ma matrix
194      * becomes upper diagonal:
195      * <pre>
196      *     Ma = [sx    mxy  mxz]
197      *          [0     sy   myz]
198      *          [0     0    sz ]
199      * </pre>
200      * Values of this matrix are unit-less.
201      */
202     private Matrix estimatedAccelerometerMa;
203 
204     /**
205      * Estimated accelerometer biases for each IMU axis expressed in meter per squared
206      * second (m/s^2).
207      */
208     private double[] estimatedAccelerometerBiases;
209 
210     /**
211      * Estimated covariance matrix for estimated gyroscope parameters.
212      */
213     private Matrix estimatedGyroscopeCovariance;
214 
215     /**
216      * Estimated angular rate biases for each IMU axis expressed in radians per
217      * second (rad/s).
218      */
219     private double[] estimatedGyroscopeBiases;
220 
221     /**
222      * Estimated gyroscope scale factors and cross-coupling errors.
223      * This is the product of matrix Tg containing cross-coupling errors and Kg
224      * containing scaling factors.
225      * So that:
226      * <pre>
227      *     Mg = [sx    mxy  mxz] = Tg*Kg
228      *          [myx   sy   myz]
229      *          [mzx   mzy  sz ]
230      * </pre>
231      * Where:
232      * <pre>
233      *     Kg = [sx 0   0 ]
234      *          [0  sy  0 ]
235      *          [0  0   sz]
236      * </pre>
237      * and
238      * <pre>
239      *     Tg = [1          -alphaXy    alphaXz ]
240      *          [alphaYx    1           -alphaYz]
241      *          [-alphaZx   alphaZy     1       ]
242      * </pre>
243      * Hence:
244      * <pre>
245      *     Mg = [sx    mxy  mxz] = Tg*Kg =  [sx             -sy * alphaXy   sz * alphaXz ]
246      *          [myx   sy   myz]            [sx * alphaYx   sy              -sz * alphaYz]
247      *          [mzx   mzy  sz ]            [-sx * alphaZx  sy * alphaZy    sz           ]
248      * </pre>
249      * This instance allows any 3x3 matrix. However, typically alphaYx, alphaZx and alphaZy
250      * are considered to be zero if the gyroscope z-axis is assumed to be the same
251      * as the body z-axis. When this is assumed, myx = mzx = mzy = 0 and the Mg matrix
252      * becomes upper diagonal:
253      * <pre>
254      *     Mg = [sx    mxy  mxz]
255      *          [0     sy   myz]
256      *          [0     0    sz ]
257      * </pre>
258      * Values of this matrix are unit-less.
259      */
260     private Matrix estimatedGyroscopeMg;
261 
262     /**
263      * Estimated G-dependent cross-biases introduced on the gyroscope by the
264      * specific forces sensed by the accelerometer.
265      * This instance allows any 3x3 matrix.
266      */
267     private Matrix estimatedGyroscopeGg;
268 
269     /**
270      * Constructor.
271      */
272     protected AccelerometerAndGyroscopeIntervalDetectorThresholdFactorOptimizer() {
273         initialize();
274     }
275 
276     /**
277      * Constructor.
278      *
279      * @param dataSource instance in charge of retrieving data for this optimizer.
280      */
281     protected AccelerometerAndGyroscopeIntervalDetectorThresholdFactorOptimizer(
282             final AccelerometerAndGyroscopeIntervalDetectorThresholdFactorOptimizerDataSource dataSource) {
283         super(dataSource);
284         initialize();
285     }
286 
287     /**
288      * Constructor.
289      *
290      * @param accelerometerCalibrator an accelerometer calibrator to be used to
291      *                                optimize its Mean Square Error (MSE).
292      * @param gyroscopeCalibrator     a gyroscope calibrator to be used to optimize
293      *                                its Mean Square Error (MSE).
294      * @throws IllegalArgumentException if accelerometer calibrator does not use
295      *                                  {@link StandardDeviationBodyKinematics} measurements
296      *                                  or if gyroscope calibrator does not use
297      *                                  {@link BodyKinematicsSequence} sequences of
298      *                                  {@link StandardDeviationTimedBodyKinematics}.
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             // never happens
308         }
309         initialize();
310     }
311 
312     /**
313      * Constructor.
314      *
315      * @param dataSource              instance in charge of retrieving data for this
316      *                                optimizer.
317      * @param accelerometerCalibrator an accelerometer calibrator to be used to
318      *                                optimize its Mean Square Error (MSE).
319      * @param gyroscopeCalibrator     a gyroscope calibrator to be used to optimize
320      *                                its Mean Square Error (MSE).
321      * @throws IllegalArgumentException if accelerometer calibrator does not use
322      *                                  {@link StandardDeviationBodyKinematics} measurements
323      *                                  or if gyroscope calibrator does not use
324      *                                  {@link BodyKinematicsSequence} sequences of
325      *                                  {@link StandardDeviationTimedBodyKinematics}.
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             // never happens
337         }
338         initialize();
339     }
340 
341 
342     /**
343      * Gets provided accelerometer calibrator to be used to optimize its Mean Square Error (MSE).
344      *
345      * @return accelerometer calibrator to be used to optimize its MSE.
346      */
347     public AccelerometerNonLinearCalibrator getAccelerometerCalibrator() {
348         return accelerometerCalibrator;
349     }
350 
351     /**
352      * Sets accelerometer calibrator to be used to optimize its Mean Square Error (MSE).
353      *
354      * @param accelerometerCalibrator accelerometer calibrator to be used to optimize its MSE.
355      * @throws LockedException          if optimizer is already running.
356      * @throws IllegalArgumentException if accelerometer calibrator does not use
357      *                                  {@link StandardDeviationBodyKinematics} measurements.
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      * Gets provided gyroscope calibrator to be used to optimize its Mean Square Error (MSE).
375      *
376      * @return gyroscope calibrator to be used to optimize its MSE.
377      */
378     public GyroscopeNonLinearCalibrator getGyroscopeCalibrator() {
379         return gyroscopeCalibrator;
380     }
381 
382     /**
383      * Sets gyroscope calibrator to be used to optimize its Mean Square Error (MSE).
384      *
385      * @param gyroscopeCalibrator gyroscope calibrator to be use dto optimize its MSE.
386      * @throws LockedException          if optimizer is already running.
387      * @throws IllegalArgumentException if gyroscope calibrator does not use
388      *                                  {@link BodyKinematicsSequence} sequences of
389      *                                  {@link StandardDeviationTimedBodyKinematics}.
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      * Gets mapper to convert {@link StandardDeviationBodyKinematics} accelerometer measurements
407      * into quality scores.
408      *
409      * @return mapper to convert accelerometer measurements into quality scores.
410      */
411     public QualityScoreMapper<StandardDeviationBodyKinematics> getAccelerometerQualityScoreMapper() {
412         return accelerometerQualityScoreMapper;
413     }
414 
415     /**
416      * Sets mapper to convert {@link StandardDeviationBodyKinematics} accelerometer measurements
417      * into quality scores.
418      *
419      * @param accelerometerQualityScoreMapper mapper to convert accelerometer measurements
420      *                                        into quality scores.
421      * @throws LockedException if optimizer is already running.
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      * Gets mapper to convert {@link BodyKinematicsSequence} gyroscope sequences of
435      * {@link StandardDeviationTimedBodyKinematics} into quality scores.
436      *
437      * @return mapper to convert gyroscope sequences into quality scores.
438      */
439     public QualityScoreMapper<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>>
440     getGyroscopeQualityScoreMapper() {
441         return gyroscopeQualityScoreMapper;
442     }
443 
444     /**
445      * Sets mapper to convert {@link BodyKinematicsSequence} gyroscope sequences of
446      * {@link StandardDeviationTimedBodyKinematics} into quality scores.
447      *
448      * @param gyroscopeQualityScoreMapper mapper to convert gyroscope sequences
449      *                                    into quality scores.
450      * @throws LockedException if optimizer is already running.
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      * Gets rule to convert accelerometer and gyroscope MSE values into a single
464      * global MSE value.
465      *
466      * @return rule to convert accelerometer and gyroscope MSE values into a
467      * single global MSE value.
468      */
469     public AccelerometerAndGyroscopeMseRule getMseRule() {
470         return mseRule;
471     }
472 
473     /**
474      * Sets rule to convert accelerometer and gyroscope MSE values into a single
475      * global MSE value.
476      *
477      * @param mseRule rule to convert accelerometer and gyroscope MSE values into
478      *                a single global MSE value.
479      * @throws LockedException if optimizer is already running.
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      * Gets the minimum threshold factor.
491      *
492      * @return minimum threshold factor.
493      */
494     public double getMinThresholdFactor() {
495         return minThresholdFactor;
496     }
497 
498     /**
499      * Gets the maximum threshold factor.
500      *
501      * @return maximum threshold factor.
502      */
503     public double getMaxThresholdFactor() {
504         return maxThresholdFactor;
505     }
506 
507     /**
508      * Sets a range of threshold factor values to get an optimized threshold factor value.
509      *
510      * @param minThresholdFactor minimum threshold.
511      * @param maxThresholdFactor maximum threshold.
512      * @throws LockedException          if optimizer is already running.
513      * @throws IllegalArgumentException if either minimum or maximum values are
514      *                                  negative, or if the minimum value is larger
515      *                                  than the maximum one.
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      * Indicates whether this optimizer is ready to start optimization.
532      *
533      * @return true if this optimizer is ready, false otherwise.
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      * Gets the time interval between input measurements provided to the
546      * {@link #getDataSource()} expressed in seconds (s).
547      *
548      * @return time interval between input measurements.
549      */
550     public double getTimeInterval() {
551         return generator.getTimeInterval();
552     }
553 
554     /**
555      * Sets time interval between input measurements provided to the
556      * {@link #getDataSource()} expressed in seconds (s).
557      *
558      * @param timeInterval time interval between input measurements.
559      * @throws LockedException          if optimizer is already running.
560      * @throws IllegalArgumentException if provided value is negative.
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      * Gets the time interval between input measurements provided to the
572      * {@link #getDataSource()}.
573      *
574      * @return time interval between input measurements.
575      */
576     public Time getTimeIntervalAsTime() {
577         return generator.getTimeIntervalAsTime();
578     }
579 
580     /**
581      * Gets the time interval between input measurements provided to the
582      * {@link #getDataSource()}.
583      *
584      * @param result instance where the time interval will be stored.
585      */
586     public void getTimeIntervalAsTime(final Time result) {
587         generator.getTimeIntervalAsTime(result);
588     }
589 
590     /**
591      * Sets time interval between input measurements provided to the
592      * {@link #getDataSource()}.
593      *
594      * @param timeInterval time interval between input measurements.
595      * @throws LockedException          if optimizer is already running.
596      * @throws IllegalArgumentException if provided value is negative.
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      * Gets minimum number of input measurements provided to the
608      * {@link #getDataSource()} required in a static interval to be taken
609      * into account.
610      * Smaller static intervals will be discarded.
611      *
612      * @return a minimum number of input measurements required in a static interval
613      * to be taken into account.
614      */
615     public int getMinStaticSamples() {
616         return generator.getMinStaticSamples();
617     }
618 
619     /**
620      * Sets minimum number of input measurements provided to the
621      * {@link #getDataSource()} required in a static interval to be taken
622      * into account.
623      * Smaller static intervals will be discarded.
624      *
625      * @param minStaticSamples a minimum number of input measurements required in
626      *                         a static interval to be taken into account.
627      * @throws LockedException          if optimizer is already running.
628      * @throws IllegalArgumentException if provided value is less than 2.
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      * Gets maximum number of input measurements provided to the
640      * {@link #getDataSource()} allowed in dynamic intervals.
641      *
642      * @return maximum number of input measurements allowed in dynamic intervals.
643      */
644     public int getMaxDynamicSamples() {
645         return generator.getMaxDynamicSamples();
646     }
647 
648     /**
649      * Sets maximum number of input measurements provided to the
650      * {@link #getDataSource()} allowed in dynamic intervals.
651      *
652      * @param maxDynamicSamples maximum number of input measurements allowed in
653      *                          dynamic intervals.
654      * @throws LockedException          if optimizer is already running.
655      * @throws IllegalArgumentException if provided value is less than 2.
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      * Gets length of number of input measurements provided to the
667      * {@link #getDataSource()} to keep within the window being processed
668      * to determine instantaneous accelerometer noise level.
669      *
670      * @return length of input measurements to keep within the window.
671      */
672     public int getWindowSize() {
673         return generator.getWindowSize();
674     }
675 
676     /**
677      * Sets length of number of input measurements provided to the
678      * {@link #getDataSource()} to keep within the window being processed
679      * to determine instantaneous noise level.
680      * Window size must always be larger than the allowed minimum value, which is 2
681      * and must have an odd value.
682      *
683      * @param windowSize length of number of samples to keep within the window.
684      * @throws LockedException          if optimizer is already running.
685      * @throws IllegalArgumentException if provided value is not valid.
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      * Gets number of input measurements provided to the
697      * {@link #getDataSource()} to be processed initially while keeping the sensor
698      * static to find the base noise level when the device is static.
699      *
700      * @return number of samples to be processed initially.
701      */
702     public int getInitialStaticSamples() {
703         return generator.getInitialStaticSamples();
704     }
705 
706     /**
707      * Sets number of input parameters provided to the {@link #getDataSource()}
708      * to be processed initially while keeping the sensor static to
709      * find the base noise level when the device is static.
710      *
711      * @param initialStaticSamples number of samples ot be processed initially.
712      * @throws LockedException          if optimizer is already running.
713      * @throws IllegalArgumentException if provided value is less than
714      *                                  {@link TriadStaticIntervalDetector#MINIMUM_INITIAL_STATIC_SAMPLES}.
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      * Gets factor to determine that a sudden movement has occurred during
726      * initialization if instantaneous noise level exceeds accumulated noise
727      * level by this factor amount.
728      * This factor is unit-less.
729      *
730      * @return factor to determine that a sudden movement has occurred.
731      */
732     public double getInstantaneousNoiseLevelFactor() {
733         return generator.getInstantaneousNoiseLevelFactor();
734     }
735 
736     /**
737      * Sets factor to determine that a sudden movement has occurred during
738      * initialization if instantaneous noise level exceeds accumulated noise
739      * level by this factor amount.
740      * This factor is unit-less.
741      *
742      * @param instantaneousNoiseLevelFactor factor to determine that a sudden
743      *                                      movement has occurred during
744      *                                      initialization.
745      * @throws LockedException          if optimizer is already running.
746      * @throws IllegalArgumentException if provided value is zero or negative.
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      * Gets the overall absolute threshold to determine whether there has been
758      * excessive motion during the whole initialization phase.
759      * This threshold is expressed in meters per squared second (m/s^2).
760      *
761      * @return overall absolute threshold to determine whether there has been
762      * excessive motion.
763      */
764     public double getBaseNoiseLevelAbsoluteThreshold() {
765         return generator.getBaseNoiseLevelAbsoluteThreshold();
766     }
767 
768     /**
769      * Sets the overall absolute threshold to determine whether there has been
770      * excessive motion during the whole initialization phase.
771      * This threshold is expressed in meters per squared second (m/s^2).
772      *
773      * @param baseNoiseLevelAbsoluteThreshold overall absolute threshold to
774      *                                        determine whether there has been
775      *                                        excessive motion.
776      * @throws LockedException          if optimizer is already running.
777      * @throws IllegalArgumentException if provided value is zero or negative.
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      * Gets the overall absolute threshold to determine whether there has been
790      * excessive motion during the whole initialization phase.
791      *
792      * @return overall absolute threshold to determine whether there has been
793      * excessive motion.
794      */
795     public Acceleration getBaseNoiseLevelAbsoluteThresholdAsMeasurement() {
796         return generator.getBaseNoiseLevelAbsoluteThresholdAsMeasurement();
797     }
798 
799     /**
800      * Gets the overall absolute threshold to determine whether there has been
801      * excessive motion during the whole initialization phase.
802      *
803      * @param result instance where the result will be stored.
804      */
805     public void getBaseNoiseLevelAbsoluteThresholdAsMeasurement(final Acceleration result) {
806         generator.getBaseNoiseLevelAbsoluteThresholdAsMeasurement(result);
807     }
808 
809     /**
810      * Sets the overall absolute threshold to determine whether there has been
811      * excessive motion during the whole initialization phase.
812      *
813      * @param baseNoiseLevelAbsoluteThreshold overall absolute threshold to
814      *                                        determine whether there has been
815      *                                        excessive motion.
816      * @throws LockedException          if optimizer is already running.
817      * @throws IllegalArgumentException if provided value is zero or negative.
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      * Gets accelerometer base noise level that has been detected during
830      * initialization of the best solution that has been found expressed in
831      * meters per squared second (m/s^2).
832      * This is equal to the standard deviation of the accelerometer measurements
833      * during the initialization phase.
834      *
835      * @return accelerometer base noise level of the best solution that has been
836      * found.
837      */
838     public double getAccelerometerBaseNoiseLevel() {
839         return baseNoiseLevel;
840     }
841 
842     /**
843      * Gets accelerometer base noise level that has been detected during
844      * initialization of the best solution that has been found.
845      * This is equal to the standard deviation of the accelerometer measurements
846      * during the initialization phase.
847      *
848      * @return accelerometer base noise level of the best solution that has been
849      * found.
850      */
851     public Acceleration getAccelerometerBaseNoiseLevelAsMeasurement() {
852         return createMeasurement(baseNoiseLevel, getDefaultUnit());
853     }
854 
855     /**
856      * Gets accelerometer base noise level that has been detected during
857      * initialization of the best solution that has been found.
858      * This is equal to the standard deviation of the accelerometer measurements
859      * during the initialization phase.
860      *
861      * @param result instance where the result will be stored.
862      */
863     public void getAccelerometerBaseNoiseLevelAsMeasurement(final Acceleration result) {
864         result.setValue(baseNoiseLevel);
865         result.setUnit(getDefaultUnit());
866     }
867 
868     /**
869      * Gets gyroscope base noise level PSD (Power Spectral Density)
870      * expressed in (rad^2/s).
871      *
872      * @return gyroscope base noise level PSD.
873      */
874     public double getGyroscopeBaseNoiseLevelPsd() {
875         return angularSpeedNoiseRootPsd * angularSpeedNoiseRootPsd;
876     }
877 
878     /**
879      * Gets gyroscope base noise level root PSD (Power Spectral Density)
880      * expressed in (rad * s^-0.5)
881      *
882      * @return gyroscope base noise level root PSD.
883      */
884     @Override
885     public double getGyroscopeBaseNoiseLevelRootPsd() {
886         return angularSpeedNoiseRootPsd;
887     }
888 
889     /**
890      * Gets accelerometer base noise level PSD (Power Spectral Density)
891      * expressed in (m^2 * s^-3).
892      *
893      * @return accelerometer base noise level PSD.
894      */
895     public double getAccelerometerBaseNoiseLevelPsd() {
896         return baseNoiseLevel * baseNoiseLevel * getTimeInterval();
897     }
898 
899     /**
900      * Gets accelerometer base noise level root PSD (Power Spectral Density)
901      * expressed in (m * s^-1.5).
902      *
903      * @return accelerometer base noise level root PSD.
904      */
905     @Override
906     public double getAccelerometerBaseNoiseLevelRootPsd() {
907         return baseNoiseLevel * Math.sqrt(getTimeInterval());
908     }
909 
910     /**
911      * Gets the threshold to determine static/dynamic period changes expressed in
912      * meters per squared second (m/s^2) for the best calibration solution that
913      * has been found.
914      *
915      * @return threshold to determine static/dynamic period changes for the best
916      * solution.
917      */
918     public double getThreshold() {
919         return threshold;
920     }
921 
922     /**
923      * Gets the threshold to determine static/dynamic period changes for the best
924      * calibration solution that has been found.
925      *
926      * @return threshold to determine static/dynamic period changes for the best
927      * solution.
928      */
929     public Acceleration getThresholdAsMeasurement() {
930         return createMeasurement(threshold, getDefaultUnit());
931     }
932 
933     /**
934      * Get the threshold to determine static/dynamic period changes for the best
935      * calibration solution that has been found.
936      *
937      * @param result instance where the result will be stored.
938      */
939     public void getThresholdAsMeasurement(final Acceleration result) {
940         result.setValue(threshold);
941         result.setUnit(getDefaultUnit());
942     }
943 
944     /**
945      * Gets estimated standard deviation norm of accelerometer bias expressed in
946      * meters per squared second (m/s^2).
947      * This can be used as the initial accelerometer bias uncertainty for
948      * {@link INSLooselyCoupledKalmanInitializerConfig} or {@link INSTightlyCoupledKalmanInitializerConfig}.
949      *
950      * @return estimated standard deviation norm of accelerometer bias or null
951      * if not available.
952      */
953     public Double getEstimatedAccelerometerBiasStandardDeviationNorm() {
954         return estimatedAccelerometerCovariance != null
955                 ? Math.sqrt(getEstimatedAccelerometerBiasFxVariance()
956                 + getEstimatedAccelerometerBiasFyVariance()
957                 + getEstimatedAccelerometerBiasFzVariance())
958                 : null;
959     }
960 
961     /**
962      * Gets estimated x coordinate variance of accelerometer bias expressed in (m^2/s^4).
963      *
964      * @return estimated x coordinate variance of accelerometer bias or null if not available.
965      */
966     public Double getEstimatedAccelerometerBiasFxVariance() {
967         return estimatedAccelerometerCovariance != null
968                 ? estimatedAccelerometerCovariance.getElementAt(0, 0) : null;
969     }
970 
971     /**
972      * Gets estimated y coordinate variance of accelerometer bias expressed in (m^2/s^4).
973      *
974      * @return estimated y coordinate variance of accelerometer bias or null if not available.
975      */
976     public Double getEstimatedAccelerometerBiasFyVariance() {
977         return estimatedAccelerometerCovariance != null
978                 ? estimatedAccelerometerCovariance.getElementAt(1, 1) : null;
979     }
980 
981     /**
982      * Gets estimated z coordinate variance of accelerometer bias expressed in (m^2/s^4).
983      *
984      * @return estimated z coordinate variance of accelerometer bias or null if not available.
985      */
986     public Double getEstimatedAccelerometerBiasFzVariance() {
987         return estimatedAccelerometerCovariance != null
988                 ? estimatedAccelerometerCovariance.getElementAt(2, 2) : null;
989     }
990 
991     /**
992      * Gets an array containing x,y,z components of estimated accelerometer biases
993      * expressed in meters per squared second (m/s^2).
994      *
995      * @return array containing x,y,z components of estimated accelerometer biases.
996      */
997     public double[] getEstimatedAccelerometerBiases() {
998         return estimatedAccelerometerBiases;
999     }
1000 
1001     /**
1002      * Gets estimated accelerometer scale factors and cross-coupling errors.
1003      * This is the product of matrix Ta containing cross-coupling errors and Ka
1004      * containing scaling factors.
1005      * So that:
1006      * <pre>
1007      *     Ma = [sx    mxy  mxz] = Ta*Ka
1008      *          [myx   sy   myz]
1009      *          [mzx   mzy  sz ]
1010      * </pre>
1011      * Where:
1012      * <pre>
1013      *     Ka = [sx 0   0 ]
1014      *          [0  sy  0 ]
1015      *          [0  0   sz]
1016      * </pre>
1017      * and
1018      * <pre>
1019      *     Ta = [1          -alphaXy    alphaXz ]
1020      *          [alphaYx    1           -alphaYz]
1021      *          [-alphaZx   alphaZy     1       ]
1022      * </pre>
1023      * Hence:
1024      * <pre>
1025      *     Ma = [sx    mxy  mxz] = Ta*Ka =  [sx             -sy * alphaXy   sz * alphaXz ]
1026      *          [myx   sy   myz]            [sx * alphaYx   sy              -sz * alphaYz]
1027      *          [mzx   mzy  sz ]            [-sx * alphaZx  sy * alphaZy    sz           ]
1028      * </pre>
1029      * This instance allows any 3x3 matrix. However, typically alphaYx, alphaZx and alphaZy
1030      * are considered to be zero if the accelerometer z-axis is assumed to be the same
1031      * as the body z-axis. When this is assumed, myx = mzx = mzy = 0 and the Ma matrix
1032      * becomes upper diagonal:
1033      * <pre>
1034      *     Ma = [sx    mxy  mxz]
1035      *          [0     sy   myz]
1036      *          [0     0    sz ]
1037      * </pre>
1038      * Values of this matrix are unit-less.
1039      *
1040      * @return estimated accelerometer scale factors and cross-coupling errors, or null
1041      * if not available.
1042      */
1043     public Matrix getEstimatedAccelerometerMa() {
1044         return estimatedAccelerometerMa;
1045     }
1046 
1047     /**
1048      * Gets estimated standard deviation norm of gyroscope bias expressed in
1049      * radians per second (rad/s).
1050      * This can be used as the initial gyroscope bias uncertainty for
1051      * {@link INSLooselyCoupledKalmanInitializerConfig} or {@link INSTightlyCoupledKalmanInitializerConfig}.
1052      *
1053      * @return estimated standard deviation norm of gyroscope bias or null
1054      * if not available.
1055      */
1056     public Double getEstimatedGyroscopeBiasStandardDeviationNorm() {
1057         return estimatedGyroscopeCovariance != null
1058                 ? Math.sqrt(getEstimatedGyroscopeBiasXVariance()
1059                 + getEstimatedGyroscopeBiasYVariance()
1060                 + getEstimatedGyroscopeBiasZVariance())
1061                 : null;
1062     }
1063 
1064     /**
1065      * Gets estimated x coordinate variance of gyroscope bias expressed in (rad^2/s^2).
1066      *
1067      * @return estimated x coordinate variance of gyroscope bias or null if not available.
1068      */
1069     public Double getEstimatedGyroscopeBiasXVariance() {
1070         return estimatedGyroscopeCovariance != null
1071                 ? estimatedGyroscopeCovariance.getElementAt(0, 0) : null;
1072     }
1073 
1074     /**
1075      * Gets estimated y coordinate variance of gyroscope bias expressed in (rad^2/s^2).
1076      *
1077      * @return estimated y coordinate variance of gyroscope bias or null if not available.
1078      */
1079     public Double getEstimatedGyroscopeBiasYVariance() {
1080         return estimatedGyroscopeCovariance != null
1081                 ? estimatedGyroscopeCovariance.getElementAt(1, 1) : null;
1082     }
1083 
1084     /**
1085      * Gets estimated z coordinate variance of gyroscope bias expressed in (rad^2/s^2).
1086      *
1087      * @return estimated z coordinate variance of gyroscope bias or null if not available.
1088      */
1089     public Double getEstimatedGyroscopeBiasZVariance() {
1090         return estimatedGyroscopeCovariance != null
1091                 ? estimatedGyroscopeCovariance.getElementAt(2, 2) : null;
1092     }
1093 
1094     /**
1095      * Gets the array containing x,y,z components of estimated gyroscope biases
1096      * expressed in radians per second (rad/s).
1097      *
1098      * @return array containing x,y,z components of estimated gyroscope biases.
1099      */
1100     public double[] getEstimatedGyroscopeBiases() {
1101         return estimatedGyroscopeBiases;
1102     }
1103 
1104     /**
1105      * Gets estimated gyroscope scale factors and cross-coupling errors.
1106      * This is the product of matrix Tg containing cross-coupling errors and Kg
1107      * containing scaling factors.
1108      * So that:
1109      * <pre>
1110      *     Mg = [sx    mxy  mxz] = Tg*Kg
1111      *          [myx   sy   myz]
1112      *          [mzx   mzy  sz ]
1113      * </pre>
1114      * Where:
1115      * <pre>
1116      *     Kg = [sx 0   0 ]
1117      *          [0  sy  0 ]
1118      *          [0  0   sz]
1119      * </pre>
1120      * and
1121      * <pre>
1122      *     Tg = [1          -alphaXy    alphaXz ]
1123      *          [alphaYx    1           -alphaYz]
1124      *          [-alphaZx   alphaZy     1       ]
1125      * </pre>
1126      * Hence:
1127      * <pre>
1128      *     Mg = [sx    mxy  mxz] = Tg*Kg =  [sx             -sy * alphaXy   sz * alphaXz ]
1129      *          [myx   sy   myz]            [sx * alphaYx   sy              -sz * alphaYz]
1130      *          [mzx   mzy  sz ]            [-sx * alphaZx  sy * alphaZy    sz           ]
1131      * </pre>
1132      * This instance allows any 3x3 matrix. However, typically alphaYx, alphaZx and alphaZy
1133      * are considered to be zero if the gyroscope z-axis is assumed to be the same
1134      * as the body z-axis. When this is assumed, myx = mzx = mzy = 0 and the Mg matrix
1135      * becomes upper diagonal:
1136      * <pre>
1137      *     Mg = [sx    mxy  mxz]
1138      *          [0     sy   myz]
1139      *          [0     0    sz ]
1140      * </pre>
1141      * Values of this matrix are unit-less.
1142      *
1143      * @return estimated gyroscope scale factors and cross-coupling errors.
1144      */
1145     public Matrix getEstimatedGyroscopeMg() {
1146         return estimatedGyroscopeMg;
1147     }
1148 
1149     /**
1150      * Gets estimated G-dependent cross-biases introduced on the gyroscope by the
1151      * specific forces sensed by the accelerometer.
1152      *
1153      * @return a 3x3 matrix containing g-dependent cross biases.
1154      */
1155     public Matrix getEstimatedGyroscopeGg() {
1156         return estimatedGyroscopeGg;
1157     }
1158 
1159     /**
1160      * Evaluates calibration Mean Square Error (MSE) for the provided threshold factor.
1161      *
1162      * @param thresholdFactor threshold factor to be used for interval detection
1163      *                        and measurement generation to be used for
1164      *                        calibration.
1165      * @return calibration MSE.
1166      * @throws LockedException                                   if the generator is busy.
1167      * @throws CalibrationException                              if calibration fails.
1168      * @throws NotReadyException                                 if the calibrator is not ready.
1169      * @throws IntervalDetectorThresholdFactorOptimizerException interval detection failed.
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             // interval detection failed
1200             return Double.MAX_VALUE;
1201         }
1202 
1203         // check that enough measurements have been obtained
1204         if (measurements.size() < accelerometerCalibrator.getMinimumRequiredMeasurements()
1205                 || sequences.size() < gyroscopeCalibrator.getMinimumRequiredMeasurementsOrSequences()) {
1206             return Double.MAX_VALUE;
1207         }
1208 
1209         // set calibrator measurements
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                 // Throw exception. Cannot use frames
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         // once we have accelerometer estimations, we can set known
1265         // accelerometer bias and cross-coupling errors to the gyroscope calibrator
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         // convert accelerometer and gyroscope mse to global mse
1290         final var mse = mseRule.evaluate(accelerometerMse, gyroscopeMse);
1291         if (mse < minMse) {
1292             keepBestResult(mse, thresholdFactor);
1293         }
1294         return mse;
1295     }
1296 
1297     /**
1298      * Initializes accelerometer + gyroscope measurement generator to convert timed
1299      * body kinematics measurements after interval detection into measurements and
1300      * sequences used for accelerometer and gyroscope calibration.
1301      */
1302     private void initialize() {
1303         final var generatorListener = new AccelerometerAndGyroscopeMeasurementsGeneratorListener() {
1304             @Override
1305             public void onInitializationStarted(final AccelerometerAndGyroscopeMeasurementsGenerator generator) {
1306                 // not needed
1307             }
1308 
1309             @Override
1310             public void onInitializationCompleted(
1311                     final AccelerometerAndGyroscopeMeasurementsGenerator generator,
1312                     final double accelerometerBaseNoiseLevel) {
1313                 // not needed
1314             }
1315 
1316             @Override
1317             public void onError(
1318                     final AccelerometerAndGyroscopeMeasurementsGenerator generator,
1319                     final TriadStaticIntervalDetector.ErrorReason reason) {
1320                 // not needed
1321             }
1322 
1323             @Override
1324             public void onStaticIntervalDetected(final AccelerometerAndGyroscopeMeasurementsGenerator generator) {
1325                 // not needed
1326             }
1327 
1328             @Override
1329             public void onDynamicIntervalDetected(final AccelerometerAndGyroscopeMeasurementsGenerator generator) {
1330                 // not needed
1331             }
1332 
1333             @Override
1334             public void onStaticIntervalSkipped(final AccelerometerAndGyroscopeMeasurementsGenerator generator) {
1335                 // not needed
1336             }
1337 
1338             @Override
1339             public void onDynamicIntervalSkipped(final AccelerometerAndGyroscopeMeasurementsGenerator generator) {
1340                 // not needed
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                 // not needed
1360             }
1361         };
1362 
1363         generator = new AccelerometerAndGyroscopeMeasurementsGenerator(generatorListener);
1364     }
1365 
1366     /**
1367      * Keeps the best calibration solution found so far.
1368      *
1369      * @param mse             Estimated Mean Square Error during calibration.
1370      * @param thresholdFactor threshold factor to be kept.
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      * Creates an acceleration instance using the provided value and unit.
1421      *
1422      * @param value value of measurement.
1423      * @param unit  unit of value.
1424      * @return created acceleration.
1425      */
1426     private Acceleration createMeasurement(final double value, final AccelerationUnit unit) {
1427         return new Acceleration(value, unit);
1428     }
1429 
1430     /**
1431      * Gets the default unit for acceleration, which is meters per
1432      * squared second (m/s^2).
1433      *
1434      * @return default unit for acceleration.
1435      */
1436     private AccelerationUnit getDefaultUnit() {
1437         return AccelerationUnit.METERS_PER_SQUARED_SECOND;
1438     }
1439 }