Class KnownFrameGyroscopeLinearLeastSquaresCalibrator

java.lang.Object
com.irurueta.navigation.inertial.calibration.gyroscope.KnownFrameGyroscopeLinearLeastSquaresCalibrator
All Implemented Interfaces:
GyroscopeCalibrator, KnownFrameGyroscopeCalibrator<FrameBodyKinematics,KnownFrameGyroscopeLinearLeastSquaresCalibratorListener>, UnknownBiasGyroscopeCalibrator, UnorderedFrameBodyKinematicsGyroscopeCalibrator, GyroscopeCalibrationSource

Estimates gyroscope biases, cross couplings and scaling factors along with G-dependent cross biases introduced on the gyroscope by the specific forces sensed by the accelerometer.

This calibrator uses a linear approach to find a minimum least squared error solution.

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:
    • EQUATIONS_PER_MEASUREMENT

      private static final int EQUATIONS_PER_MEASUREMENT
      Number of equations generated for each measurement.
      See Also:
    • COMMON_Z_AXIS_UNKNOWNS

      private static final int COMMON_Z_AXIS_UNKNOWNS
      Number of unknowns when common z-axis is assumed for both the accelerometer and gyroscope.
      See Also:
    • GENERAL_UNKNOWNS

      private static final int GENERAL_UNKNOWNS
      Number of unknowns for the general case.
      See Also:
    • measurements

      private Collection<FrameBodyKinematics> measurements
      Contains a collection of body kinematics measurements taken at different frames (positions, orientations and velocities). 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.
    • 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 Mg matrix.
    • listener

      Listener to handle events raised by this calibrator.
    • estimatedBiases

      private double[] estimatedBiases
      Estimated angular rate 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.
    • running

      private boolean running
      Indicates whether calibrator is running.
  • Constructor Details

    • KnownFrameGyroscopeLinearLeastSquaresCalibrator

      public KnownFrameGyroscopeLinearLeastSquaresCalibrator()
      Constructor.
    • KnownFrameGyroscopeLinearLeastSquaresCalibrator

      public KnownFrameGyroscopeLinearLeastSquaresCalibrator(KnownFrameGyroscopeLinearLeastSquaresCalibratorListener listener)
      Constructor.
      Parameters:
      listener - listener to handle events raised by this calibrator.
    • KnownFrameGyroscopeLinearLeastSquaresCalibrator

      public KnownFrameGyroscopeLinearLeastSquaresCalibrator(Collection<? extends FrameBodyKinematics> measurements)
      Constructor.
      Parameters:
      measurements - collection of body kinematics measurements taken at different frames (positions, orientations and velocities).
    • KnownFrameGyroscopeLinearLeastSquaresCalibrator

      public KnownFrameGyroscopeLinearLeastSquaresCalibrator(Collection<? extends FrameBodyKinematics> measurements, KnownFrameGyroscopeLinearLeastSquaresCalibratorListener listener)
      Constructor.
      Parameters:
      measurements - collection of body kinematics measurements taken at different frames (positions, orientations and velocities).
      listener - listener to handle events raised by this calibrator.
    • KnownFrameGyroscopeLinearLeastSquaresCalibrator

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

      public KnownFrameGyroscopeLinearLeastSquaresCalibrator(boolean commonAxisUsed, KnownFrameGyroscopeLinearLeastSquaresCalibratorListener 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.
    • KnownFrameGyroscopeLinearLeastSquaresCalibrator

      public KnownFrameGyroscopeLinearLeastSquaresCalibrator(Collection<? extends FrameBodyKinematics> measurements, boolean commonAxisUsed)
      Constructor.
      Parameters:
      measurements - collection of body kinematics measurements taken at different frames (positions, orientations and velocities).
      commonAxisUsed - indicates whether z-axis is assumed to be common for accelerometer and gyroscope.
    • KnownFrameGyroscopeLinearLeastSquaresCalibrator

      public KnownFrameGyroscopeLinearLeastSquaresCalibrator(Collection<? extends FrameBodyKinematics> measurements, boolean commonAxisUsed, KnownFrameGyroscopeLinearLeastSquaresCalibratorListener listener)
      Constructor.
      Parameters:
      measurements - collection of body kinematics measurements 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

    • getMeasurements

      public Collection<FrameBodyKinematics> getMeasurements()
      Gets a collection of body kinematics measurements taken at different frames (positions, orientations and velocities). 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.
      Specified by:
      getMeasurements in interface KnownFrameGyroscopeCalibrator<FrameBodyKinematics,KnownFrameGyroscopeLinearLeastSquaresCalibratorListener>
      Specified by:
      getMeasurements in interface UnorderedFrameBodyKinematicsGyroscopeCalibrator
      Returns:
      a collection of body kinematics measurements taken at different frames (positions, orientations and velocities).
    • setMeasurements

      public void setMeasurements(Collection<? extends FrameBodyKinematics> measurements) throws com.irurueta.navigation.LockedException
      Sets a collection of body kinematics measurements taken at different frames (positions, orientations and velocities). 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 KnownFrameGyroscopeCalibrator<FrameBodyKinematics,KnownFrameGyroscopeLinearLeastSquaresCalibratorListener>
      Specified by:
      setMeasurements in interface UnorderedFrameBodyKinematicsGyroscopeCalibrator
      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.
    • isQualityScoresRequired

      public boolean isQualityScoresRequired()
      Indicates whether this calibrator requires quality scores for each measurement/sequence or not.
      Specified by:
      isQualityScoresRequired in interface GyroscopeCalibrator
      Returns:
      true if quality scores are required, 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 Mg 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 Mg 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 calibrator.
      Specified by:
      getListener in interface KnownFrameGyroscopeCalibrator<FrameBodyKinematics,KnownFrameGyroscopeLinearLeastSquaresCalibratorListener>
      Returns:
      listener to handle events raised by this calibrator.
    • setListener

      public void setListener(KnownFrameGyroscopeLinearLeastSquaresCalibratorListener listener) throws com.irurueta.navigation.LockedException
      Sets listener to handle events raised by this calibrator.
      Specified by:
      setListener in interface KnownFrameGyroscopeCalibrator<FrameBodyKinematics,KnownFrameGyroscopeLinearLeastSquaresCalibratorListener>
      Parameters:
      listener - listener to handle events raised by this calibrator.
      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 the calibration.
      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.
    • calibrate

      public void calibrate() throws com.irurueta.navigation.LockedException, com.irurueta.navigation.NotReadyException, CalibrationException
      Estimates gyroscope calibration parameters containing bias, scale factors, cross-coupling errors and g-dependant cross biases.
      Specified by:
      calibrate in interface GyroscopeCalibrator
      Throws:
      com.irurueta.navigation.LockedException - if calibrator is currently running.
      com.irurueta.navigation.NotReadyException - if calibrator is not ready.
      CalibrationException - if calibration fails for numerical reasons.
    • 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 component 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.
    • 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.
      Specified by:
      getEstimatedGg in interface GyroscopeCalibrationSource
      Specified by:
      getEstimatedGg in interface GyroscopeCalibrator
      Returns:
      a 3x3 matrix containing g-dependent cross biases.
    • calibrateCommonAxis

      private void calibrateCommonAxis() throws com.irurueta.algebra.AlgebraException
      Internal method to perform calibration when common z-axis is assumed for both the accelerometer and gyroscope.
      Throws:
      com.irurueta.algebra.AlgebraException - if there are numerical errors.
    • calibrateGeneral

      private void calibrateGeneral() throws com.irurueta.algebra.AlgebraException
      Internal method to perform general calibration.
      Throws:
      com.irurueta.algebra.AlgebraException - if there are numerical errors.
    • fillBiases

      private void fillBiases(double bx, double by, double bz)
      Fills estimated biases array with estimated values.
      Parameters:
      bx - x coordinate of bias.
      by - y coordinate of bias.
      bz - z coordinate of bias.
    • fillMg

      private void fillMg(double sx, double sy, double sz, double mxy, double mxz, double myx, double myz, double mzx, double mzy) throws com.irurueta.algebra.WrongSizeException
      Fills scale factor and cross coupling error matrix with estimated values.
      Parameters:
      sx - x scale factor
      sy - y scale factor
      sz - z scale factor
      mxy - x-y cross coupling
      mxz - x-z cross coupling
      myx - y-x cross coupling
      myz - y-z cross coupling
      mzx - z-x cross coupling
      mzy - z-y cross coupling
      Throws:
      com.irurueta.algebra.WrongSizeException - never happens.
    • fillGg

      private void fillGg(double g11, double g12, double g13, double g21, double g22, double g23, double g31, double g32, double g33) throws com.irurueta.algebra.WrongSizeException
      Fills G-dependant cross biases.
      Parameters:
      g11 - element 1,1 of G-dependant cross biases matrix.
      g12 - element 1,2 of G-dependant cross biases matrix.
      g13 - element 1,3 of G-dependant cross biases matrix.
      g21 - element 2,1 of G-dependant cross biases matrix.
      g22 - element 2,2 of G-dependant cross biases matrix.
      g23 - element 2,3 of G-dependant cross biases matrix.
      g31 - element 3,1 of G-dependant cross biases matrix.
      g32 - element 3,2 of G-dependant cross biases matrix.
      g33 - element 3,3 of G-dependant cross biases matrix.
      Throws:
      com.irurueta.algebra.WrongSizeException - never happens.