Class LMedSRobustEasyGyroscopeCalibrator

java.lang.Object
com.irurueta.navigation.inertial.calibration.gyroscope.RobustEasyGyroscopeCalibrator
com.irurueta.navigation.inertial.calibration.gyroscope.LMedSRobustEasyGyroscopeCalibrator
All Implemented Interfaces:
AccelerometerDependentGyroscopeCalibrator, GyroscopeCalibrator, GyroscopeNonLinearCalibrator, OrderedBodyKinematicsSequenceGyroscopeCalibrator, QualityScoredGyroscopeCalibrator, UnknownBiasGyroscopeCalibrator, GyroscopeBiasUncertaintySource, GyroscopeCalibrationSource

public class LMedSRobustEasyGyroscopeCalibrator extends RobustEasyGyroscopeCalibrator
Robustly estimates gyroscope biases, cross couplings and scaling factors along with G-dependent cross biases introduced on the gyroscope by the specific forces sensed by the accelerometer using LMedS robust estimator.

This calibrator assumes that the IMU is at a more or less fixed location on Earth, and evaluates sequences of measured body kinematics to perform calibration for unknown orientations on those provided sequences. Each provided sequence will be preceded by a static period where mean specific force will be measured to determine gravity (and hence partial body attitude).

Measured gyroscope angular rates is assumed to follow the model shown below:

     Ωmeas = bg + (I + Mg) * Ωtrue + Gg * ftrue + w
 
Where: - Ωmeas is the measured gyroscope angular rates. This is a 3x1 vector. - bg is the gyroscope bias. Ideally, on a perfect gyroscope, this should be a 3x1 zero vector. - I is the 3x3 identity matrix. - Mg is the 3x3 matrix containing cross-couplings and scaling factors. Ideally, on a perfect gyroscope, this should be a 3x3 zero matrix. - Ωtrue is ground-truth gyroscope angular rates. - Gg is the G-dependent cross biases introduced by the specific forces sensed by the accelerometer. Ideally, on a perfect gyroscope, this should be a 3x3 zero matrix. - ftrue is ground-truth specific force. This is a 3x1 vector. - w is measurement noise. This is a 3x1 vector.
  • Field Details

    • DEFAULT_STOP_THRESHOLD

      public static final double DEFAULT_STOP_THRESHOLD
      Default value to be used for stop threshold. Stop threshold can be used to avoid keeping the algorithm unnecessarily iterating in case that best estimated threshold using median of residuals is not small enough. Once a solution is found that generates a threshold below this value, the algorithm will stop. The stop threshold can be used to prevent the LMedS algorithm iterating too many times in cases where samples have a very similar accuracy. For instance, in cases where proportion of outliers is very small (close to 0%), and samples are very accurate (i.e. 1e-6), the algorithm would iterate for a long time trying to find the best solution when indeed there is no need to do that if a reasonable threshold has already been reached. Because of this behaviour the stop threshold can be set to a value much lower than the one typically used in RANSAC, and yet the algorithm could still produce even smaller thresholds in estimated results.
      See Also:
    • MIN_STOP_THRESHOLD

      public static final double MIN_STOP_THRESHOLD
      Minimum allowed stop threshold value.
      See Also:
    • stopThreshold

      private double stopThreshold
      Threshold to be used to keep the algorithm iterating in case that best estimated threshold using median of residuals is not small enough. Once a solution is found that generates a threshold below this value, the algorithm will stop. The stop threshold can be used to prevent the LMedS algorithm iterating too many times in cases where samples have a very similar accuracy. For instance, in cases where proportion of outliers is very small (close to 0%), and samples are very accurate (i.e. 1e-6), the algorithm would iterate for a long time trying to find the best solution when indeed there is no need to do that if a reasonable threshold has already been reached. Because of this behaviour the stop threshold can be set to a value much lower than the one typically used in RANSAC, and yet the algorithm could still produce even smaller thresholds in estimated results.
  • Constructor Details

    • LMedSRobustEasyGyroscopeCalibrator

      public LMedSRobustEasyGyroscopeCalibrator()
      Constructor.
    • LMedSRobustEasyGyroscopeCalibrator

      public LMedSRobustEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, com.irurueta.algebra.Matrix initialBias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg)
      Constructor.
      Parameters:
      sequences - collection of sequences containing timestamped body kinematics measurements.
      initialBias - initial gyroscope bias to be used to find a solution. This must be 3x1 and is expressed in radians per second (rad/s).
      initialMg - initial gyroscope scale factors and cross coupling errors matrix. Must be 3x3.
      initialGg - initial gyroscope G-dependent cross biases introduced on the gyroscope by the specific forces sensed by the accelerometer. Must be 3x3.
      Throws:
      IllegalArgumentException - if any of the provided values does not have proper size.
    • LMedSRobustEasyGyroscopeCalibrator

      public LMedSRobustEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, com.irurueta.algebra.Matrix initialBias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg, RobustEasyGyroscopeCalibratorListener listener)
      Constructor.
      Parameters:
      sequences - collection of sequences containing timestamped body kinematics measurements.
      initialBias - initial gyroscope bias to be used to find a solution. This must be 3x1 and is expressed in radians per second (rad/s).
      initialMg - initial gyroscope scale factors and cross coupling errors matrix. Must be 3x3.
      initialGg - initial gyroscope G-dependent cross biases introduced on the gyroscope by the specific forces sensed by the accelerometer. Must be 3x3.
      listener - listener to handle events raised by this calibrator.
      Throws:
      IllegalArgumentException - if any of the provided values does not have proper size.
    • LMedSRobustEasyGyroscopeCalibrator

      public LMedSRobustEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, double[] initialBias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg)
      Constructor.
      Parameters:
      sequences - collection of sequences containing timestamped body kinematics measurements.
      initialBias - initial gyroscope bias to be used to find a solution. This must have length 3 and is expressed in radians per second (rad/s).
      initialMg - initial gyroscope scale factors and cross coupling errors matrix. Must be 3x3.
      initialGg - initial gyroscope G-dependent cross biases introduced on the gyroscope by the specific forces sensed by the accelerometer. Must be 3x3.
      Throws:
      IllegalArgumentException - if any of the provided values does not have proper size.
    • LMedSRobustEasyGyroscopeCalibrator

      public LMedSRobustEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, double[] initialBias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg, RobustEasyGyroscopeCalibratorListener listener)
      Constructor.
      Parameters:
      sequences - collection of sequences containing timestamped body kinematics measurements.
      initialBias - initial gyroscope bias to be used to find a solution. This must have length 3 and is expressed in radians per second (rad/s).
      initialMg - initial gyroscope scale factors and cross coupling errors matrix. Must be 3x3.
      initialGg - initial gyroscope G-dependent cross biases introduced on the gyroscope by the specific forces sensed by the accelerometer. Must be 3x3.
      listener - listener to handle events raised by this calibrator.
      Throws:
      IllegalArgumentException - if any of the provided values does not have proper size.
    • LMedSRobustEasyGyroscopeCalibrator

      public LMedSRobustEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, double[] initialBias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg, double[] accelerometerBias, com.irurueta.algebra.Matrix accelerometerMa)
      Constructor.
      Parameters:
      sequences - collection of sequences containing timestamped body kinematics measurements.
      initialBias - initial gyroscope bias to be used to find a solution. This must have length 3 and is expressed in radians per second (rad/s).
      initialMg - initial gyroscope scale factors and cross coupling errors matrix. Must be 3x3.
      initialGg - initial gyroscope G-dependent cross biases introduced on the gyroscope by the specific forces sensed by the accelerometer. Must be 3x3.
      accelerometerBias - known accelerometer bias. This must have length 3 and is expressed in meters per squared second (m/s^2).
      accelerometerMa - known accelerometer scale factors and cross coupling matrix. Must be 3x3.
      Throws:
      IllegalArgumentException - if any of the provided values does not have proper size.
    • LMedSRobustEasyGyroscopeCalibrator

      public LMedSRobustEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, double[] initialBias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg, double[] accelerometerBias, com.irurueta.algebra.Matrix accelerometerMa, RobustEasyGyroscopeCalibratorListener listener)
      Constructor.
      Parameters:
      sequences - collection of sequences containing timestamped body kinematics measurements.
      initialBias - initial gyroscope bias to be used to find a solution. This must have length 3 and is expressed in radians per second (rad/s).
      initialMg - initial gyroscope scale factors and cross coupling errors matrix. Must be 3x3.
      initialGg - initial gyroscope G-dependent cross biases introduced on the gyroscope by the specific forces sensed by the accelerometer. Must be 3x3.
      accelerometerBias - known accelerometer bias. This must have length 3 and is expressed in meters per squared second (m/s^2).
      accelerometerMa - known accelerometer scale factors and cross coupling matrix. Must be 3x3.
      listener - listener to handle events raised by this calibrator.
      Throws:
      IllegalArgumentException - if any of the provided values does not have proper size.
    • LMedSRobustEasyGyroscopeCalibrator

      public LMedSRobustEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, com.irurueta.algebra.Matrix initialBias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg, com.irurueta.algebra.Matrix accelerometerBias, com.irurueta.algebra.Matrix accelerometerMa)
      Constructor.
      Parameters:
      sequences - collection of sequences containing timestamped body kinematics measurements.
      initialBias - initial gyroscope bias to be used to find a solution. This must be 3x1 and is expressed in radians per second (rad/s).
      initialMg - initial gyroscope scale factors and cross coupling errors matrix. Must be 3x3.
      initialGg - initial gyroscope G-dependent cross biases introduced on the gyroscope by the specific forces sensed by the accelerometer. Must be 3x3.
      accelerometerBias - known accelerometer bias. This must be 3x1 and is expressed in meters per squared second (m/s^2).
      accelerometerMa - known accelerometer scale factors and cross coupling matrix. Must be 3x3.
      Throws:
      IllegalArgumentException - if any of the provided values does not have proper size.
    • LMedSRobustEasyGyroscopeCalibrator

      public LMedSRobustEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, com.irurueta.algebra.Matrix initialBias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg, com.irurueta.algebra.Matrix accelerometerBias, com.irurueta.algebra.Matrix accelerometerMa, RobustEasyGyroscopeCalibratorListener listener)
      Constructor.
      Parameters:
      sequences - collection of sequences containing timestamped body kinematics measurements.
      initialBias - initial gyroscope bias to be used to find a solution. This must be 3x1 and is expressed in radians per second (rad/s).
      initialMg - initial gyroscope scale factors and cross coupling errors matrix. Must be 3x3.
      initialGg - initial gyroscope G-dependent cross biases introduced on the gyroscope by the specific forces sensed by the accelerometer. Must be 3x3.
      accelerometerBias - known accelerometer bias. This must be 3x1 and is expressed in meters per squared second (m/s^2).
      accelerometerMa - known accelerometer scale factors and cross coupling matrix. Must be 3x3.
      listener - listener to handle events raised by this calibrator.
      Throws:
      IllegalArgumentException - if any of the provided values does not have proper size.
    • LMedSRobustEasyGyroscopeCalibrator

      public LMedSRobustEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, boolean commonAxisUsed, boolean estimateGDependentCrossBiases, com.irurueta.algebra.Matrix initialBias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg)
      Constructor.
      Parameters:
      sequences - collection of sequences containing timestamped body kinematics measurements.
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
      estimateGDependentCrossBiases - true if G-dependent cross biases will be estimated, false otherwise.
      initialBias - initial gyroscope bias to be used to find a solution. This must be 3x1 and is expressed in radians per second (rad/s).
      initialMg - initial gyroscope scale factors and cross coupling errors matrix. Must be 3x3.
      initialGg - initial gyroscope G-dependent cross biases introduced on the gyroscope by the specific forces sensed by the accelerometer. Must be 3x3.
      Throws:
      IllegalArgumentException - if any of the provided values does not have proper size.
    • LMedSRobustEasyGyroscopeCalibrator

      public LMedSRobustEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, boolean commonAxisUsed, boolean estimateGDependentCrossBiases, com.irurueta.algebra.Matrix initialBias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg, RobustEasyGyroscopeCalibratorListener listener)
      Constructor.
      Parameters:
      sequences - collection of sequences containing timestamped body kinematics measurements.
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
      estimateGDependentCrossBiases - true if G-dependent cross biases will be estimated, false otherwise.
      initialBias - initial gyroscope bias to be used to find a solution. This must be 3x1 and is expressed in radians per second (rad/s).
      initialMg - initial gyroscope scale factors and cross coupling errors matrix. Must be 3x3.
      initialGg - initial gyroscope G-dependent cross biases introduced on the gyroscope by the specific forces sensed by the accelerometer. Must be 3x3.
      listener - listener to handle events raised by this calibrator.
      Throws:
      IllegalArgumentException - if any of the provided values does not have proper size.
    • LMedSRobustEasyGyroscopeCalibrator

      public LMedSRobustEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, boolean commonAxisUsed, boolean estimateGDependentCrossBiases, double[] initialBias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg)
      Constructor.
      Parameters:
      sequences - collection of sequences containing timestamped body kinematics measurements.
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
      estimateGDependentCrossBiases - true if G-dependent cross biases will be estimated, false otherwise.
      initialBias - initial gyroscope bias to be used to find a solution. This must have length 3 and is expressed in radians per second (rad/s).
      initialMg - initial gyroscope scale factors and cross coupling errors matrix. Must be 3x3.
      initialGg - initial gyroscope G-dependent cross biases introduced on the gyroscope by the specific forces sensed by the accelerometer. Must be 3x3.
      Throws:
      IllegalArgumentException - if any of the provided values does not have proper size.
    • LMedSRobustEasyGyroscopeCalibrator

      public LMedSRobustEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, boolean commonAxisUsed, boolean estimateGDependentCrossBiases, double[] initialBias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg, RobustEasyGyroscopeCalibratorListener listener)
      Constructor.
      Parameters:
      sequences - collection of sequences containing timestamped body kinematics measurements.
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
      estimateGDependentCrossBiases - true if G-dependent cross biases will be estimated, false otherwise.
      initialBias - initial gyroscope bias to be used to find a solution. This must have length 3 and is expressed in radians per second (rad/s).
      initialMg - initial gyroscope scale factors and cross coupling errors matrix. Must be 3x3.
      initialGg - initial gyroscope G-dependent cross biases introduced on the gyroscope by the specific forces sensed by the accelerometer. Must be 3x3.
      listener - listener to handle events raised by this calibrator.
      Throws:
      IllegalArgumentException - if any of the provided values does not have proper size.
    • LMedSRobustEasyGyroscopeCalibrator

      public LMedSRobustEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, boolean commonAxisUsed, boolean estimateGDependentCrossBiases, double[] initialBias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg, double[] accelerometerBias, com.irurueta.algebra.Matrix accelerometerMa)
      Constructor.
      Parameters:
      sequences - collection of sequences containing timestamped body kinematics measurements.
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
      estimateGDependentCrossBiases - true if G-dependent cross biases will be estimated, false otherwise.
      initialBias - initial gyroscope bias to be used to find a solution. This must have length 3 and is expressed in radians per second (rad/s).
      initialMg - initial gyroscope scale factors and cross coupling errors matrix. Must be 3x3.
      initialGg - initial gyroscope G-dependent cross biases introduced on the gyroscope by the specific forces sensed by the accelerometer. Must be 3x3.
      accelerometerBias - known accelerometer bias. This must have length 3 and is expressed in meters per squared second (m/s^2).
      accelerometerMa - known accelerometer scale factors and cross coupling matrix. Must be 3x3.
      Throws:
      IllegalArgumentException - if any of the provided values does not have proper size.
    • LMedSRobustEasyGyroscopeCalibrator

      public LMedSRobustEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, boolean commonAxisUsed, boolean estimateGDependentCrossBiases, double[] initialBias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg, double[] accelerometerBias, com.irurueta.algebra.Matrix accelerometerMa, RobustEasyGyroscopeCalibratorListener listener)
      Constructor.
      Parameters:
      sequences - collection of sequences containing timestamped body kinematics measurements.
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
      estimateGDependentCrossBiases - true if G-dependent cross biases will be estimated, false otherwise.
      initialBias - initial gyroscope bias to be used to find a solution. This must have length 3 and is expressed in radians per second (rad/s).
      initialMg - initial gyroscope scale factors and cross coupling errors matrix. Must be 3x3.
      initialGg - initial gyroscope G-dependent cross biases introduced on the gyroscope by the specific forces sensed by the accelerometer. Must be 3x3.
      accelerometerBias - known accelerometer bias. This must have length 3 and is expressed in meters per squared second (m/s^2).
      accelerometerMa - known accelerometer scale factors and cross coupling matrix. Must be 3x3.
      listener - listener to handle events raised by this calibrator.
      Throws:
      IllegalArgumentException - if any of the provided values does not have proper size.
    • LMedSRobustEasyGyroscopeCalibrator

      public LMedSRobustEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, boolean commonAxisUsed, boolean estimateGDependentCrossBiases, com.irurueta.algebra.Matrix initialBias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg, com.irurueta.algebra.Matrix accelerometerBias, com.irurueta.algebra.Matrix accelerometerMa)
      Constructor.
      Parameters:
      sequences - collection of sequences containing timestamped body kinematics measurements.
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
      estimateGDependentCrossBiases - true if G-dependent cross biases will be estimated, false otherwise.
      initialBias - initial gyroscope bias to be used to find a solution. This must be 3x1 and is expressed in radians per second (rad/s).
      initialMg - initial gyroscope scale factors and cross coupling errors matrix. Must be 3x3.
      initialGg - initial gyroscope G-dependent cross biases introduced on the gyroscope by the specific forces sensed by the accelerometer. Must be 3x3.
      accelerometerBias - known accelerometer bias. This must have length 3 and is expressed in meters per squared second (m/s^2).
      accelerometerMa - known accelerometer scale factors and cross coupling matrix. Must be 3x3.
      Throws:
      IllegalArgumentException - if any of the provided values does not have proper size.
    • LMedSRobustEasyGyroscopeCalibrator

      public LMedSRobustEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, boolean commonAxisUsed, boolean estimateGDependentCrossBiases, com.irurueta.algebra.Matrix initialBias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg, com.irurueta.algebra.Matrix accelerometerBias, com.irurueta.algebra.Matrix accelerometerMa, RobustEasyGyroscopeCalibratorListener listener)
      Constructor.
      Parameters:
      sequences - collection of sequences containing timestamped body kinematics measurements.
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
      estimateGDependentCrossBiases - true if G-dependent cross biases will be estimated, false otherwise.
      initialBias - initial gyroscope bias to be used to find a solution. This must be 3x1 and is expressed in radians per second (rad/s).
      initialMg - initial gyroscope scale factors and cross coupling errors matrix. Must be 3x3.
      initialGg - initial gyroscope G-dependent cross biases introduced on the gyroscope by the specific forces sensed by the accelerometer. Must be 3x3.
      accelerometerBias - known accelerometer bias. This must have length 3 and is expressed in meters per squared second (m/s^2).
      accelerometerMa - known accelerometer scale factors and cross coupling matrix. Must be 3x3.
      listener - listener to handle events raised by this calibrator.
      Throws:
      IllegalArgumentException - if any of the provided values does not have proper size.
  • Method Details

    • getStopThreshold

      public double getStopThreshold()
      Returns threshold to be used to keep the algorithm iterating in case that best estimated threshold using median of residuals is not small enough. Once a solution is found that generates a threshold below this value, the algorithm will stop. The stop threshold can be used to prevent the LMedS algorithm to iterate too many times in cases where samples have a very similar accuracy. For instance, in cases where proportion of outliers is very small (close to 0%), and samples are very accurate (i.e. 1e-6), the algorithm would iterate for a long time trying to find the best solution when indeed there is no need to do that if a reasonable threshold has already been reached. Because of this behaviour the stop threshold can be set to a value much lower than the one typically used in RANSAC, and yet the algorithm could still produce even smaller thresholds in estimated results.
      Returns:
      stop threshold to stop the algorithm prematurely when a certain accuracy has been reached.
    • setStopThreshold

      public void setStopThreshold(double stopThreshold) throws com.irurueta.navigation.LockedException
      Sets threshold to be used to keep the algorithm iterating in case that best estimated threshold using median of residuals is not small enough. Once a solution is found that generates a threshold below this value, the algorithm will stop. The stop threshold can be used to prevent the LMedS algorithm to iterate too many times in cases where samples have a very similar accuracy. For instance, in cases where proportion of outliers is very small (close to 0%), and samples are very accurate (i.e. 1e-6), the algorithm would iterate for a long time trying to find the best solution when indeed there is no need to do that if a reasonable threshold has already been reached. Because of this behaviour the stop threshold can be set to a value much lower than the one typically used in RANSAC, and yet the algorithm could still produce even smaller thresholds in estimated results.
      Parameters:
      stopThreshold - stop threshold to stop the algorithm prematurely when a certain accuracy has been reached.
      Throws:
      IllegalArgumentException - if provided value is zero or negative.
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • calibrate

      public void calibrate() throws com.irurueta.navigation.LockedException, com.irurueta.navigation.NotReadyException, CalibrationException
      Estimates gyroscope calibration parameters containing bias, scale factors, cross-coupling errors and G-dependent coupling.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
      com.irurueta.navigation.NotReadyException - if calibrator is not ready.
      CalibrationException - if estimation fails for numerical reasons.
    • getMethod

      public com.irurueta.numerical.robust.RobustEstimatorMethod getMethod()
      Returns method being used for robust estimation.
      Specified by:
      getMethod in class RobustEasyGyroscopeCalibrator
      Returns:
      method being used for robust estimation.
    • isQualityScoresRequired

      public boolean isQualityScoresRequired()
      Indicates whether this calibrator requires quality scores for each measurement/sequence or not.
      Returns:
      true if quality scores are required, false otherwise.