Class RANSACRobustKnownBiasEasyGyroscopeCalibrator

java.lang.Object
com.irurueta.navigation.inertial.calibration.gyroscope.RobustKnownBiasEasyGyroscopeCalibrator
com.irurueta.navigation.inertial.calibration.gyroscope.RANSACRobustKnownBiasEasyGyroscopeCalibrator
All Implemented Interfaces:
AccelerometerDependentGyroscopeCalibrator, GyroscopeCalibrator, GyroscopeNonLinearCalibrator, KnownBiasGyroscopeCalibrator, OrderedBodyKinematicsSequenceGyroscopeCalibrator, QualityScoredGyroscopeCalibrator

public class RANSACRobustKnownBiasEasyGyroscopeCalibrator extends RobustKnownBiasEasyGyroscopeCalibrator
Robustly estimates gyroscope cross couplings and scaling factors along with G-dependent cross biases introduced on the gyroscope by the specific forces sensed by the accelerometer using RANSAC 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_THRESHOLD

      public static final double DEFAULT_THRESHOLD
      Constant defining default threshold to determine whether samples are inliers or not.
      See Also:
    • MIN_THRESHOLD

      public static final double MIN_THRESHOLD
      Minimum value that can be set as threshold. Threshold must be strictly greater than 0.0.
      See Also:
    • DEFAULT_COMPUTE_AND_KEEP_INLIERS

      public static final boolean DEFAULT_COMPUTE_AND_KEEP_INLIERS
      Indicates that by default inliers will only be computed but not kept.
      See Also:
    • DEFAULT_COMPUTE_AND_KEEP_RESIDUALS

      public static final boolean DEFAULT_COMPUTE_AND_KEEP_RESIDUALS
      Indicates that by default residuals will only be computed but not kept.
      See Also:
    • threshold

      private double threshold
      Threshold to determine whether samples are inliers or not when testing possible solutions. The threshold refers to the amount of error on distance between estimated position and distances provided for each sample.
    • computeAndKeepInliers

      private boolean computeAndKeepInliers
      Indicates whether inliers must be computed and kept.
    • computeAndKeepResiduals

      private boolean computeAndKeepResiduals
      Indicates whether residuals must be computed and kept.
  • Constructor Details

    • RANSACRobustKnownBiasEasyGyroscopeCalibrator

      public RANSACRobustKnownBiasEasyGyroscopeCalibrator()
      Constructor.
    • RANSACRobustKnownBiasEasyGyroscopeCalibrator

      public RANSACRobustKnownBiasEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, com.irurueta.algebra.Matrix bias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg)
      Constructor.
      Parameters:
      sequences - collection of sequences containing timestamped body kinematics measurements.
      bias - gyroscope known bias. 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.
    • RANSACRobustKnownBiasEasyGyroscopeCalibrator

      public RANSACRobustKnownBiasEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, com.irurueta.algebra.Matrix bias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg, RobustKnownBiasEasyGyroscopeCalibratorListener listener)
      Constructor.
      Parameters:
      sequences - collection of sequences containing timestamped body kinematics measurements.
      bias - gyroscope known bias. 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.
    • RANSACRobustKnownBiasEasyGyroscopeCalibrator

      public RANSACRobustKnownBiasEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, double[] bias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg)
      Constructor.
      Parameters:
      sequences - collection of sequences containing timestamped body kinematics measurements.
      bias - gyroscope known bias. 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.
    • RANSACRobustKnownBiasEasyGyroscopeCalibrator

      public RANSACRobustKnownBiasEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, double[] bias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg, RobustKnownBiasEasyGyroscopeCalibratorListener listener)
      Constructor.
      Parameters:
      sequences - collection of sequences containing timestamped body kinematics measurements.
      bias - gyroscope known bias. 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.
    • RANSACRobustKnownBiasEasyGyroscopeCalibrator

      public RANSACRobustKnownBiasEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, double[] bias, 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.
      bias - gyroscope known bias. 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.
    • RANSACRobustKnownBiasEasyGyroscopeCalibrator

      public RANSACRobustKnownBiasEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, double[] bias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg, double[] accelerometerBias, com.irurueta.algebra.Matrix accelerometerMa, RobustKnownBiasEasyGyroscopeCalibratorListener listener)
      Constructor.
      Parameters:
      sequences - collection of sequences containing timestamped body kinematics measurements.
      bias - gyroscope known bias. 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.
    • RANSACRobustKnownBiasEasyGyroscopeCalibrator

      public RANSACRobustKnownBiasEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, com.irurueta.algebra.Matrix bias, 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.
      bias - gyroscope known bias. 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.
    • RANSACRobustKnownBiasEasyGyroscopeCalibrator

      public RANSACRobustKnownBiasEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, com.irurueta.algebra.Matrix bias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg, com.irurueta.algebra.Matrix accelerometerBias, com.irurueta.algebra.Matrix accelerometerMa, RobustKnownBiasEasyGyroscopeCalibratorListener listener)
      Constructor.
      Parameters:
      sequences - collection of sequences containing timestamped body kinematics measurements.
      bias - gyroscope known bias. 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.
    • RANSACRobustKnownBiasEasyGyroscopeCalibrator

      public RANSACRobustKnownBiasEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, boolean commonAxisUsed, boolean estimateGDependentCrossBiases, com.irurueta.algebra.Matrix bias, 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.
      bias - gyroscope known bias. 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.
    • RANSACRobustKnownBiasEasyGyroscopeCalibrator

      public RANSACRobustKnownBiasEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, boolean commonAxisUsed, boolean estimateGDependentCrossBiases, com.irurueta.algebra.Matrix bias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg, RobustKnownBiasEasyGyroscopeCalibratorListener 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.
      bias - gyroscope known bias. 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.
    • RANSACRobustKnownBiasEasyGyroscopeCalibrator

      public RANSACRobustKnownBiasEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, boolean commonAxisUsed, boolean estimateGDependentCrossBiases, double[] bias, 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.
      bias - gyroscope known bias. 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.
    • RANSACRobustKnownBiasEasyGyroscopeCalibrator

      public RANSACRobustKnownBiasEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, boolean commonAxisUsed, boolean estimateGDependentCrossBiases, double[] bias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg, RobustKnownBiasEasyGyroscopeCalibratorListener 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.
      bias - gyroscope known bias. 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.
    • RANSACRobustKnownBiasEasyGyroscopeCalibrator

      public RANSACRobustKnownBiasEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, boolean commonAxisUsed, boolean estimateGDependentCrossBiases, double[] bias, 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.
      bias - gyroscope known bias. 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.
    • RANSACRobustKnownBiasEasyGyroscopeCalibrator

      public RANSACRobustKnownBiasEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, boolean commonAxisUsed, boolean estimateGDependentCrossBiases, double[] bias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg, double[] accelerometerBias, com.irurueta.algebra.Matrix accelerometerMa, RobustKnownBiasEasyGyroscopeCalibratorListener 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.
      bias - gyroscope known bias. 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.
    • RANSACRobustKnownBiasEasyGyroscopeCalibrator

      public RANSACRobustKnownBiasEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, boolean commonAxisUsed, boolean estimateGDependentCrossBiases, com.irurueta.algebra.Matrix bias, 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.
      bias - gyroscope known bias. 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.
    • RANSACRobustKnownBiasEasyGyroscopeCalibrator

      public RANSACRobustKnownBiasEasyGyroscopeCalibrator(List<BodyKinematicsSequence<StandardDeviationTimedBodyKinematics>> sequences, boolean commonAxisUsed, boolean estimateGDependentCrossBiases, com.irurueta.algebra.Matrix bias, com.irurueta.algebra.Matrix initialMg, com.irurueta.algebra.Matrix initialGg, com.irurueta.algebra.Matrix accelerometerBias, com.irurueta.algebra.Matrix accelerometerMa, RobustKnownBiasEasyGyroscopeCalibratorListener 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.
      bias - gyroscope known bias. 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

    • getThreshold

      public double getThreshold()
      Gets threshold to determine whether samples are inliers or not when testing possible solutions. The threshold refers to the amount of error on norm between measured angular rates and the ones generated with estimated calibration parameters provided for each sample.
      Returns:
      threshold to determine whether samples are inliers or not.
    • setThreshold

      public void setThreshold(double threshold) throws com.irurueta.navigation.LockedException
      Sets threshold to determine whether samples are inliers or not when testing possible solutions. The threshold refers to the amount of error on norm between measured angular rates and the ones generated with estimated calibration parameters provided for each sample.
      Parameters:
      threshold - threshold to determine whether samples are inliers or not.
      Throws:
      IllegalArgumentException - if provided value is equal or less than zero.
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • isComputeAndKeepInliersEnabled

      public boolean isComputeAndKeepInliersEnabled()
      Indicates whether inliers must be computed and kept.
      Returns:
      true if inliers must be computed and kept, false if inliers only need to be computed but not kept.
    • setComputeAndKeepInliersEnabled

      public void setComputeAndKeepInliersEnabled(boolean computeAndKeepInliers) throws com.irurueta.navigation.LockedException
      Specifies whether inliers must be computed and kept.
      Parameters:
      computeAndKeepInliers - true if inliers must be computed and kept, false if inliers only need to be computed but not kept.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • isComputeAndKeepResiduals

      public boolean isComputeAndKeepResiduals()
      Indicates whether residuals must be computed and kept.
      Returns:
      true if residuals must be computed and kept, false if residuals only need to be computed but not kept.
    • setComputeAndKeepResidualsEnabled

      public void setComputeAndKeepResidualsEnabled(boolean computeAndKeepResiduals) throws com.irurueta.navigation.LockedException
      Specifies whether residuals must be computed and kept.
      Parameters:
      computeAndKeepResiduals - true if residuals must be computed and kept, false if residuals only need to be computed but not kept.
      Throws:
      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 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 RobustKnownBiasEasyGyroscopeCalibrator
      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.