Class RobustKnownFrameGyroscopeCalibrator

java.lang.Object
com.irurueta.navigation.inertial.calibration.gyroscope.RobustKnownFrameGyroscopeCalibrator
All Implemented Interfaces:
GyroscopeCalibrator, GyroscopeNonLinearCalibrator, OrderedStandardDeviationFrameBodyKinematicsGyroscopeCalibrator, QualityScoredGyroscopeCalibrator, UnknownBiasGyroscopeCalibrator, UnknownBiasNonLinearGyroscopeCalibrator, GyroscopeBiasUncertaintySource, GyroscopeCalibrationSource
Direct Known Subclasses:
LMedSRobustKnownFrameGyroscopeCalibrator, MSACRobustKnownFrameGyroscopeCalibrator, PROMedSRobustKnownFrameGyroscopeCalibrator, PROSACRobustKnownFrameGyroscopeCalibrator, RANSACRobustKnownFrameGyroscopeCalibrator

This is an abstract class to robustly estimate 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.

To use this calibrator at least 7 measurements at different known frames must be provided. In other words, accelerometer and gyroscope (i.e. body kinematics) samples must be obtained at 7 different positions, orientations and velocities (although typically velocities are always zero).

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_USE_COMMON_Z_AXIS

      public static final boolean DEFAULT_USE_COMMON_Z_AXIS
      Indicates whether by default a common z-axis is assumed for both the accelerometer and gyroscope.
      See Also:
    • MINIMUM_MEASUREMENTS

      public static final int MINIMUM_MEASUREMENTS
      Required minimum number of measurements.
      See Also:
    • DEFAULT_USE_LINEAR_CALIBRATOR

      public static final boolean DEFAULT_USE_LINEAR_CALIBRATOR
      Indicates that by default a linear calibrator is used for preliminary solution estimation. The result obtained on each preliminary solution might be later refined.
      See Also:
    • DEFAULT_REFINE_PRELIMINARY_SOLUTIONS

      public static final boolean DEFAULT_REFINE_PRELIMINARY_SOLUTIONS
      Indicates that by default preliminary solutions are refined.
      See Also:
    • DEFAULT_ROBUST_METHOD

      public static final com.irurueta.numerical.robust.RobustEstimatorMethod DEFAULT_ROBUST_METHOD
      Default robust estimator method when none is provided.
    • DEFAULT_REFINE_RESULT

      public static final boolean DEFAULT_REFINE_RESULT
      Indicates that result is refined by default using a non-linear calibrator (which uses a Levenberg-Marquardt fitter).
      See Also:
    • DEFAULT_KEEP_COVARIANCE

      public static final boolean DEFAULT_KEEP_COVARIANCE
      Indicates that covariance is kept by default after refining result.
      See Also:
    • DEFAULT_PROGRESS_DELTA

      public static final float DEFAULT_PROGRESS_DELTA
      Default amount of progress variation before notifying a change in estimation progress. By default this is set to 5%.
      See Also:
    • MIN_PROGRESS_DELTA

      public static final float MIN_PROGRESS_DELTA
      Minimum allowed value for progress delta.
      See Also:
    • MAX_PROGRESS_DELTA

      public static final float MAX_PROGRESS_DELTA
      Maximum allowed value for progress delta.
      See Also:
    • DEFAULT_CONFIDENCE

      public static final double DEFAULT_CONFIDENCE
      Constant defining default confidence of the estimated result, which is 99%. This means that with a probability of 99% estimation will be accurate because chosen sub-samples will be inliers.
      See Also:
    • DEFAULT_MAX_ITERATIONS

      public static final int DEFAULT_MAX_ITERATIONS
      Default maximum allowed number of iterations.
      See Also:
    • MIN_CONFIDENCE

      public static final double MIN_CONFIDENCE
      Minimum allowed confidence value.
      See Also:
    • MAX_CONFIDENCE

      public static final double MAX_CONFIDENCE
      Maximum allowed confidence value.
      See Also:
    • MIN_ITERATIONS

      public static final int MIN_ITERATIONS
      Minimum allowed number of iterations.
      See Also:
    • measurements

      protected List<StandardDeviationFrameBodyKinematics> measurements
      Contains a list of body kinematics measurements taken at different frames (positions, orientations and velocities) and containing the standard deviations of accelerometer and gyroscope measurements. If a single device IMU needs to be calibrated, typically all measurements are taken at the same position, with zero velocity and multiple orientations. However, if we just want to calibrate a given IMU model (e.g. obtain an average and less precise calibration for the IMU of a given phone model), we could take measurements collected throughout the planet at multiple positions while the phone remains static (e.g. while charging), hence each measurement position will change, velocity will remain zero and orientation will be typically constant at horizontal orientation while the phone remains on a flat surface.
    • listener

      Listener to be notified of events such as when calibration starts, ends or its progress significantly changes.
    • running

      protected boolean running
      Indicates whether estimator is running.
    • progressDelta

      protected float progressDelta
      Amount of progress variation before notifying a progress change during calibration.
    • confidence

      protected double confidence
      Amount of confidence expressed as a value between 0.0 and 1.0 (which is equivalent to 100%). The amount of confidence indicates the probability that the estimated result is correct. Usually this value will be close to 1.0, but not exactly 1.0.
    • maxIterations

      protected int maxIterations
      Maximum allowed number of iterations. When the maximum number of iterations is exceeded, result will not be available, however an approximate result will be available for retrieval.
    • inliersData

      protected com.irurueta.numerical.robust.InliersData inliersData
      Data related to inliers found after calibration.
    • refineResult

      protected boolean refineResult
      Indicates whether result must be refined using a non linear calibrator over found inliers. If true, inliers will be computed and kept in any implementation regardless of the settings.
    • preliminarySubsetSize

      protected int preliminarySubsetSize
      Size of subsets to be checked during robust estimation.
    • commonAxisUsed

      private boolean commonAxisUsed
      This flag indicates whether z-axis is assumed to be common for accelerometer and gyroscope. When enabled, this eliminates 3 variables from Ma matrix.
    • initialBiasX

      private double initialBiasX
      Initial x-coordinate of gyroscope bias to be used to find a solution. This is expressed in radians per second (rad/s).
    • initialBiasY

      private double initialBiasY
      Initial y-coordinate of gyroscope bias to be used to find a solution. This is expressed in radians per second (rad/s).
    • initialBiasZ

      private double initialBiasZ
      Initial z-coordinate of gyroscope bias to be used to find a solution. This is expressed in radians per second (rad/s).
    • initialSx

      private double initialSx
      Initial x scaling factor.
    • initialSy

      private double initialSy
      Initial y scaling factor.
    • initialSz

      private double initialSz
      Initial z scaling factor.
    • initialMxy

      private double initialMxy
      Initial x-y cross coupling error.
    • initialMxz

      private double initialMxz
      Initial x-z cross coupling error.
    • initialMyx

      private double initialMyx
      Initial y-x cross coupling error.
    • initialMyz

      private double initialMyz
      Initial y-z cross coupling error.
    • initialMzx

      private double initialMzx
      Initial z-x cross coupling error.
    • initialMzy

      private double initialMzy
      Initial z-y cross coupling error.
    • initialGg

      private com.irurueta.algebra.Matrix initialGg
      Initial G-dependent cross biases introduced on the gyroscope by the specific forces sensed by the accelerometer.
    • useLinearCalibrator

      private boolean useLinearCalibrator
      Indicates whether a linear calibrator is used or not for preliminary solutions.
    • refinePreliminarySolutions

      private boolean refinePreliminarySolutions
      Indicates whether preliminary solutions must be refined after an initial linear solution is found.
    • estimatedBiases

      private double[] estimatedBiases
      Estimated gyroscope biases for each IMU axis expressed in radians per second (rad/s).
    • estimatedMg

      private com.irurueta.algebra.Matrix estimatedMg
      Estimated gyroscope scale factors and cross coupling errors. This is the product of matrix Tg containing cross coupling errors and Kg containing scaling factors. So that:
           Mg = [sx    mxy  mxz] = Tg*Kg
                [myx   sy   myz]
                [mzx   mzy  sz ]
       
      Where:
           Kg = [sx 0   0 ]
                [0  sy  0 ]
                [0  0   sz]
       
      and
           Tg = [1          -alphaXy    alphaXz ]
                [alphaYx    1           -alphaYz]
                [-alphaZx   alphaZy     1       ]
       
      Hence:
           Mg = [sx    mxy  mxz] = Tg*Kg =  [sx             -sy * alphaXy   sz * alphaXz ]
                [myx   sy   myz]            [sx * alphaYx   sy              -sz * alphaYz]
                [mzx   mzy  sz ]            [-sx * alphaZx  sy * alphaZy    sz           ]
       
      This instance allows any 3x3 matrix however, typically alphaYx, alphaZx and alphaZy are considered to be zero if the gyroscope z-axis is assumed to be the same as the body z-axis. When this is assumed, myx = mzx = mzy = 0 and the Mg matrix becomes upper diagonal:
           Mg = [sx    mxy  mxz]
                [0     sy   myz]
                [0     0    sz ]
       
      Values of this matrix are unit-less.
    • estimatedGg

      private com.irurueta.algebra.Matrix estimatedGg
      Estimated G-dependent cross biases introduced on the gyroscope by the specific forces sensed by the accelerometer. This instance allows any 3x3 matrix.
    • keepCovariance

      private boolean keepCovariance
      Indicates whether covariance must be kept after refining result. This setting is only taken into account if result is refined.
    • estimatedCovariance

      private com.irurueta.algebra.Matrix estimatedCovariance
      Estimated covariance of estimated position. This is only available when result has been refined and covariance is kept.
    • estimatedChiSq

      private double estimatedChiSq
      Estimated chi square value.
    • estimatedMse

      private double estimatedMse
      Estimated mean square error respect to provided measurements.
    • linearCalibrator

      private final KnownFrameGyroscopeLinearLeastSquaresCalibrator linearCalibrator
      A linear least squares calibrator.
    • nonLinearCalibrator

      private final KnownFrameGyroscopeNonLinearLeastSquaresCalibrator nonLinearCalibrator
      A non-linear least squares calibrator.
  • Constructor Details

    • RobustKnownFrameGyroscopeCalibrator

      protected RobustKnownFrameGyroscopeCalibrator()
      Constructor.
    • RobustKnownFrameGyroscopeCalibrator

      protected RobustKnownFrameGyroscopeCalibrator(RobustKnownFrameGyroscopeCalibratorListener listener)
      Constructor.
      Parameters:
      listener - listener to be notified of events such as when estimation starts, ends or its progress significantly changes.
    • RobustKnownFrameGyroscopeCalibrator

      protected RobustKnownFrameGyroscopeCalibrator(List<StandardDeviationFrameBodyKinematics> measurements)
      Constructor.
      Parameters:
      measurements - list of body kinematics measurements with standard deviations taken at different frames (positions, orientations and velocities).
    • RobustKnownFrameGyroscopeCalibrator

      protected RobustKnownFrameGyroscopeCalibrator(List<StandardDeviationFrameBodyKinematics> measurements, RobustKnownFrameGyroscopeCalibratorListener listener)
      Constructor.
      Parameters:
      measurements - list of body kinematics measurements with standard deviations taken at different frames (positions, orientations and velocities).
      listener - listener to be notified of events such as when estimation starts, ends or its progress significantly changes.
    • RobustKnownFrameGyroscopeCalibrator

      protected RobustKnownFrameGyroscopeCalibrator(boolean commonAxisUsed)
      Constructor.
      Parameters:
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
    • RobustKnownFrameGyroscopeCalibrator

      protected RobustKnownFrameGyroscopeCalibrator(boolean commonAxisUsed, RobustKnownFrameGyroscopeCalibratorListener listener)
      Constructor.
      Parameters:
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
      listener - listener to handle events raised by this calibrator.
    • RobustKnownFrameGyroscopeCalibrator

      protected RobustKnownFrameGyroscopeCalibrator(List<StandardDeviationFrameBodyKinematics> measurements, boolean commonAxisUsed)
      Constructor.
      Parameters:
      measurements - list of body kinematics measurements with standard deviations taken at different frames (positions, orientations and velocities).
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
    • RobustKnownFrameGyroscopeCalibrator

      protected RobustKnownFrameGyroscopeCalibrator(List<StandardDeviationFrameBodyKinematics> measurements, boolean commonAxisUsed, RobustKnownFrameGyroscopeCalibratorListener listener)
      Constructor.
      Parameters:
      measurements - list of body kinematics measurements with standard deviations taken at different frames (positions, orientations and velocities).
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
      listener - listener to handle events raised by this calibrator.
  • Method Details

    • getInitialBiasX

      public double getInitialBiasX()
      Gets initial x-coordinate of gyroscope bias to be used to find a solutions. This is expressed in radians per second (rad/s) and only taken into account if non-linear preliminary solutions are used.
      Specified by:
      getInitialBiasX in interface UnknownBiasNonLinearGyroscopeCalibrator
      Returns:
      initial x-coordinate of gyroscope bias.
    • setInitialBiasX

      public void setInitialBiasX(double initialBiasX) throws com.irurueta.navigation.LockedException
      Sets initial x-coordinate of gyroscope bias to be used to find a solution. This is expressed in radians per second (rad/s) and only taken into account if non-linear preliminary solutions are used.
      Specified by:
      setInitialBiasX in interface UnknownBiasNonLinearGyroscopeCalibrator
      Parameters:
      initialBiasX - initial x-coordinate of gyroscope bias.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getInitialBiasY

      public double getInitialBiasY()
      Gets initial y-coordinate of gyroscope bias to be used to find a solution. This is expressed in radians per second (rad/s) and only taken into account if non-linear preliminary solutions are used.
      Specified by:
      getInitialBiasY in interface UnknownBiasNonLinearGyroscopeCalibrator
      Returns:
      initial y-coordinate of gyroscope bias.
    • setInitialBiasY

      public void setInitialBiasY(double initialBiasY) throws com.irurueta.navigation.LockedException
      Sets initial y-coordinate of gyroscope bias to be used to find a solution. This is expressed in radians per second (rad/s) and only taken into account if non-linear preliminary solutions are used.
      Specified by:
      setInitialBiasY in interface UnknownBiasNonLinearGyroscopeCalibrator
      Parameters:
      initialBiasY - initial y-coordinate of gyroscope bias.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getInitialBiasZ

      public double getInitialBiasZ()
      Gets initial z-coordinate of gyroscope bias to be used to find a solution. This is expressed in radians per second (rad/s) and only taken into account if non-linear preliminary solutions are used.
      Specified by:
      getInitialBiasZ in interface UnknownBiasNonLinearGyroscopeCalibrator
      Returns:
      initial z-coordinate of gyroscope bias.
    • setInitialBiasZ

      public void setInitialBiasZ(double initialBiasZ) throws com.irurueta.navigation.LockedException
      Sets initial z-coordinate of gyroscope bias to be used to find a solution. This is expressed in radians per second (rad/s) and only taken into account if non-linear preliminary solutions are used.
      Specified by:
      setInitialBiasZ in interface UnknownBiasNonLinearGyroscopeCalibrator
      Parameters:
      initialBiasZ - initial z-coordinate of gyroscope bias.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getInitialBiasAngularSpeedX

      public com.irurueta.units.AngularSpeed getInitialBiasAngularSpeedX()
      Gets initial x-coordinate of gyroscope bias to be used to find a solution.
      Specified by:
      getInitialBiasAngularSpeedX in interface UnknownBiasNonLinearGyroscopeCalibrator
      Returns:
      initial x-coordinate of gyroscope bias.
    • getInitialBiasAngularSpeedX

      public void getInitialBiasAngularSpeedX(com.irurueta.units.AngularSpeed result)
      Gets initial x-coordinate of gyroscope bias to be used to find a solution.
      Specified by:
      getInitialBiasAngularSpeedX in interface UnknownBiasNonLinearGyroscopeCalibrator
      Parameters:
      result - instance where result data will be stored.
    • setInitialBiasX

      public void setInitialBiasX(com.irurueta.units.AngularSpeed initialBiasX) throws com.irurueta.navigation.LockedException
      Sets initial x-coordinate of gyroscope bias to be used to find a solution.
      Specified by:
      setInitialBiasX in interface UnknownBiasNonLinearGyroscopeCalibrator
      Parameters:
      initialBiasX - initial x-coordinate of gyroscope bias.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getInitialBiasAngularSpeedY

      public com.irurueta.units.AngularSpeed getInitialBiasAngularSpeedY()
      Gets initial y-coordinate of gyroscope bias to be used to find a solution.
      Specified by:
      getInitialBiasAngularSpeedY in interface UnknownBiasNonLinearGyroscopeCalibrator
      Returns:
      initial y-coordinate of gyroscope bias.
    • getInitialBiasAngularSpeedY

      public void getInitialBiasAngularSpeedY(com.irurueta.units.AngularSpeed result)
      Gets initial y-coordinate of gyroscope bias to be used to find a solution.
      Specified by:
      getInitialBiasAngularSpeedY in interface UnknownBiasNonLinearGyroscopeCalibrator
      Parameters:
      result - instance where result data will be stored.
    • setInitialBiasY

      public void setInitialBiasY(com.irurueta.units.AngularSpeed initialBiasY) throws com.irurueta.navigation.LockedException
      Sets initial y-coordinate of gyroscope bias to be used to find a solution.
      Specified by:
      setInitialBiasY in interface UnknownBiasNonLinearGyroscopeCalibrator
      Parameters:
      initialBiasY - initial y-coordinate of gyroscope bias.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getInitialBiasAngularSpeedZ

      public com.irurueta.units.AngularSpeed getInitialBiasAngularSpeedZ()
      Gets initial z-coordinate of gyroscope bias to be used to find a solution.
      Specified by:
      getInitialBiasAngularSpeedZ in interface UnknownBiasNonLinearGyroscopeCalibrator
      Returns:
      initial z-coordinate of gyroscope bias.
    • getInitialBiasAngularSpeedZ

      public void getInitialBiasAngularSpeedZ(com.irurueta.units.AngularSpeed result)
      Gets initial z-coordinate of gyroscope bias to be used to find a solution.
      Specified by:
      getInitialBiasAngularSpeedZ in interface UnknownBiasNonLinearGyroscopeCalibrator
      Parameters:
      result - instance where result data will be stored.
    • setInitialBiasZ

      public void setInitialBiasZ(com.irurueta.units.AngularSpeed initialBiasZ) throws com.irurueta.navigation.LockedException
      Sets initial z-coordinate of gyroscope bias to be used to find a solution.
      Specified by:
      setInitialBiasZ in interface UnknownBiasNonLinearGyroscopeCalibrator
      Parameters:
      initialBiasZ - initial z-coordinate of gyroscope bias.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • setInitialBias

      public void setInitialBias(double initialBiasX, double initialBiasY, double initialBiasZ) throws com.irurueta.navigation.LockedException
      Sets initial bias coordinates of gyroscope used to find a solution expressed in radians per second (rad/s).
      Specified by:
      setInitialBias in interface UnknownBiasNonLinearGyroscopeCalibrator
      Parameters:
      initialBiasX - initial x-coordinate of gyroscope bias.
      initialBiasY - initial y-coordinate of gyroscope bias.
      initialBiasZ - initial z-coordinate of gyroscope bias.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • setInitialBias

      public void setInitialBias(com.irurueta.units.AngularSpeed initialBiasX, com.irurueta.units.AngularSpeed initialBiasY, com.irurueta.units.AngularSpeed initialBiasZ) throws com.irurueta.navigation.LockedException
      Sets initial bias coordinates of gyroscope used to find a solution.
      Specified by:
      setInitialBias in interface UnknownBiasNonLinearGyroscopeCalibrator
      Parameters:
      initialBiasX - initial x-coordinate of gyroscope bias.
      initialBiasY - initial y-coordinate of gyroscope bias.
      initialBiasZ - initial z-coordinate of gyroscope bias.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getInitialSx

      public double getInitialSx()
      Gets initial x scaling factor. This is only taken into account if non-linear preliminary solutions are used.
      Specified by:
      getInitialSx in interface GyroscopeNonLinearCalibrator
      Returns:
      initial x scaling factor.
    • setInitialSx

      public void setInitialSx(double initialSx) throws com.irurueta.navigation.LockedException
      Sets initial x scaling factor. This is only taken into account if non-linear preliminary solutions are used.
      Specified by:
      setInitialSx in interface GyroscopeNonLinearCalibrator
      Parameters:
      initialSx - initial x scaling factor.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getInitialSy

      public double getInitialSy()
      Gets initial y scaling factor. This is only taken into account if non-linear preliminary solutions are used.
      Specified by:
      getInitialSy in interface GyroscopeNonLinearCalibrator
      Returns:
      initial y scaling factor.
    • setInitialSy

      public void setInitialSy(double initialSy) throws com.irurueta.navigation.LockedException
      Sets initial y scaling factor. This is only taken into account if non-linear preliminary solutions are used.
      Specified by:
      setInitialSy in interface GyroscopeNonLinearCalibrator
      Parameters:
      initialSy - initial y scaling factor.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getInitialSz

      public double getInitialSz()
      Gets initial z scaling factor. This is only taken into account if non-linear preliminary solutions are used.
      Specified by:
      getInitialSz in interface GyroscopeNonLinearCalibrator
      Returns:
      initial z scaling factor.
    • setInitialSz

      public void setInitialSz(double initialSz) throws com.irurueta.navigation.LockedException
      Sets initial z scaling factor. This is only taken into account if non-linear preliminary solutions are used.
      Specified by:
      setInitialSz in interface GyroscopeNonLinearCalibrator
      Parameters:
      initialSz - initial z scaling factor.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getInitialMxy

      public double getInitialMxy()
      Gets initial x-y cross coupling error. This is only taken into account if non-linear preliminary solutions are used.
      Specified by:
      getInitialMxy in interface GyroscopeNonLinearCalibrator
      Returns:
      initial x-y cross coupling error.
    • setInitialMxy

      public void setInitialMxy(double initialMxy) throws com.irurueta.navigation.LockedException
      Sets initial x-y cross coupling error. This is only taken into account if non-linear preliminary solutions are used.
      Specified by:
      setInitialMxy in interface GyroscopeNonLinearCalibrator
      Parameters:
      initialMxy - initial x-y cross coupling error.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getInitialMxz

      public double getInitialMxz()
      Gets initial x-z cross coupling error. This is only taken into account if non-linear preliminary solutions are used.
      Specified by:
      getInitialMxz in interface GyroscopeNonLinearCalibrator
      Returns:
      initial x-z cross coupling error.
    • setInitialMxz

      public void setInitialMxz(double initialMxz) throws com.irurueta.navigation.LockedException
      Sets initial x-z cross coupling error. This is only taken into account if non-linear preliminary solutions are used.
      Specified by:
      setInitialMxz in interface GyroscopeNonLinearCalibrator
      Parameters:
      initialMxz - initial x-z cross coupling error.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getInitialMyx

      public double getInitialMyx()
      Gets initial y-x cross coupling error. This is only taken into account if non-linear preliminary solutions are used.
      Specified by:
      getInitialMyx in interface GyroscopeNonLinearCalibrator
      Returns:
      initial y-x cross coupling error.
    • setInitialMyx

      public void setInitialMyx(double initialMyx) throws com.irurueta.navigation.LockedException
      Sets initial y-x cross coupling error. This is only taken into account if non-linear preliminary solutions are used.
      Specified by:
      setInitialMyx in interface GyroscopeNonLinearCalibrator
      Parameters:
      initialMyx - initial y-x cross coupling error.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getInitialMyz

      public double getInitialMyz()
      Gets initial y-z cross coupling error. This is only taken into account if non-linear preliminary solutions are used.
      Specified by:
      getInitialMyz in interface GyroscopeNonLinearCalibrator
      Returns:
      initial y-z cross coupling error.
    • setInitialMyz

      public void setInitialMyz(double initialMyz) throws com.irurueta.navigation.LockedException
      Sets initial y-z cross coupling error. This is only taken into account if non-linear preliminary solutions are used.
      Specified by:
      setInitialMyz in interface GyroscopeNonLinearCalibrator
      Parameters:
      initialMyz - initial y-z cross coupling error.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getInitialMzx

      public double getInitialMzx()
      Gets initial z-x cross coupling error. This is only taken into account if non-linear preliminary solutions are used.
      Specified by:
      getInitialMzx in interface GyroscopeNonLinearCalibrator
      Returns:
      initial z-x cross coupling error.
    • setInitialMzx

      public void setInitialMzx(double initialMzx) throws com.irurueta.navigation.LockedException
      Sets initial z-x cross coupling error. This is only taken into account if non-linear preliminary solutions are used.
      Specified by:
      setInitialMzx in interface GyroscopeNonLinearCalibrator
      Parameters:
      initialMzx - initial z-x cross coupling error.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getInitialMzy

      public double getInitialMzy()
      Gets initial z-y cross coupling error. This is only taken into account if non-linear preliminary solutions are used.
      Specified by:
      getInitialMzy in interface GyroscopeNonLinearCalibrator
      Returns:
      initial z-y cross coupling error.
    • setInitialMzy

      public void setInitialMzy(double initialMzy) throws com.irurueta.navigation.LockedException
      Sets initial z-y cross coupling error. This is only taken into account if non-linear preliminary solutions are used.
      Specified by:
      setInitialMzy in interface GyroscopeNonLinearCalibrator
      Parameters:
      initialMzy - initial z-y cross coupling error.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • setInitialScalingFactors

      public void setInitialScalingFactors(double initialSx, double initialSy, double initialSz) throws com.irurueta.navigation.LockedException
      Sets initial scaling factors. This is only taken into account if non-linear preliminary solutions are used.
      Specified by:
      setInitialScalingFactors in interface GyroscopeNonLinearCalibrator
      Parameters:
      initialSx - initial x scaling factor.
      initialSy - initial y scaling factor.
      initialSz - initial z scaling factor.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • setInitialCrossCouplingErrors

      public void setInitialCrossCouplingErrors(double initialMxy, double initialMxz, double initialMyx, double initialMyz, double initialMzx, double initialMzy) throws com.irurueta.navigation.LockedException
      Sets initial cross coupling errors. This is only taken into account if non-linear preliminary solutions are used.
      Specified by:
      setInitialCrossCouplingErrors in interface GyroscopeNonLinearCalibrator
      Parameters:
      initialMxy - initial x-y cross coupling error.
      initialMxz - initial x-z cross coupling error.
      initialMyx - initial y-x cross coupling error.
      initialMyz - initial y-z cross coupling error.
      initialMzx - initial z-x cross coupling error.
      initialMzy - initial z-y cross coupling error.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • setInitialScalingFactorsAndCrossCouplingErrors

      public void setInitialScalingFactorsAndCrossCouplingErrors(double initialSx, double initialSy, double initialSz, double initialMxy, double initialMxz, double initialMyx, double initialMyz, double initialMzx, double initialMzy) throws com.irurueta.navigation.LockedException
      Sets initial scaling factors and cross coupling errors. This is only taken into account if non-linear preliminary solutions are used.
      Specified by:
      setInitialScalingFactorsAndCrossCouplingErrors in interface GyroscopeNonLinearCalibrator
      Parameters:
      initialSx - initial x scaling factor.
      initialSy - initial y scaling factor.
      initialSz - initial z scaling factor.
      initialMxy - initial x-y cross coupling error.
      initialMxz - initial x-z cross coupling error.
      initialMyx - initial y-x cross coupling error.
      initialMyz - initial y-z cross coupling error.
      initialMzx - initial z-x cross coupling error.
      initialMzy - initial z-y cross coupling error.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getInitialBias

      public double[] getInitialBias()
      Gets initial bias to be used to find a solution as an array. Array values are expressed in radians per second (rad/s).
      Specified by:
      getInitialBias in interface UnknownBiasNonLinearGyroscopeCalibrator
      Returns:
      array containing coordinates of initial bias.
    • getInitialBias

      public void getInitialBias(double[] result)
      Gets initial bias to be used to find a solution as an array. Array values are expressed in radians per second (rad/s).
      Specified by:
      getInitialBias in interface UnknownBiasNonLinearGyroscopeCalibrator
      Parameters:
      result - instance where result data will be copied to.
      Throws:
      IllegalArgumentException - if provided array does not have length 3.
    • setInitialBias

      public void setInitialBias(double[] initialBias) throws com.irurueta.navigation.LockedException
      Sets initial bias to be used to find a solution as an array. Array values are expressed in radians per second (rad/s).
      Specified by:
      setInitialBias in interface UnknownBiasNonLinearGyroscopeCalibrator
      Parameters:
      initialBias - initial bias to find a solution.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
      IllegalArgumentException - if provided array does not have length 3.
    • getInitialBiasAsMatrix

      public com.irurueta.algebra.Matrix getInitialBiasAsMatrix()
      Gets initial bias to be used to find a solution as a column matrix. Values are expressed in radians per second (rad/s).
      Specified by:
      getInitialBiasAsMatrix in interface UnknownBiasNonLinearGyroscopeCalibrator
      Returns:
      initial bias to be used to find a solution as a column matrix.
    • getInitialBiasAsMatrix

      public void getInitialBiasAsMatrix(com.irurueta.algebra.Matrix result)
      Gets initial bias to be used to find a solution as a column matrix. Values are expressed in radians per second (rad/s).
      Specified by:
      getInitialBiasAsMatrix in interface UnknownBiasNonLinearGyroscopeCalibrator
      Parameters:
      result - instance where result data will be copied to.
      Throws:
      IllegalArgumentException - if provided matrix is not 3x1.
    • setInitialBias

      public void setInitialBias(com.irurueta.algebra.Matrix initialBias) throws com.irurueta.navigation.LockedException
      Sets initial bias to be used to find a solution as a column matrix with values expressed in radians per second (rad/s).
      Specified by:
      setInitialBias in interface UnknownBiasNonLinearGyroscopeCalibrator
      Parameters:
      initialBias - initial bias to find a solution.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
      IllegalArgumentException - if provided matrix is not 3x1.
    • getInitialBiasAsTriad

      public AngularSpeedTriad getInitialBiasAsTriad()
      Gets initial bias coordinates of gyroscope used to find a solution.
      Specified by:
      getInitialBiasAsTriad in interface UnknownBiasNonLinearGyroscopeCalibrator
      Returns:
      initial bias coordinates.
    • getInitialBiasAsTriad

      public void getInitialBiasAsTriad(AngularSpeedTriad result)
      Gets initial bias coordinates of gyroscope used to find a solution.
      Specified by:
      getInitialBiasAsTriad in interface UnknownBiasNonLinearGyroscopeCalibrator
      Parameters:
      result - instance where result will be stored.
    • setInitialBias

      public void setInitialBias(AngularSpeedTriad initialBias) throws com.irurueta.navigation.LockedException
      Sets initial bias coordinates of gyroscope used to find a solution.
      Specified by:
      setInitialBias in interface UnknownBiasNonLinearGyroscopeCalibrator
      Parameters:
      initialBias - initial bias coordinates to be set.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getInitialMg

      public com.irurueta.algebra.Matrix getInitialMg()
      Gets initial scale factors and cross coupling errors matrix.
      Specified by:
      getInitialMg in interface GyroscopeNonLinearCalibrator
      Returns:
      initial scale factors and cross coupling errors matrix.
    • getInitialMg

      public void getInitialMg(com.irurueta.algebra.Matrix result)
      Gets initial scale factors and cross coupling errors matrix.
      Specified by:
      getInitialMg in interface GyroscopeNonLinearCalibrator
      Parameters:
      result - instance where data will be stored.
      Throws:
      IllegalArgumentException - if provided matrix is not 3x3.
    • setInitialMg

      public void setInitialMg(com.irurueta.algebra.Matrix initialMg) throws com.irurueta.navigation.LockedException
      Sets initial scale factors and cross coupling errors matrix.
      Specified by:
      setInitialMg in interface GyroscopeNonLinearCalibrator
      Parameters:
      initialMg - initial scale factors and cross coupling errors matrix.
      Throws:
      IllegalArgumentException - if provided matrix is not 3x3.
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getInitialGg

      public com.irurueta.algebra.Matrix getInitialGg()
      Gets initial G-dependent cross biases introduced on the gyroscope by the specific forces sensed by the accelerometer.
      Specified by:
      getInitialGg in interface GyroscopeNonLinearCalibrator
      Returns:
      a 3x3 matrix containing initial g-dependent cross biases.
    • getInitialGg

      public void getInitialGg(com.irurueta.algebra.Matrix result)
      Gets initial G-dependent cross biases introduced on the gyroscope by the specific forces sensed by the accelerometer.
      Specified by:
      getInitialGg in interface GyroscopeNonLinearCalibrator
      Parameters:
      result - instance where data will be stored.
      Throws:
      IllegalArgumentException - if provided matrix is not 3x3.
    • setInitialGg

      public void setInitialGg(com.irurueta.algebra.Matrix initialGg) throws com.irurueta.navigation.LockedException
      Sets initial G-dependent cross biases introduced on the gyroscope by the specific forces sensed by the accelerometer.
      Specified by:
      setInitialGg in interface GyroscopeNonLinearCalibrator
      Parameters:
      initialGg - g-dependent cross biases.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
      IllegalArgumentException - if provided matrix is not 3x3.
    • getMeasurements

      public List<StandardDeviationFrameBodyKinematics> getMeasurements()
      Gets a list of body kinematics measurements taken at different frames (positions, orientations and velocities) and containing the standard deviations of accelerometer and gyroscope measurements. If a single device IMU needs to be calibrated, typically all measurements are taken at the same position, with zero velocity and multiple orientations. However, if we just want to calibrate the a given IMU model (e.g. obtain an average and less precise calibration for the IMU of a given phone model), we could take measurements collected throughout the planet at multiple positions while the phone remains static (e.g. while charging), hence each measurement position will change, velocity will remain zero and orientation will be typically constant at horizontal orientation while the phone remains on a flat surface.
      Specified by:
      getMeasurements in interface OrderedStandardDeviationFrameBodyKinematicsGyroscopeCalibrator
      Returns:
      a collection of body kinematics measurements taken at different frames (positions, orientations and velocities).
    • setMeasurements

      public void setMeasurements(List<StandardDeviationFrameBodyKinematics> measurements) throws com.irurueta.navigation.LockedException
      Sets a list of body kinematics measurements taken at different frames (positions, orientations and velocities) and containing the standard deviations of accelerometer and gyroscope measurements. If a single device IMU needs to be calibrated, typically all measurements are taken at the same position, with zero velocity and multiple orientations. However, if we just want to calibrate the a given IMU model (e.g. obtain an average and less precise calibration for the IMU of a given phone model), we could take measurements collected throughout the planet at multiple positions while the phone remains static (e.g. while charging), hence each measurement position will change, velocity will remain zero and orientation will be typically constant at horizontal orientation while the phone remains on a flat surface.
      Specified by:
      setMeasurements in interface OrderedStandardDeviationFrameBodyKinematicsGyroscopeCalibrator
      Parameters:
      measurements - collection of body kinematics measurements taken at different frames (positions, orientations and velocities).
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getMeasurementOrSequenceType

      public GyroscopeCalibratorMeasurementOrSequenceType getMeasurementOrSequenceType()
      Indicates the type of measurement or sequence used by this calibrator.
      Specified by:
      getMeasurementOrSequenceType in interface GyroscopeCalibrator
      Returns:
      type of measurement or sequence used by this calibrator.
    • isOrderedMeasurementsOrSequencesRequired

      public boolean isOrderedMeasurementsOrSequencesRequired()
      Indicates whether this calibrator requires ordered measurements or sequences in a list or not.
      Specified by:
      isOrderedMeasurementsOrSequencesRequired in interface GyroscopeCalibrator
      Returns:
      true if measurements or sequences must be ordered, false otherwise.
    • isCommonAxisUsed

      public boolean isCommonAxisUsed()
      Indicates whether z-axis is assumed to be common for accelerometer and gyroscope. When enabled, this eliminates 3 variables from Ma matrix.
      Specified by:
      isCommonAxisUsed in interface GyroscopeCalibrator
      Returns:
      true if z-axis is assumed to be common for accelerometer and gyroscope, false otherwise.
    • setCommonAxisUsed

      public void setCommonAxisUsed(boolean commonAxisUsed) throws com.irurueta.navigation.LockedException
      Specifies whether z-axis is assumed to be common for accelerometer and gyroscope. When enabled, this eliminates 3 variables from Ma matrix.
      Specified by:
      setCommonAxisUsed in interface GyroscopeCalibrator
      Parameters:
      commonAxisUsed - true if z-axis is assumed to be common for accelerometer and gyroscope, false otherwise.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getListener

      Gets listener to handle events raised by this estimator.
      Returns:
      listener to handle events raised by this estimator.
    • setListener

      public void setListener(RobustKnownFrameGyroscopeCalibratorListener listener) throws com.irurueta.navigation.LockedException
      Sets listener to handle events raised by this estimator.
      Parameters:
      listener - listener to handle events raised by this estimator.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getMinimumRequiredMeasurementsOrSequences

      public int getMinimumRequiredMeasurementsOrSequences()
      Gets minimum number of required measurements.
      Specified by:
      getMinimumRequiredMeasurementsOrSequences in interface GyroscopeCalibrator
      Returns:
      minimum number of required measurements.
    • isReady

      public boolean isReady()
      Indicates whether calibrator is ready to start.
      Specified by:
      isReady in interface GyroscopeCalibrator
      Returns:
      true if calibrator is ready, false otherwise.
    • isRunning

      public boolean isRunning()
      Indicates whether calibrator is currently running or not.
      Specified by:
      isRunning in interface GyroscopeCalibrator
      Returns:
      true if calibrator is running, false otherwise.
    • isLinearCalibratorUsed

      public boolean isLinearCalibratorUsed()
      Indicates whether a linear calibrator is used or not for preliminary solutions.
      Returns:
      indicates whether a linear calibrator is used or not for preliminary solutions.
    • setLinearCalibratorUsed

      public void setLinearCalibratorUsed(boolean linearCalibratorUsed) throws com.irurueta.navigation.LockedException
      Specifies whether a linear calibrator is used or not for preliminary solutions.
      Parameters:
      linearCalibratorUsed - indicates whether a linear calibrator is used or not for preliminary solutions.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • isPreliminarySolutionRefined

      public boolean isPreliminarySolutionRefined()
      Indicates whether preliminary solutions must be refined after an initial linear solution is found. If no initial solution is found using a linear solver, a non linear solver will be used regardless of this value using an average solution as the initial value to be refined.
      Returns:
      true if preliminary solutions must be refined after an initial linear solution, false otherwise.
    • setPreliminarySolutionRefined

      public void setPreliminarySolutionRefined(boolean preliminarySolutionRefined) throws com.irurueta.navigation.LockedException
      Specifies whether preliminary solutions must be refined after an initial linear solution is found. If no initial solution is found using a linear solver, a non linear solver will be used regardless of this value using an average solution as the initial value to be refined.
      Parameters:
      preliminarySolutionRefined - true if preliminary solutions must be refined after an initial linear solution, false otherwise.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getProgressDelta

      public float getProgressDelta()
      Returns amount of progress variation before notifying a progress change during calibration.
      Returns:
      amount of progress variation before notifying a progress change during calibration.
    • setProgressDelta

      public void setProgressDelta(float progressDelta) throws com.irurueta.navigation.LockedException
      Sets amount of progress variation before notifying a progress change during calibration.
      Parameters:
      progressDelta - amount of progress variation before notifying a progress change during calibration.
      Throws:
      IllegalArgumentException - if progress delta is less than zero or greater than 1.
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getConfidence

      public double getConfidence()
      Returns amount of confidence expressed as a value between 0.0 and 1.0 (which is equivalent to 100%). The amount of confidence indicates the probability that the estimated result is correct. Usually this value will be close to 1.0, but not exactly 1.0.
      Returns:
      amount of confidence as a value between 0.0 and 1.0.
    • setConfidence

      public void setConfidence(double confidence) throws com.irurueta.navigation.LockedException
      Sets amount of confidence expressed as a value between 0.0 and 1.0 (which is equivalent to 100%). The amount of confidence indicates the probability that the estimated result is correct. Usually this value will be close to 1.0, but not exactly 1.0.
      Parameters:
      confidence - confidence to be set as a value between 0.0 and 1.0.
      Throws:
      IllegalArgumentException - if provided value is not between 0.0 and 1.0.
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getMaxIterations

      public int getMaxIterations()
      Returns maximum allowed number of iterations. If maximum allowed number of iterations is achieved without converging to a result when calling calibrate(), a RobustEstimatorException will be raised.
      Returns:
      maximum allowed number of iterations.
    • setMaxIterations

      public void setMaxIterations(int maxIterations) throws com.irurueta.navigation.LockedException
      Sets maximum allowed number of iterations. When the maximum number of iterations is exceeded, result will not be available, however an approximate result will be available for retrieval.
      Parameters:
      maxIterations - maximum allowed number of iterations to be set.
      Throws:
      IllegalArgumentException - if provided value is less than 1.
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getInliersData

      public com.irurueta.numerical.robust.InliersData getInliersData()
      Gets data related to inliers found after estimation.
      Returns:
      data related to inliers found after estimation.
    • isResultRefined

      public boolean isResultRefined()
      Indicates whether result must be refined using a non-linear solver over found inliers.
      Returns:
      true to refine result, false to simply use result found by robust estimator without further refining.
    • setResultRefined

      public void setResultRefined(boolean refineResult) throws com.irurueta.navigation.LockedException
      Specifies whether result must be refined using a non-linear solver over found inliers.
      Parameters:
      refineResult - true to refine result, false to simply use result found by robust estimator without further refining.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • isCovarianceKept

      public boolean isCovarianceKept()
      Indicates whether covariance must be kept after refining result. This setting is only taken into account if result is refined.
      Returns:
      true if covariance must be kept after refining result, false otherwise.
    • setCovarianceKept

      public void setCovarianceKept(boolean keepCovariance) throws com.irurueta.navigation.LockedException
      Specifies whether covariance must be kept after refining result. This setting is only taken into account if result is refined.
      Parameters:
      keepCovariance - true if covariance must be kept after refining result, false otherwise.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getQualityScores

      public double[] getQualityScores()
      Returns quality scores corresponding to each measurement. The larger the score value the better the quality of the sample. This implementation always returns null. Subclasses using quality scores must implement proper behavior.
      Specified by:
      getQualityScores in interface QualityScoredGyroscopeCalibrator
      Returns:
      quality scores corresponding to each sample.
    • setQualityScores

      public void setQualityScores(double[] qualityScores) throws com.irurueta.navigation.LockedException
      Sets quality scores corresponding to each measurement. The larger the score value the better the quality of the sample. This implementation makes no action. Subclasses using quality scores must implement proper behaviour.
      Specified by:
      setQualityScores in interface QualityScoredGyroscopeCalibrator
      Parameters:
      qualityScores - quality scores corresponding to each pair of matched points.
      Throws:
      IllegalArgumentException - if provided quality scores length is smaller than minimum required samples.
      com.irurueta.navigation.LockedException - if calibrator is currently running.
    • getEstimatedBiases

      public double[] getEstimatedBiases()
      Gets array containing x,y,z components of estimated gyroscope biases expressed in radians per second (rad/s).
      Specified by:
      getEstimatedBiases in interface GyroscopeCalibrationSource
      Specified by:
      getEstimatedBiases in interface UnknownBiasGyroscopeCalibrator
      Returns:
      array containing x,y,z components of estimated gyroscope biases.
    • getEstimatedBiases

      public boolean getEstimatedBiases(double[] result)
      Gets array containing x,y,z components of estimated gyroscope biases expressed in radians per second (rad/s).
      Specified by:
      getEstimatedBiases in interface UnknownBiasGyroscopeCalibrator
      Parameters:
      result - instance where estimated gyroscope biases will be stored.
      Returns:
      true if result instance was updated, false otherwise (when estimation is not yet available).
    • getEstimatedBiasesAsMatrix

      public com.irurueta.algebra.Matrix getEstimatedBiasesAsMatrix()
      Gets column matrix containing x,y,z components of estimated gyroscope biases expressed in radians per second (rad/s).
      Specified by:
      getEstimatedBiasesAsMatrix in interface UnknownBiasGyroscopeCalibrator
      Returns:
      column matrix containing x,y,z components of estimated gyroscope biases.
    • getEstimatedBiasesAsMatrix

      public boolean getEstimatedBiasesAsMatrix(com.irurueta.algebra.Matrix result) throws com.irurueta.algebra.WrongSizeException
      Gets column matrix containing x,y,z components of estimated gyroscope biases expressed in radians per second (rad/s).
      Specified by:
      getEstimatedBiasesAsMatrix in interface UnknownBiasGyroscopeCalibrator
      Parameters:
      result - instance where result data will be stored.
      Returns:
      true if result was updated, false otherwise.
      Throws:
      com.irurueta.algebra.WrongSizeException - if provided result instance has invalid size.
    • getEstimatedBiasX

      public Double getEstimatedBiasX()
      Gets x coordinate of estimated gyroscope bias expressed in radians per second (rad/s).
      Specified by:
      getEstimatedBiasX in interface UnknownBiasGyroscopeCalibrator
      Returns:
      x coordinate of estimated gyroscope bias or null if not available.
    • getEstimatedBiasY

      public Double getEstimatedBiasY()
      Gets y coordinate of estimated gyroscope bias expressed in radians per second (rad/s).
      Specified by:
      getEstimatedBiasY in interface UnknownBiasGyroscopeCalibrator
      Returns:
      y coordinate of estimated gyroscope bias or null if not available.
    • getEstimatedBiasZ

      public Double getEstimatedBiasZ()
      Gets z coordinate of estimated gyroscope bias expressed in radians per second (rad/s).
      Specified by:
      getEstimatedBiasZ in interface UnknownBiasGyroscopeCalibrator
      Returns:
      z coordinate of estimated gyroscope bias or null if not available.
    • getEstimatedBiasAngularSpeedX

      public com.irurueta.units.AngularSpeed getEstimatedBiasAngularSpeedX()
      Gets x coordinate of estimated gyroscope bias.
      Specified by:
      getEstimatedBiasAngularSpeedX in interface UnknownBiasGyroscopeCalibrator
      Returns:
      x coordinate of estimated gyroscope bias or null if not available.
    • getEstimatedBiasAngularSpeedX

      public boolean getEstimatedBiasAngularSpeedX(com.irurueta.units.AngularSpeed result)
      Gets x coordinate of estimated gyroscope bias.
      Specified by:
      getEstimatedBiasAngularSpeedX in interface UnknownBiasGyroscopeCalibrator
      Parameters:
      result - instance where result will be stored.
      Returns:
      true if result was updated, false if estimation is not available.
    • getEstimatedBiasAngularSpeedY

      public com.irurueta.units.AngularSpeed getEstimatedBiasAngularSpeedY()
      Gets y coordinate of estimated gyroscope bias.
      Specified by:
      getEstimatedBiasAngularSpeedY in interface UnknownBiasGyroscopeCalibrator
      Returns:
      y coordinate of estimated gyroscope bias or null if not available.
    • getEstimatedBiasAngularSpeedY

      public boolean getEstimatedBiasAngularSpeedY(com.irurueta.units.AngularSpeed result)
      Gets y coordinate of estimated gyroscope bias.
      Specified by:
      getEstimatedBiasAngularSpeedY in interface UnknownBiasGyroscopeCalibrator
      Parameters:
      result - instance where result will be stored.
      Returns:
      true if result was updated, false if estimation is not available.
    • getEstimatedBiasAngularSpeedZ

      public com.irurueta.units.AngularSpeed getEstimatedBiasAngularSpeedZ()
      Gets z coordinate of estimated gyroscope bias.
      Specified by:
      getEstimatedBiasAngularSpeedZ in interface UnknownBiasGyroscopeCalibrator
      Returns:
      z coordinate of estimated gyroscope bias or null if not available.
    • getEstimatedBiasAngularSpeedZ

      public boolean getEstimatedBiasAngularSpeedZ(com.irurueta.units.AngularSpeed result)
      Gets z coordinate of estimated gyroscope bias.
      Specified by:
      getEstimatedBiasAngularSpeedZ in interface UnknownBiasGyroscopeCalibrator
      Parameters:
      result - instance where result will be stored.
      Returns:
      true if result was updated, false if estimation is not available.
    • getEstimatedBiasAsTriad

      public AngularSpeedTriad getEstimatedBiasAsTriad()
      Gets estimated gyroscope bias.
      Specified by:
      getEstimatedBiasAsTriad in interface UnknownBiasGyroscopeCalibrator
      Returns:
      estimated gyroscope bias or null if not available.
    • getEstimatedBiasAsTriad

      public boolean getEstimatedBiasAsTriad(AngularSpeedTriad result)
      Gets estimated gyroscope bias.
      Specified by:
      getEstimatedBiasAsTriad in interface UnknownBiasGyroscopeCalibrator
      Parameters:
      result - instance where result will be stored.
      Returns:
      true if estimated gyroscope bias is available and result was modified, false otherwise.
    • getEstimatedMg

      public com.irurueta.algebra.Matrix getEstimatedMg()
      Gets estimated gyroscope scale factors and cross coupling errors. This is the product of matrix Tg containing cross coupling errors and Kg containing scaling factors. So that:
           Mg = [sx    mxy  mxz] = Tg*Kg
                [myx   sy   myz]
                [mzx   mzy  sz ]
       
      Where:
           Kg = [sx 0   0 ]
                [0  sy  0 ]
                [0  0   sz]
       
      and
           Tg = [1          -alphaXy    alphaXz ]
                [alphaYx    1           -alphaYz]
                [-alphaZx   alphaZy     1       ]
       
      Hence:
           Mg = [sx    mxy  mxz] = Tg*Kg =  [sx             -sy * alphaXy   sz * alphaXz ]
                [myx   sy   myz]            [sx * alphaYx   sy              -sz * alphaYz]
                [mzx   mzy  sz ]            [-sx * alphaZx  sy * alphaZy    sz           ]
       
      This instance allows any 3x3 matrix however, typically alphaYx, alphaZx and alphaZy are considered to be zero if the gyroscope z-axis is assumed to be the same as the body z-axis. When this is assumed, myx = mzx = mzy = 0 and the Mg matrix becomes upper diagonal:
           Mg = [sx    mxy  mxz]
                [0     sy   myz]
                [0     0    sz ]
       
      Values of this matrix are unit-less.
      Specified by:
      getEstimatedMg in interface GyroscopeCalibrationSource
      Specified by:
      getEstimatedMg in interface GyroscopeCalibrator
      Returns:
      estimated gyroscope scale factors and cross coupling errors, or null if not available.
    • getEstimatedSx

      public Double getEstimatedSx()
      Gets estimated x-axis scale factor.
      Specified by:
      getEstimatedSx in interface GyroscopeCalibrator
      Returns:
      estimated x-axis scale factor or null if not available.
    • getEstimatedSy

      public Double getEstimatedSy()
      Gets estimated y-axis scale factor.
      Specified by:
      getEstimatedSy in interface GyroscopeCalibrator
      Returns:
      estimated y-axis scale factor or null if not available.
    • getEstimatedSz

      public Double getEstimatedSz()
      Gets estimated z-axis scale factor.
      Specified by:
      getEstimatedSz in interface GyroscopeCalibrator
      Returns:
      estimated z-axis scale factor or null if not available.
    • getEstimatedMxy

      public Double getEstimatedMxy()
      Gets estimated x-y cross-coupling error.
      Specified by:
      getEstimatedMxy in interface GyroscopeCalibrator
      Returns:
      estimated x-y cross-coupling error or null if not available.
    • getEstimatedMxz

      public Double getEstimatedMxz()
      Gets estimated x-z cross-coupling error.
      Specified by:
      getEstimatedMxz in interface GyroscopeCalibrator
      Returns:
      estimated x-z cross-coupling error or null if not available.
    • getEstimatedMyx

      public Double getEstimatedMyx()
      Gets estimated y-x cross-coupling error.
      Specified by:
      getEstimatedMyx in interface GyroscopeCalibrator
      Returns:
      estimated y-x cross-coupling error or null if not available.
    • getEstimatedMyz

      public Double getEstimatedMyz()
      Gets estimated y-z cross-coupling error.
      Specified by:
      getEstimatedMyz in interface GyroscopeCalibrator
      Returns:
      estimated y-z cross-coupling error or null if not available.
    • getEstimatedMzx

      public Double getEstimatedMzx()
      Gets estimated z-x cross-coupling error.
      Specified by:
      getEstimatedMzx in interface GyroscopeCalibrator
      Returns:
      estimated z-x cross-coupling error or null if not available.
    • getEstimatedMzy

      public Double getEstimatedMzy()
      Gets estimated z-y cross-coupling error.
      Specified by:
      getEstimatedMzy in interface GyroscopeCalibrator
      Returns:
      estimated z-y cross-coupling error or null if not available.
    • getEstimatedGg

      public com.irurueta.algebra.Matrix getEstimatedGg()
      Gets estimated G-dependent cross biases introduced on the gyroscope by the specific forces sensed by the accelerometer. This instance allows any 3x3 matrix.
      Specified by:
      getEstimatedGg in interface GyroscopeCalibrationSource
      Specified by:
      getEstimatedGg in interface GyroscopeCalibrator
      Returns:
      estimated G-dependent cross biases.
    • getEstimatedMse

      public double getEstimatedMse()
      Gets estimated mean square error respect to provided measurements.
      Specified by:
      getEstimatedMse in interface GyroscopeNonLinearCalibrator
      Returns:
      estimated mean square error respect to provided measurements.
    • getEstimatedChiSq

      public double getEstimatedChiSq()
      Gets estimated chi square value.
      Specified by:
      getEstimatedChiSq in interface GyroscopeNonLinearCalibrator
      Returns:
      estimated chi square value.
    • getEstimatedCovariance

      public com.irurueta.algebra.Matrix getEstimatedCovariance()
      Gets estimated covariance matrix for estimated calibration solution. Diagonal elements of the matrix contains variance for the following parameters (following indicated order): bgx, bgy, bgz, sx, sy, sz, mxy, mxz, myx, myz, mzx, mzy, gg11, gg21, gg31, gg12, gg22, gg32, gg13, gg23, gg33. This is only available when result has been refined and covariance is kept.
      Specified by:
      getEstimatedCovariance in interface GyroscopeNonLinearCalibrator
      Returns:
      estimated covariance matrix for estimated position.
    • getEstimatedBiasXVariance

      public Double getEstimatedBiasXVariance()
      Gets variance of estimated x coordinate of gyroscope bias expressed in (rad^2/s^2).
      Returns:
      variance of estimated x coordinate of gyroscope bias or null if not available.
    • getEstimatedBiasXStandardDeviation

      public Double getEstimatedBiasXStandardDeviation()
      Gets standard deviation of estimated x coordinate of gyroscope bias expressed in radians per second (rad/s).
      Returns:
      standard deviation of estimated x coordinate of gyroscope bias or null if not available.
    • getEstimatedBiasXStandardDeviationAsAngularSpeed

      public com.irurueta.units.AngularSpeed getEstimatedBiasXStandardDeviationAsAngularSpeed()
      Gets standard deviation of estimated x coordinate of gyroscope bias.
      Returns:
      standard deviation of estimated x coordinate of gyroscope bias or null if not available.
    • getEstimatedBiasXStandardDeviationAsAngularSpeed

      public boolean getEstimatedBiasXStandardDeviationAsAngularSpeed(com.irurueta.units.AngularSpeed result)
      Gets standard deviation of estimated x coordinate of gyroscope bias.
      Parameters:
      result - instance where result will be stored.
      Returns:
      true if standard deviation of estimated x coordinate of gyroscope bias is available, false otherwise.
    • getEstimatedBiasYVariance

      public Double getEstimatedBiasYVariance()
      Gets variance of estimated y coordinate of gyroscope bias expressed in (rad^2/s^2).
      Returns:
      variance of estimated y coordinate of gyroscope bias or null if not available.
    • getEstimatedBiasYStandardDeviation

      public Double getEstimatedBiasYStandardDeviation()
      Gets standard deviation of estimated y coordinate of gyroscope bias expressed in radians per second (rad/s).
      Returns:
      standard deviation of estimated y coordinate of gyroscope bias or null if not available.
    • getEstimatedBiasYStandardDeviationAsAngularSpeed

      public com.irurueta.units.AngularSpeed getEstimatedBiasYStandardDeviationAsAngularSpeed()
      Gets standard deviation of estimated y coordinate of gyroscope bias.
      Returns:
      standard deviation of estimated y coordinate of gyroscope bias or null if not available.
    • getEstimatedBiasYStandardDeviationAsAngularSpeed

      public boolean getEstimatedBiasYStandardDeviationAsAngularSpeed(com.irurueta.units.AngularSpeed result)
      Gets standard deviation of estimated y coordinate of gyroscope bias.
      Parameters:
      result - instance where result will be stored.
      Returns:
      true if standard deviation of estimated y coordinate of gyroscope bias is available, false otherwise.
    • getEstimatedBiasZVariance

      public Double getEstimatedBiasZVariance()
      Gets variance of estimated z coordinate of gyroscope bias expressed in (rad^2/s^2).
      Returns:
      variance of estimated z coordinate of gyroscope bias or null if not available.
    • getEstimatedBiasZStandardDeviation

      public Double getEstimatedBiasZStandardDeviation()
      Gets standard deviation of estimated z coordinate of gyroscope bias expressed in radians per second (rad/s).
      Returns:
      standard deviation of estimated z coordinate of gyroscope bias or null if not available.
    • getEstimatedBiasZStandardDeviationAsAngularSpeed

      public com.irurueta.units.AngularSpeed getEstimatedBiasZStandardDeviationAsAngularSpeed()
      Gets standard deviation of estimated z coordinate of gyroscope bias.
      Returns:
      standard deviation of estimated z coordinate of gyroscope bias or null if not available.
    • getEstimatedBiasZStandardDeviationAsAngularSpeed

      public boolean getEstimatedBiasZStandardDeviationAsAngularSpeed(com.irurueta.units.AngularSpeed result)
      Gets standard deviation of estimated z coordinate of gyroscope bias.
      Parameters:
      result - instance where result will be stored.
      Returns:
      true if standard deviation of estimated z coordinate of gyroscope bias is available, false otherwise.
    • getEstimatedBiasStandardDeviation

      public AngularSpeedTriad getEstimatedBiasStandardDeviation()
      Gets standard deviation of estimated gyroscope bias coordinates.
      Returns:
      standard deviation of estimated gyroscope bias coordinates.
    • getEstimatedBiasStandardDeviation

      public boolean getEstimatedBiasStandardDeviation(AngularSpeedTriad result)
      Gets standard deviation of estimated gyroscope bias coordinates.
      Parameters:
      result - instance where result will be stored.
      Returns:
      true if standard deviation of gyroscope bias was available, false otherwise.
    • getEstimatedBiasStandardDeviationAverage

      public Double getEstimatedBiasStandardDeviationAverage()
      Gets average of estimated standard deviation of gyroscope bias coordinates expressed in radians per second (rad/s).
      Returns:
      average of estimated standard deviation of gyroscope bias coordinates or null if not available.
    • getEstimatedBiasStandardDeviationAverageAsAngularSpeed

      public com.irurueta.units.AngularSpeed getEstimatedBiasStandardDeviationAverageAsAngularSpeed()
      Gets average of estimated standard deviation of gyroscope bias coordinates.
      Returns:
      average of estimated standard deviation of gyroscope bias coordinates or null.
    • getEstimatedBiasStandardDeviationAverageAsAngularSpeed

      public boolean getEstimatedBiasStandardDeviationAverageAsAngularSpeed(com.irurueta.units.AngularSpeed result)
      Gets average of estimated standard deviation of gyroscope bias coordinates.
      Parameters:
      result - instance where result will be stored.
      Returns:
      true if average of estimated standard deviation of gyroscope bias is available, false otherwise.
    • getEstimatedBiasStandardDeviationNorm

      public Double getEstimatedBiasStandardDeviationNorm()
      Gets norm of estimated standard deviation of gyroscope bias expressed in radians per second (rad/s). This can be used as the initial gyroscope bias uncertainty for INSLooselyCoupledKalmanInitializerConfig or INSTightlyCoupledKalmanInitializerConfig.
      Specified by:
      getEstimatedBiasStandardDeviationNorm in interface GyroscopeBiasUncertaintySource
      Returns:
      norm of estimated standard deviation of gyroscope bias or null if not available.
    • getEstimatedBiasStandardDeviationNormAsAngularSpeed

      public com.irurueta.units.AngularSpeed getEstimatedBiasStandardDeviationNormAsAngularSpeed()
      Gets norm of estimated standard deviation of gyroscope bias. This can be used as the initial gyroscope bias uncertainty for INSLooselyCoupledKalmanInitializerConfig or INSTightlyCoupledKalmanInitializerConfig.
      Returns:
      norm of estimated standard deviation of gyroscope bias or null if not available.
    • getEstimatedBiasStandardDeviationNormAsAngularSpeed

      public boolean getEstimatedBiasStandardDeviationNormAsAngularSpeed(com.irurueta.units.AngularSpeed result)
      Gets norm of estimated standard deviation of gyroscope bias coordinates. This can be used as the initial gyroscope bias uncertainty for INSLooselyCoupledKalmanInitializerConfig or INSTightlyCoupledKalmanInitializerConfig.
      Parameters:
      result - instance where result will be stored.
      Returns:
      true if norm of estimated standard deviation of gyroscope bias is available, false otherwise.
    • getPreliminarySubsetSize

      public int getPreliminarySubsetSize()
      Gets size of subsets to be checked during robust estimation. This has to be at least MINIMUM_MEASUREMENTS.
      Returns:
      size of subsets to be checked during robust estimation.
    • setPreliminarySubsetSize

      public void setPreliminarySubsetSize(int preliminarySubsetSize) throws com.irurueta.navigation.LockedException
      Sets size of subsets to be checked during robust estimation. This has to be at least MINIMUM_MEASUREMENTS.
      Parameters:
      preliminarySubsetSize - size of subsets to be checked during robust estimation.
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
      IllegalArgumentException - if provided value is less than MINIMUM_MEASUREMENTS.
    • getMethod

      public abstract com.irurueta.numerical.robust.RobustEstimatorMethod getMethod()
      Returns method being used for robust estimation.
      Returns:
      method being used for robust estimation.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(com.irurueta.numerical.robust.RobustEstimatorMethod method)
      Creates a robust gyroscope calibrator.
      Parameters:
      method - robust estimator method.
      Returns:
      a robust gyroscope calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(RobustKnownFrameGyroscopeCalibratorListener listener, com.irurueta.numerical.robust.RobustEstimatorMethod method)
      Creates a robust gyroscope calibrator.
      Parameters:
      listener - listener to be notified of events such as when estimation starts, ends or its progress significantly changes.
      method - robust estimator method.
      Returns:
      a robust gyroscope calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(List<StandardDeviationFrameBodyKinematics> measurements, com.irurueta.numerical.robust.RobustEstimatorMethod method)
      Creates a robust gyroscope calibrator.
      Parameters:
      measurements - list of body kinematics measurements with standard deviations taken at different frames (positions, orientations and velocities).
      method - robust estimator method.
      Returns:
      a robust gyroscope calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(List<StandardDeviationFrameBodyKinematics> measurements, RobustKnownFrameGyroscopeCalibratorListener listener, com.irurueta.numerical.robust.RobustEstimatorMethod method)
      Creates a robust gyroscope calibrator.
      Parameters:
      measurements - list of body kinematics measurements with standard deviations taken at different frames (positions, orientations and velocities).
      listener - listener to handle events raised by this calibrator.
      method - robust estimator method.
      Returns:
      a robust gyroscope calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(boolean commonAxisUsed, com.irurueta.numerical.robust.RobustEstimatorMethod method)
      Creates a robust gyroscope calibrator.
      Parameters:
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
      method - robust estimator method.
      Returns:
      a robust gyroscope calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(boolean commonAxisUsed, RobustKnownFrameGyroscopeCalibratorListener listener, com.irurueta.numerical.robust.RobustEstimatorMethod method)
      Creates a robust gyroscope calibrator.
      Parameters:
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
      listener - listener to handle events raised by this calibrator.
      method - robust estimator method.
      Returns:
      a robust gyroscope calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(List<StandardDeviationFrameBodyKinematics> measurements, boolean commonAxisUsed, com.irurueta.numerical.robust.RobustEstimatorMethod method)
      Creates a robust gyroscope calibrator.
      Parameters:
      measurements - list of body kinematics measurements with standard deviations taken at different frames (positions, orientation and velocities).
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
      method - robust estimator method.
      Returns:
      a robust gyroscope calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(List<StandardDeviationFrameBodyKinematics> measurements, boolean commonAxisUsed, RobustKnownFrameGyroscopeCalibratorListener listener, com.irurueta.numerical.robust.RobustEstimatorMethod method)
      Creates a robust gyroscope calibrator.
      Parameters:
      measurements - list of body kinematics measurements with standard deviations taken at different frames (positions, orientations and velocities).
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
      listener - listener to handle events raised by this calibrator.
      method - robust estimator method.
      Returns:
      a robust gyroscope calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(double[] qualityScores, com.irurueta.numerical.robust.RobustEstimatorMethod method)
      Creates a robust gyroscope calibrator.
      Parameters:
      qualityScores - quality scores corresponding to each provided measurement. The larger the score value the better the quality of the sample.
      method - robust estimator method.
      Returns:
      a robust gyroscope calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(double[] qualityScores, RobustKnownFrameGyroscopeCalibratorListener listener, com.irurueta.numerical.robust.RobustEstimatorMethod method)
      Creates a robust gyroscope calibrator.
      Parameters:
      qualityScores - quality scores corresponding to each provided measurement. The larger the score value the better the quality of the sample.
      listener - listener to be notified of events such as when estimation starts, ends or its progress significantly changes.
      method - robust estimator method.
      Returns:
      a robust gyroscope calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(double[] qualityScores, List<StandardDeviationFrameBodyKinematics> measurements, com.irurueta.numerical.robust.RobustEstimatorMethod method)
      Creates a robust gyroscope calibrator.
      Parameters:
      qualityScores - quality scores corresponding to each provided measurement. The larger the score value the better the quality of the sample.
      measurements - list of body kinematics measurements with standard deviations taken at different frames (positions, orientations and velocities).
      method - robust estimator method.
      Returns:
      a robust gyroscope calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(double[] qualityScores, List<StandardDeviationFrameBodyKinematics> measurements, RobustKnownFrameGyroscopeCalibratorListener listener, com.irurueta.numerical.robust.RobustEstimatorMethod method)
      Creates a robust gyroscope calibrator.
      Parameters:
      qualityScores - quality scores corresponding to each provided measurement. The larger the score value the better the quality of the sample.
      measurements - list of body kinematics measurements with standard deviations taken at different frames (positions, orientations and velocities).
      listener - listener to handle events raised by this calibrator.
      method - robust estimator method.
      Returns:
      a robust gyroscope calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(double[] qualityScores, boolean commonAxisUsed, com.irurueta.numerical.robust.RobustEstimatorMethod method)
      Creates a robust gyroscope calibrator.
      Parameters:
      qualityScores - quality scores corresponding to each provided measurement. The larger the score value the better the quality of the sample.
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
      method - robust estimator method.
      Returns:
      a robust gyroscope calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(double[] qualityScores, boolean commonAxisUsed, RobustKnownFrameGyroscopeCalibratorListener listener, com.irurueta.numerical.robust.RobustEstimatorMethod method)
      Creates a robust gyroscope calibrator.
      Parameters:
      qualityScores - quality scores corresponding to each provided measurement. The larger the score value the better the quality of the sample.
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
      listener - listener to handle events raised by this calibrator.
      method - robust estimator method.
      Returns:
      a robust gyroscope calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(double[] qualityScores, List<StandardDeviationFrameBodyKinematics> measurements, boolean commonAxisUsed, com.irurueta.numerical.robust.RobustEstimatorMethod method)
      Creates a robust gyroscope calibrator.
      Parameters:
      qualityScores - quality scores corresponding to each provided measurement. The larger the score value the better the quality of the sample.
      measurements - list of body kinematics measurements with standard deviations taken at different frames (positions, orientations and velocities).
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
      method - robust estimator method.
      Returns:
      a robust gyroscope calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(double[] qualityScores, List<StandardDeviationFrameBodyKinematics> measurements, boolean commonAxisUsed, RobustKnownFrameGyroscopeCalibratorListener listener, com.irurueta.numerical.robust.RobustEstimatorMethod method)
      Creates a robust gyroscope calibrator.
      Parameters:
      qualityScores - quality scores corresponding to each provided measurement. The larger the score value the better the quality of the sample.
      measurements - list of body kinematics measurements with standard deviations taken at different frames (positions, orientations and velocities).
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
      listener - listener to handle events raised by this calibrator.
      method - robust estimator method.
      Returns:
      a robust gyroscope calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create()
      Creates a robust gyroscope calibrator using default robust method.
      Returns:
      a robust gyroscope calibrator.
    • create

      Creates a robust gyroscope calibrator using default robust method.
      Parameters:
      listener - listener to be notified of events such as when estimation starts, ends or its progress significantly changes.
      Returns:
      a robust gyroscope calibrator.
    • create

      Creates a robust gyroscope calibrator using default robust method.
      Parameters:
      measurements - list of body kinematics measurements with standard deviations taken at different frames (positions, orientations and velocities).
      Returns:
      a robust gyroscope calibrator.
    • create

      Creates a robust gyroscope calibrator using default robust method.
      Parameters:
      measurements - list of body kinematics measurements with standard deviations taken at different frames (positions, orientations and velocities).
      listener - listener to handle events raised by this calibrator.
      Returns:
      a robust gyroscope calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(boolean commonAxisUsed)
      Creates a robust gyroscope calibrator using default robust method.
      Parameters:
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
      Returns:
      a robust accelerometer calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(boolean commonAxisUsed, RobustKnownFrameGyroscopeCalibratorListener listener)
      Creates a robust gyroscope calibrator using default robust method.
      Parameters:
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
      listener - listener to handle events raised by this calibrator.
      Returns:
      a robust accelerometer calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(List<StandardDeviationFrameBodyKinematics> measurements, boolean commonAxisUsed)
      Creates a robust gyroscope calibrator using default robust method.
      Parameters:
      measurements - list of body kinematics measurements with standard deviations taken at different (positions, orientations and velocities).
      commonAxisUsed - indicates whether z-axis is assigned to be common for accelerometer and gyroscope.
      Returns:
      a robust gyroscope calibrator.
    • create

      Creates a robust gyroscope calibrator using default robust method.
      Parameters:
      measurements - list of body kinematics measurements with standard deviations taken at different frames (positions, orientations and velocities).
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
      listener - listener to handle events raised by this calibrator.
      Returns:
      a robust gyroscope calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(double[] qualityScores)
      Creates a robust gyroscope calibrator using default robust method.
      Parameters:
      qualityScores - quality scores corresponding to each provided measurement. The larger the score value the better the quality of the sample.
      Returns:
      a robust gyroscope calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(double[] qualityScores, RobustKnownFrameGyroscopeCalibratorListener listener)
      Creates a robust gyroscope calibrator using default robust method.
      Parameters:
      qualityScores - quality scores corresponding to each provided measurement. The larger the score value the better the quality of the sample.
      listener - listener to be notified of events such as when estimation starts, ends or its progress significantly changes.
      Returns:
      a robust gyroscope calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(double[] qualityScores, List<StandardDeviationFrameBodyKinematics> measurements)
      Creates a robust gyroscope calibrator using default robust method
      Parameters:
      qualityScores - quality scores corresponding to each provided measurement. The larger the score value the better the quality of the sample.
      measurements - list of body kinematics measurements with standard deviations taken at different frames (positions, orientations and velocities).
      Returns:
      a robust gyroscope calibrator.
    • create

      Creates a robust gyroscope calibrator using default robust method.
      Parameters:
      qualityScores - quality scores corresponding to each provided measurement. The larger the score value the better the quality of the sample.
      measurements - list of body kinematics measurements with standard deviations taken at different frames (positions, orientations and velocities).
      listener - listener to handle events raised by this calibrator.
      Returns:
      a robust gyroscope calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(double[] qualityScores, boolean commonAxisUsed)
      Creates a robust gyroscope calibrator using default robust method.
      Parameters:
      qualityScores - quality scores corresponding to each provided measurement. The larger the score value the better the quality of the sample.
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
      Returns:
      a robust gyroscope calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(double[] qualityScores, boolean commonAxisUsed, RobustKnownFrameGyroscopeCalibratorListener listener)
      Creates a robust gyroscope calibrator using default robust method.
      Parameters:
      qualityScores - quality scores corresponding to each provided measurement. The larger the score value the better the quality of the sample.
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
      listener - listener to handle events raised by this calibrator.
      Returns:
      a robust gyroscope calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(double[] qualityScores, List<StandardDeviationFrameBodyKinematics> measurements, boolean commonAxisUsed)
      Creates a robust gyroscope calibrator using default robust method.
      Parameters:
      qualityScores - quality scores corresponding to each provided measurement. The larger the score value the better the quality of the sample.
      measurements - list of body kinematics measurements with standard deviations taken at different frames (positions, orientations and velocities).
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
      Returns:
      a robust gyroscope calibrator.
    • create

      public static RobustKnownFrameGyroscopeCalibrator create(double[] qualityScores, List<StandardDeviationFrameBodyKinematics> measurements, boolean commonAxisUsed, RobustKnownFrameGyroscopeCalibratorListener listener)
      Creates a robust gyroscope calibrator using default robust method.
      Parameters:
      qualityScores - quality scores corresponding to each provided measurement. The larger the score value the better the quality of the sample.
      measurements - list of body kinematics measurements with standard deviations taken at different frames (positions, orientations and velocities).
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
      listener - listener to handle events raised by this calibrator.
      Returns:
      a robust gyroscope calibrator.
    • computeError

      protected double computeError(StandardDeviationFrameBodyKinematics measurement, RobustKnownFrameGyroscopeCalibrator.PreliminaryResult preliminaryResult)
      Computes error of a preliminary result respect a given measurement.
      Parameters:
      measurement - a measurement.
      preliminaryResult - a preliminary result.
      Returns:
      computed error.
    • computePreliminarySolutions

      protected void computePreliminarySolutions(int[] samplesIndices, List<RobustKnownFrameGyroscopeCalibrator.PreliminaryResult> solutions)
      Computes a preliminary solution for a subset of samples picked by a robust estimator.
      Parameters:
      samplesIndices - indices of samples picked by the robust estimator.
      solutions - list where estimated preliminary solution will be stored.
    • attemptRefine

      protected void attemptRefine(RobustKnownFrameGyroscopeCalibrator.PreliminaryResult preliminaryResult)
      Attempts to refine calibration parameters if refinement is requested. This method returns a refined solution or provided input if refinement is not requested or has failed. If refinement is enabled and it is requested to keep covariance, this method will also keep covariance of refined position.
      Parameters:
      preliminaryResult - a preliminary result.
    • convertAngularSpeed

      private static double convertAngularSpeed(double value, com.irurueta.units.AngularSpeedUnit unit)
      Converts angular speed value and unit to radians per second.
      Parameters:
      value - angular speed value.
      unit - unit of angular speed value.
      Returns:
      converted value.
    • convertAngularSpeed

      private static double convertAngularSpeed(com.irurueta.units.AngularSpeed angularSpeed)
      Converts angular speed instance to radians per second.
      Parameters:
      angularSpeed - angular speed instance to be converted.
      Returns:
      converted value.