Class BodyKinematicsFixer

java.lang.Object
com.irurueta.navigation.inertial.calibration.BodyKinematicsFixer

public class BodyKinematicsFixer extends Object
Fixes body kinematics (acceleration + angular rate) values taking into account provided biases, cross coupling errors and G-dependent errors.
  • Field Details

    • accelerationFixer

      private final AccelerationFixer accelerationFixer
      Fixes specific force (acceleration) components of body kinematics measurements.
    • angularRateFixer

      private final AngularRateFixer angularRateFixer
      Fixes angular rate components of body kinematics measurements.
    • measuredAcceleration

      private final AccelerationTriad measuredAcceleration
      Contains measured acceleration to be reused.
    • measuredAngularSpeed

      private final AngularSpeedTriad measuredAngularSpeed
      Contains measured angular speed to be reused.
    • fixedAcceleration

      private final AccelerationTriad fixedAcceleration
      Contains fixed acceleration to be reused.
    • fixedAngularSpeed

      private final AngularSpeedTriad fixedAngularSpeed
      Contains fixed angular speed to be reused.
  • Constructor Details

    • BodyKinematicsFixer

      public BodyKinematicsFixer()
  • Method Details

    • getAccelerationBias

      public com.irurueta.algebra.Matrix getAccelerationBias()
      Gets acceleration bias values expressed in meters per squared second (m/s^2).
      Returns:
      bias values expressed in meters per squared second.
    • getAccelerationBias

      public void getAccelerationBias(com.irurueta.algebra.Matrix result)
      Gets acceleration bias values expressed in meters per squared second (m/s^2).
      Parameters:
      result - instance where result will be stored.
    • setAccelerationBias

      public void setAccelerationBias(com.irurueta.algebra.Matrix bias)
      Sets acceleration bias values expressed in meters per squared second (m/s^2).
      Parameters:
      bias - bias values expressed in meters per squared second. Must be 3x1.
      Throws:
      IllegalArgumentException - if provided matrix is not 3x1.
    • getAccelerationBiasArray

      public double[] getAccelerationBiasArray()
      Gets acceleration bias values expressed in meters per squared second (m/s^2).
      Returns:
      bias values expressed in meters per squared second.
    • getAccelerationBiasArray

      public void getAccelerationBiasArray(double[] result)
      Gets acceleration bias values expressed in meters per squared second (m/s^2).
      Parameters:
      result - instance where result data will be stored.
      Throws:
      IllegalArgumentException - if provided array does not have length 3.
    • setAccelerationBias

      public void setAccelerationBias(double[] bias)
      Sets acceleration bias values expressed in meters per squared second (m/s^2).
      Parameters:
      bias - bias values expressed in meters per squared second (m/s^2). Must have length 3.
      Throws:
      IllegalArgumentException - if provided array does not have length 3.
    • getAccelerationBiasAsTriad

      public AccelerationTriad getAccelerationBiasAsTriad()
      Gets acceleration bias.
      Returns:
      acceleration bias.
    • getAccelerationBiasAsTriad

      public void getAccelerationBiasAsTriad(AccelerationTriad result)
      Gets acceleration bias.
      Parameters:
      result - instance where result will be stored.
    • setAccelerationBias

      public void setAccelerationBias(AccelerationTriad bias)
      Sets acceleration bias.
      Parameters:
      bias - acceleration bias to be set.
    • getAccelerationBiasX

      public double getAccelerationBiasX()
      Gets acceleration x-coordinate of bias expressed in meters per squared second (m/s^2).
      Returns:
      x-coordinate of bias expressed in meters per squared second (m/s^2).
    • setAccelerationBiasX

      public void setAccelerationBiasX(double biasX)
      Sets acceleration x-coordinate of bias expressed in meters per squared second (m/s^2).
      Parameters:
      biasX - x-coordinate of bias expressed in meters per squared second (m/s^2).
    • getAccelerationBiasY

      public double getAccelerationBiasY()
      Gets acceleration y-coordinate of bias expressed in meters per squared second (m/s^2).
      Returns:
      y-coordinate of bias expressed in meters per squared second (m/s^2).
    • setAccelerationBiasY

      public void setAccelerationBiasY(double biasY)
      Sets acceleration y-coordinate of bias expressed in meters per squared second (m/s^2).
      Parameters:
      biasY - y-coordinate of bias expressed in meters per squared second (m/s^2).
    • getAccelerationBiasZ

      public double getAccelerationBiasZ()
      Gets acceleration z-coordinate of bias expressed in meters per squared second (m/s^2).
      Returns:
      z-coordinate of bias expressed in meters per squared second (m/s^2).
    • setAccelerationBiasZ

      public void setAccelerationBiasZ(double biasZ)
      Sets acceleration z-coordinate of bias expressed in meters per squared second (m/s^2).
      Parameters:
      biasZ - z-coordinate of bias expressed in meters per squared second (m/s^2).
    • setAccelerationBias

      public void setAccelerationBias(double biasX, double biasY, double biasZ)
      Sets acceleration coordinates of bias expressed in meters per squared second (m/s^2).
      Parameters:
      biasX - x-coordinate of bias.
      biasY - y-coordinate of bias.
      biasZ - z-coordinate of bias.
    • getAccelerationBiasXAsAcceleration

      public com.irurueta.units.Acceleration getAccelerationBiasXAsAcceleration()
      Gets acceleration x-coordinate of bias.
      Returns:
      acceleration x-coordinate of bias.
    • getAccelerationBiasXAsAcceleration

      public void getAccelerationBiasXAsAcceleration(com.irurueta.units.Acceleration result)
      Gets acceleration x-coordinate of bias.
      Parameters:
      result - instance where result will be stored.
    • setAccelerationBiasX

      public void setAccelerationBiasX(com.irurueta.units.Acceleration biasX)
      Sets acceleration x-coordinate of bias.
      Parameters:
      biasX - acceleration x-coordinate of bias.
    • getAccelerationBiasYAsAcceleration

      public com.irurueta.units.Acceleration getAccelerationBiasYAsAcceleration()
      Gets acceleration y-coordinate of bias.
      Returns:
      acceleration y-coordinate of bias.
    • getAccelerationBiasYAsAcceleration

      public void getAccelerationBiasYAsAcceleration(com.irurueta.units.Acceleration result)
      Gets acceleration y-coordinate of bias.
      Parameters:
      result - instance where result will be stored.
    • setAccelerationBiasY

      public void setAccelerationBiasY(com.irurueta.units.Acceleration biasY)
      Sets acceleration y-coordinate of bias.
      Parameters:
      biasY - acceleration y-coordinate of bias.
    • getAccelerationBiasZAsAcceleration

      public com.irurueta.units.Acceleration getAccelerationBiasZAsAcceleration()
      Gets acceleration z-coordinate of bias.
      Returns:
      acceleration z-coordinate of bias.
    • getAccelerationBiasZAsAcceleration

      public void getAccelerationBiasZAsAcceleration(com.irurueta.units.Acceleration result)
      Gets acceleration z-coordinate of bias.
      Parameters:
      result - instance where result will be stored.
    • setAccelerationBiasZ

      public void setAccelerationBiasZ(com.irurueta.units.Acceleration biasZ)
      Sets acceleration z-coordinate of bias.
      Parameters:
      biasZ - z-coordinate of bias.
    • setAccelerationBias

      public void setAccelerationBias(com.irurueta.units.Acceleration biasX, com.irurueta.units.Acceleration biasY, com.irurueta.units.Acceleration biasZ)
      Sets acceleration coordinates of bias.
      Parameters:
      biasX - x-coordinate of bias.
      biasY - y-coordinate of bias.
      biasZ - z-coordinate of bias.
    • getAccelerationCrossCouplingErrors

      public com.irurueta.algebra.Matrix getAccelerationCrossCouplingErrors()
      Gets acceleration cross coupling errors matrix.
      Returns:
      acceleration cross coupling errors matrix.
    • getAccelerationCrossCouplingErrors

      public void getAccelerationCrossCouplingErrors(com.irurueta.algebra.Matrix result)
      Gets acceleration cross coupling errors matrix.
      Parameters:
      result - instance where result will be stored.
    • setAccelerationCrossCouplingErrors

      public void setAccelerationCrossCouplingErrors(com.irurueta.algebra.Matrix crossCouplingErrors) throws com.irurueta.algebra.AlgebraException
      Sets acceleration cross coupling errors matrix.
      Parameters:
      crossCouplingErrors - acceleration cross coupling errors matrix. Must be 3x3.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided matrix cannot be inverted.
      IllegalArgumentException - if provided matrix is not 3x3.
    • getAccelerationSx

      public double getAccelerationSx()
      Gets acceleration x scaling factor.
      Returns:
      x scaling factor.
    • setAccelerationSx

      public void setAccelerationSx(double sx) throws com.irurueta.algebra.AlgebraException
      Sets acceleration x scaling factor.
      Parameters:
      sx - x scaling factor.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided value makes cross coupling matrix non-invertible.
    • getAccelerationSy

      public double getAccelerationSy()
      Gets acceleration y scaling factor.
      Returns:
      y scaling factor.
    • setAccelerationSy

      public void setAccelerationSy(double sy) throws com.irurueta.algebra.AlgebraException
      Sets acceleration y scaling factor.
      Parameters:
      sy - y scaling factor.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided value makes cross coupling matrix non-invertible.
    • getAccelerationSz

      public double getAccelerationSz()
      Gets acceleration z scaling factor.
      Returns:
      z scaling factor.
    • setAccelerationSz

      public void setAccelerationSz(double sz) throws com.irurueta.algebra.AlgebraException
      Sets acceleration z scaling factor.
      Parameters:
      sz - z scaling factor.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided value makes cross coupling matrix non-invertible.
    • getAccelerationMxy

      public double getAccelerationMxy()
      Gets acceleration x-y cross coupling error.
      Returns:
      acceleration x-y cross coupling error.
    • setAccelerationMxy

      public void setAccelerationMxy(double mxy) throws com.irurueta.algebra.AlgebraException
      Sets acceleration x-y cross coupling error.
      Parameters:
      mxy - acceleration x-y cross coupling error.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided value makes cross coupling matrix non-invertible.
    • getAccelerationMxz

      public double getAccelerationMxz()
      Gets acceleration x-z cross coupling error.
      Returns:
      acceleration x-z cross coupling error.
    • setAccelerationMxz

      public void setAccelerationMxz(double mxz) throws com.irurueta.algebra.AlgebraException
      Sets acceleration x-z cross coupling error.
      Parameters:
      mxz - acceleration x-z cross coupling error.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided value makes cross coupling matrix non-invertible.
    • getAccelerationMyx

      public double getAccelerationMyx()
      Gets acceleration y-x cross coupling error.
      Returns:
      acceleration y-x cross coupling error.
    • setAccelerationMyx

      public void setAccelerationMyx(double myx) throws com.irurueta.algebra.AlgebraException
      Sets acceleration y-x cross coupling error.
      Parameters:
      myx - acceleration y-x cross coupling error.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided value makes cross coupling matrix non-invertible.
    • getAccelerationMyz

      public double getAccelerationMyz()
      Gets acceleration y-z cross coupling error.
      Returns:
      y-z cross coupling error.
    • setAccelerationMyz

      public void setAccelerationMyz(double myz) throws com.irurueta.algebra.AlgebraException
      Sets acceleration y-z cross coupling error.
      Parameters:
      myz - y-z cross coupling error.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided value makes cross coupling matrix non-invertible.
    • getAccelerationMzx

      public double getAccelerationMzx()
      Gets acceleration z-x cross coupling error.
      Returns:
      acceleration z-x cross coupling error.
    • setAccelerationMzx

      public void setAccelerationMzx(double mzx) throws com.irurueta.algebra.AlgebraException
      Sets acceleration z-x cross coupling error.
      Parameters:
      mzx - acceleration z-x cross coupling error.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided value makes cross coupling matrix non-invertible.
    • getAccelerationMzy

      public double getAccelerationMzy()
      Gets acceleration z-y cross coupling error.
      Returns:
      acceleration z-y cross coupling error.
    • setAccelerationMzy

      public void setAccelerationMzy(double mzy) throws com.irurueta.algebra.AlgebraException
      Sets acceleration z-y cross coupling error.
      Parameters:
      mzy - acceleration z-y cross coupling error.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided value makes cross coupling matrix non-invertible.
    • setAccelerationScalingFactors

      public void setAccelerationScalingFactors(double sx, double sy, double sz) throws com.irurueta.algebra.AlgebraException
      Sets acceleration scaling factors.
      Parameters:
      sx - x scaling factor.
      sy - y scaling factor.
      sz - z scaling factor.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided values make cross coupling matrix non-invertible.
    • setAccelerationCrossCouplingErrors

      public void setAccelerationCrossCouplingErrors(double mxy, double mxz, double myx, double myz, double mzx, double mzy) throws com.irurueta.algebra.AlgebraException
      Sets acceleration cross coupling errors.
      Parameters:
      mxy - x-y cross coupling error.
      mxz - x-z cross coupling error.
      myx - y-x cross coupling error.
      myz - y-z cross coupling error.
      mzx - z-x cross coupling error.
      mzy - z-y cross coupling error.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided values make cross coupling matrix non-invertible.
    • setAccelerationScalingFactorsAndCrossCouplingErrors

      public void setAccelerationScalingFactorsAndCrossCouplingErrors(double sx, double sy, double sz, double mxy, double mxz, double myx, double myz, double mzx, double mzy) throws com.irurueta.algebra.AlgebraException
      Sets acceleration scaling factors and cross coupling errors.
      Parameters:
      sx - x scaling factor.
      sy - y scaling factor.
      sz - z scaling factor.
      mxy - x-y cross coupling error.
      mxz - x-z cross coupling error.
      myx - y-x cross coupling error.
      myz - y-z cross coupling error.
      mzx - z-x cross coupling error.
      mzy - z-y cross coupling error.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided values make cross coupling matrix non-invertible.
    • getAngularSpeedBias

      public com.irurueta.algebra.Matrix getAngularSpeedBias()
      Gets angular speed bias values expressed in radians per second (rad/s).
      Returns:
      angular speed bias values expressed in radians per second.
    • getAngularSpeedBias

      public void getAngularSpeedBias(com.irurueta.algebra.Matrix result)
      Gets angular speed bias values expressed in radians per second (rad/s).
      Parameters:
      result - instance where result will be stored.
    • setAngularSpeedBias

      public void setAngularSpeedBias(com.irurueta.algebra.Matrix bias)
      Sets angular speed bias values expressed in radians per second (rad/s).
      Parameters:
      bias - bias values expressed in radians per second. Must be 3x1.
      Throws:
      IllegalArgumentException - if provided matrix is not 3x1.
    • getAngularSpeedBiasArray

      public double[] getAngularSpeedBiasArray()
      Gets angular speed bias values expressed in radians per second (rad/s).
      Returns:
      bias values expressed in radians per second.
    • getAngularSpeedBiasArray

      public void getAngularSpeedBiasArray(double[] result)
      Gets angular speed bias values expressed in radians per second (rad/s).
      Parameters:
      result - instance where result data will be stored.
      Throws:
      IllegalArgumentException - if provided array does not have length 3.
    • setAngularSpeedBias

      public void setAngularSpeedBias(double[] bias)
      Sets angular speed bias values expressed in radians per second (rad/s).
      Parameters:
      bias - bias values expressed in radians per second (rad/s). Must have length 3.
      Throws:
      IllegalArgumentException - if provided array does not have length 3.
    • getAngularSpeedBiasAsTriad

      public AngularSpeedTriad getAngularSpeedBiasAsTriad()
      Gets angular speed bias.
      Returns:
      angular speed bias.
    • getAngularSpeedBiasAsTriad

      public void getAngularSpeedBiasAsTriad(AngularSpeedTriad result)
      Gets angular speed bias.
      Parameters:
      result - instance where result will be stored.
    • setAngularSpeedBias

      public void setAngularSpeedBias(AngularSpeedTriad bias)
      Sets angular speed bias.
      Parameters:
      bias - angular speed bias to be set.
    • getAngularSpeedBiasX

      public double getAngularSpeedBiasX()
      Gets angular speed x-coordinate of bias expressed in radians per second (rad/s).
      Returns:
      x-coordinate of bias expressed in radians per second (rad/s).
    • setAngularSpeedBiasX

      public void setAngularSpeedBiasX(double biasX)
      Sets angular speed x-coordinate of bias expressed in radians per second (rad/s).
      Parameters:
      biasX - x-coordinate of bias expressed in radians per second (rad/s).
    • getAngularSpeedBiasY

      public double getAngularSpeedBiasY()
      Gets angular speed y-coordinate of bias expressed in radians per second (rad/s).
      Returns:
      y-coordinate of bias expressed in radians per second (rad/s).
    • setAngularSpeedBiasY

      public void setAngularSpeedBiasY(double biasY)
      Sets angular speed y-coordinate of bias expressed in radians per second (rad/s).
      Parameters:
      biasY - y-coordinate of bias expressed in radians per second (rad/s).
    • getAngularSpeedBiasZ

      public double getAngularSpeedBiasZ()
      Gets angular speed z-coordinate of bias expressed in radians per second (rad/s).
      Returns:
      z-coordinate of bias expressed in radians per second (rad/s).
    • setAngularSpeedBiasZ

      public void setAngularSpeedBiasZ(double biasZ)
      Sets angular speed z-coordinate of bias expressed in radians per second (rad/s).
      Parameters:
      biasZ - z-coordinate of bias expressed in radians per second (rad/s).
    • setAngularSpeedBias

      public void setAngularSpeedBias(double biasX, double biasY, double biasZ)
      Sets angular speed coordinates of bias expressed in radians per second (rad/s).
      Parameters:
      biasX - x-coordinate of bias.
      biasY - y-coordinate of bias.
      biasZ - z-coordinate of bias.
    • getAngularSpeedBiasXAsAngularSpeed

      public com.irurueta.units.AngularSpeed getAngularSpeedBiasXAsAngularSpeed()
      Gets angular speed x-coordinate of bias.
      Returns:
      x-coordinate of bias.
    • getAngularSpeedBiasXAsAngularSpeed

      public void getAngularSpeedBiasXAsAngularSpeed(com.irurueta.units.AngularSpeed result)
      Gets angular speed x-coordinate of bias.
      Parameters:
      result - instance where result will be stored.
    • setAngularSpeedBiasX

      public void setAngularSpeedBiasX(com.irurueta.units.AngularSpeed biasX)
      Sets angular speed x-coordinate of bias.
      Parameters:
      biasX - x-coordinate of bias.
    • getAngularSpeedBiasYAsAngularSpeed

      public com.irurueta.units.AngularSpeed getAngularSpeedBiasYAsAngularSpeed()
      Gets angular speed y-coordinate of bias.
      Returns:
      y-coordinate of bias.
    • getAngularSpeedBiasYAsAngularSpeed

      public void getAngularSpeedBiasYAsAngularSpeed(com.irurueta.units.AngularSpeed result)
      Gets angular speed y-coordinate of bias.
      Parameters:
      result - instance where result will be stored.
    • setAngularSpeedBiasY

      public void setAngularSpeedBiasY(com.irurueta.units.AngularSpeed biasY)
      Sets angular speed y-coordinate of bias.
      Parameters:
      biasY - y-coordinate of bias.
    • getAngularSpeedBiasZAsAngularSpeed

      public com.irurueta.units.AngularSpeed getAngularSpeedBiasZAsAngularSpeed()
      Gets angular speed z-coordinate of bias.
      Returns:
      z-coordinate of bias.
    • getAngularSpeedBiasZAsAngularSpeed

      public void getAngularSpeedBiasZAsAngularSpeed(com.irurueta.units.AngularSpeed result)
      Gets angular speed z-coordinate of bias.
      Parameters:
      result - instance where result will be stored.
    • setAngularSpeedBiasZ

      public void setAngularSpeedBiasZ(com.irurueta.units.AngularSpeed biasZ)
      Sets angular speed z-coordinate of bias.
      Parameters:
      biasZ - z-coordinate of bias.
    • setAngularSpeedBias

      public void setAngularSpeedBias(com.irurueta.units.AngularSpeed biasX, com.irurueta.units.AngularSpeed biasY, com.irurueta.units.AngularSpeed biasZ)
      Sets angular speed coordinates of bias.
      Parameters:
      biasX - x-coordinate of bias.
      biasY - y-coordinate of bias.
      biasZ - z-coordinate of bias.
    • getAngularSpeedCrossCouplingErrors

      public com.irurueta.algebra.Matrix getAngularSpeedCrossCouplingErrors()
      Gets angular speed cross coupling errors matrix.
      Returns:
      cross coupling errors matrix.
    • getAngularSpeedCrossCouplingErrors

      public void getAngularSpeedCrossCouplingErrors(com.irurueta.algebra.Matrix result)
      Gets angular speed cross coupling errors matrix.
      Parameters:
      result - instance where result will be stored.
    • setAngularSpeedCrossCouplingErrors

      public void setAngularSpeedCrossCouplingErrors(com.irurueta.algebra.Matrix crossCouplingErrors) throws com.irurueta.algebra.AlgebraException
      Sets angular speed cross coupling errors matrix.
      Parameters:
      crossCouplingErrors - cross coupling errors matrix. Must be 3x3.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided matrix cannot be inverted.
      IllegalArgumentException - if provided matrix is not 3x3.
    • getAngularSpeedSx

      public double getAngularSpeedSx()
      Gets angular speed x scaling factor.
      Returns:
      x scaling factor.
    • setAngularSpeedSx

      public void setAngularSpeedSx(double sx) throws com.irurueta.algebra.AlgebraException
      sets angular speed x scaling factor.
      Parameters:
      sx - x scaling factor.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided value makes cross coupling matrix non-invertible.
    • getAngularSpeedSy

      public double getAngularSpeedSy()
      Gets angular speed y scaling factor.
      Returns:
      y scaling factor.
    • setAngularSpeedSy

      public void setAngularSpeedSy(double sy) throws com.irurueta.algebra.AlgebraException
      Sets angular speed y scaling factor.
      Parameters:
      sy - y scaling factor.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided value makes cross coupling matrix non-invertible.
    • getAngularSpeedSz

      public double getAngularSpeedSz()
      Gets angular speed z scaling factor.
      Returns:
      z scaling factor.
    • setAngularSpeedSz

      public void setAngularSpeedSz(double sz) throws com.irurueta.algebra.AlgebraException
      Sets angular speed z scaling factor.
      Parameters:
      sz - z scaling factor.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided value makes cross coupling matrix non-invertible.
    • getAngularSpeedMxy

      public double getAngularSpeedMxy()
      Gets angular speed x-y cross coupling error.
      Returns:
      x-y cross coupling error.
    • setAngularSpeedMxy

      public void setAngularSpeedMxy(double mxy) throws com.irurueta.algebra.AlgebraException
      Sets angular speed x-y cross coupling error.
      Parameters:
      mxy - x-y cross coupling error.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided value makes cross coupling matrix non-invertible.
    • getAngularSpeedMxz

      public double getAngularSpeedMxz()
      Gets angular speed x-z cross coupling error.
      Returns:
      x-z cross coupling error.
    • setAngularSpeedMxz

      public void setAngularSpeedMxz(double mxz) throws com.irurueta.algebra.AlgebraException
      Sets angular speed x-z cross coupling error.
      Parameters:
      mxz - x-z cross coupling error.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided value makes cross coupling matrix non-invertible.
    • getAngularSpeedMyx

      public double getAngularSpeedMyx()
      Gets angular speed y-x cross coupling error.
      Returns:
      y-x cross coupling error.
    • setAngularSpeedMyx

      public void setAngularSpeedMyx(double myx) throws com.irurueta.algebra.AlgebraException
      Sets angular speed y-x cross coupling error.
      Parameters:
      myx - y-x cross coupling error.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided value makes cross coupling matrix non-invertible.
    • getAngularSpeedMyz

      public double getAngularSpeedMyz()
      Gets angular speed y-z cross coupling error.
      Returns:
      y-z cross coupling error.
    • setAngularSpeedMyz

      public void setAngularSpeedMyz(double myz) throws com.irurueta.algebra.AlgebraException
      Sets angular speed y-z cross coupling error.
      Parameters:
      myz - y-z cross coupling error.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided value makes cross coupling matrix non-invertible.
    • getAngularSpeedMzx

      public double getAngularSpeedMzx()
      Gets angular speed z-x cross coupling error.
      Returns:
      z-x cross coupling error.
    • setAngularSpeedMzx

      public void setAngularSpeedMzx(double mzx) throws com.irurueta.algebra.AlgebraException
      Sets angular speed z-x cross coupling error.
      Parameters:
      mzx - z-x cross coupling error.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided value makes cross coupling matrix non-invertible.
    • getAngularSpeedMzy

      public double getAngularSpeedMzy()
      Gets angular speed z-y cross coupling error.
      Returns:
      z-y cross coupling error.
    • setAngularSpeedMzy

      public void setAngularSpeedMzy(double mzy) throws com.irurueta.algebra.AlgebraException
      Sets angular speed z-y cross coupling error.
      Parameters:
      mzy - z-y cross coupling error.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided value makes cross coupling matrix non-invertible.
    • setAngularSpeedScalingFactors

      public void setAngularSpeedScalingFactors(double sx, double sy, double sz) throws com.irurueta.algebra.AlgebraException
      Sets angular speed scaling factors.
      Parameters:
      sx - x scaling factor.
      sy - y scaling factor.
      sz - z scaling factor.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided values make cross coupling matrix non-invertible.
    • setAngularSpeedCrossCouplingErrors

      public void setAngularSpeedCrossCouplingErrors(double mxy, double mxz, double myx, double myz, double mzx, double mzy) throws com.irurueta.algebra.AlgebraException
      Sets angular speed cross coupling errors.
      Parameters:
      mxy - x-y cross coupling error.
      mxz - x-z cross coupling error.
      myx - y-x cross coupling error.
      myz - y-z cross coupling error.
      mzx - z-x cross coupling error.
      mzy - z-y cross coupling error.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided values make cross coupling matrix non-invertible.
    • setAngularSpeedScalingFactorsAndCrossCouplingErrors

      public void setAngularSpeedScalingFactorsAndCrossCouplingErrors(double sx, double sy, double sz, double mxy, double mxz, double myx, double myz, double mzx, double mzy) throws com.irurueta.algebra.AlgebraException
      Sets angular speed scaling factors and cross coupling errors.
      Parameters:
      sx - x scaling factor.
      sy - y scaling factor.
      sz - z scaling factor.
      mxy - x-y cross coupling error.
      mxz - x-z cross coupling error.
      myx - y-x cross coupling error.
      myz - y-z cross coupling error.
      mzx - z-x cross coupling error.
      mzy - z-y cross coupling error.
      Throws:
      com.irurueta.algebra.AlgebraException - if provided values make cross coupling matrix non-invertible.
    • getAngularSpeedGDependantCrossBias

      public com.irurueta.algebra.Matrix getAngularSpeedGDependantCrossBias()
      Gets angular speed g-dependant cross biases matrix.
      Returns:
      g-dependant cross biases matrix.
    • getAngularSpeedGDependantCrossBias

      public void getAngularSpeedGDependantCrossBias(com.irurueta.algebra.Matrix result)
      Gets angular speed g-dependant cross biases matrix.
      Parameters:
      result - instance where result will be stored.
    • setAngularSpeedGDependantCrossBias

      public void setAngularSpeedGDependantCrossBias(com.irurueta.algebra.Matrix gDependantCrossBias)
      Sets angular speed g-dependant cross biases matrix.
      Parameters:
      gDependantCrossBias - g-dependant cross biases matrix.
      Throws:
      IllegalArgumentException - if provided matrix is not 3x3.
    • fix

      public void fix(BodyKinematics measuredKinematics, BodyKinematics result) throws com.irurueta.algebra.AlgebraException
      Fixes provided measured body kinematics by undoing the errors introduced by the accelerometer and gyroscope models to restore the true body kinematics values. This method uses last provided accelerometer and gyroscope bias and cross coupling errors.
      Parameters:
      measuredKinematics - measured body kinematics to be fixed.
      result - instance where fixed body kinematics will be stored.
      Throws:
      com.irurueta.algebra.AlgebraException - if there are numerical instabilities.
    • fix

      public void fix(AccelerationTriad measuredSpecificForce, AngularSpeedTriad measuredAngularSpeed, AccelerationTriad fixedSpecificForce, AngularSpeedTriad fixedAngularSpeed) throws com.irurueta.algebra.AlgebraException
      Fixes provided measured body kinematics by undoing the errors introduced by the accelerometer and gyroscope models to restore the true body kinematics values. This method uses last provided accelerometer and gyroscope bias and cross coupling errors.
      Parameters:
      measuredSpecificForce - measured specific force to be fixed.
      measuredAngularSpeed - measured angular speed to be fixed.
      fixedSpecificForce - instance where fixed specific force will be stored.
      fixedAngularSpeed - instance where fixed angular speed will be stored.
      Throws:
      com.irurueta.algebra.AlgebraException - if there are numerical instabilities.
    • fix

      public void fix(BodyKinematics measuredKinematics, AccelerationTriad fixedSpecificForce, AngularSpeedTriad fixedAngularSpeed) throws com.irurueta.algebra.AlgebraException
      Fixes provided measured body kinematics by undoing the errors introduced by the accelerometer and gyroscope models to restore the true body kinematics values. This method uses last provided accelerometer and gyroscope bias and cross coupling errors.
      Parameters:
      measuredKinematics - measured body kinematics to be fixed.
      fixedSpecificForce - instance where fixed specific force will be stored.
      fixedAngularSpeed - instance where fixed angular speed will be stored.
      Throws:
      com.irurueta.algebra.AlgebraException - if there are numerical instabilities.
    • fix

      public void fix(AccelerationTriad measuredSpecificForce, AngularSpeedTriad measuredAngularSpeed, BodyKinematics result) throws com.irurueta.algebra.AlgebraException
      Fixes provided measured body kinematics by undoing the errors introduced by the accelerometer and gyroscope models to restore the true body kinematics values. This method uses last provided accelerometer and gyroscope bias and cross coupling errors.
      Parameters:
      measuredSpecificForce - measured specific force to be fixed.
      measuredAngularSpeed - measured angular speed to be fixed.
      result - instance where fixed body kinematics will be stored.
      Throws:
      com.irurueta.algebra.AlgebraException - if there are numerical instabilities.
    • fixAndReturnNew

      public BodyKinematics fixAndReturnNew(BodyKinematics measuredKinematics) throws com.irurueta.algebra.AlgebraException
      Fixes provided measured body kinematics by undoing the errors introduced by the accelerometer and gyroscope models to restore the true body kinematics values. This method uses last provided accelerometer and gyroscope bias and cross coupling errors.
      Parameters:
      measuredKinematics - measured body kinematics to be fixed.
      Returns:
      restored true body kinematics.
      Throws:
      com.irurueta.algebra.AlgebraException - if there are numerical instabilities.
    • fixAndReturnNew

      public BodyKinematics fixAndReturnNew(AccelerationTriad measuredSpecificForce, AngularSpeedTriad measuredAngularSpeed) throws com.irurueta.algebra.AlgebraException
      Fixes provided measured body kinematics by undoing the errors introduced by the accelerometer and gyroscope models to restore the true body kinematics values. This method uses last provided accelerometer and gyroscope bias and cross coupling errors.
      Parameters:
      measuredSpecificForce - measured specific force to be fixed.
      measuredAngularSpeed - measured angular speed to be fixed.
      Returns:
      restored true body kinematics.
      Throws:
      com.irurueta.algebra.AlgebraException - if there are numerical instabilities.