Class INSLooselyCoupledKalmanConfigCreator

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

public class INSLooselyCoupledKalmanConfigCreator extends Object
Utility class to create INSLooselyCoupledKalmanConfig by combining different sources of estimated data. Sources of data can be any measurement generator, static interval detector or noise estimator implementing AccelerometerNoiseRootPsdSource or GyroscopeNoiseRootPsdSource.
  • Field Details

    • accelerometerNoiseRootPsdSource

      private com.irurueta.navigation.inertial.calibration.AccelerometerNoiseRootPsdSource accelerometerNoiseRootPsdSource
      A source of estimated accelerometer noise root PSD.
    • gyroscopeNoiseRootPsdSource

      private com.irurueta.navigation.inertial.calibration.GyroscopeNoiseRootPsdSource gyroscopeNoiseRootPsdSource
      A source of estimated gyroscope noise root PSD.
    • accelerometerBiasRandomWalkSource

      private AccelerometerBiasRandomWalkSource accelerometerBiasRandomWalkSource
      A source of estimated accelerometer bias random walk PSD.
    • gyroscopeBiasRandomWalkSource

      private GyroscopeBiasRandomWalkSource gyroscopeBiasRandomWalkSource
      A source of estimated gyroscope bias random walk PSD.
    • positionNoiseStandardDeviationSource

      private PositionNoiseStandardDeviationSource positionNoiseStandardDeviationSource
      A source of position noise standard deviation.
    • velocityNoiseStandardDeviationSource

      private VelocityNoiseStandardDeviationSource velocityNoiseStandardDeviationSource
      A source of velocity noise standard deviation.
  • Constructor Details

    • INSLooselyCoupledKalmanConfigCreator

      public INSLooselyCoupledKalmanConfigCreator()
      Constructor.
    • INSLooselyCoupledKalmanConfigCreator

      public INSLooselyCoupledKalmanConfigCreator(com.irurueta.navigation.inertial.calibration.AccelerometerNoiseRootPsdSource accelerometerNoiseRootPsdSource, com.irurueta.navigation.inertial.calibration.GyroscopeNoiseRootPsdSource gyroscopeNoiseRootPsdSource, AccelerometerBiasRandomWalkSource accelerometerBiasRandomWalkSource, GyroscopeBiasRandomWalkSource gyroscopeBiasRandomWalkSource, PositionNoiseStandardDeviationSource positionNoiseStandardDeviationSource, VelocityNoiseStandardDeviationSource velocityNoiseStandardDeviationSource)
      Constructor.
      Parameters:
      accelerometerNoiseRootPsdSource - a source of estimated accelerometer noise root PSD.
      gyroscopeNoiseRootPsdSource - a source of estimated gyroscope noise root PSD.
      accelerometerBiasRandomWalkSource - a source of estimated accelerometer bias random walk PSD.
      gyroscopeBiasRandomWalkSource - a source of estimated gyroscope bias random walk PSD.
      positionNoiseStandardDeviationSource - a source of position noise standard deviation.
      velocityNoiseStandardDeviationSource - a source of velocity noise standard deviation.
    • INSLooselyCoupledKalmanConfigCreator

      public INSLooselyCoupledKalmanConfigCreator(com.irurueta.navigation.inertial.calibration.generators.AccelerometerAndGyroscopeMeasurementsGenerator generator, RandomWalkEstimator randomWalkEstimator)
      Constructor.
      Parameters:
      generator - an accelerometer + gyroscope measurement generator.
      randomWalkEstimator - a random walk estimator.
    • INSLooselyCoupledKalmanConfigCreator

      public INSLooselyCoupledKalmanConfigCreator(com.irurueta.navigation.inertial.calibration.generators.AccelerometerGyroscopeAndMagnetometerMeasurementsGenerator generator, RandomWalkEstimator randomWalkEstimator)
      Constructor.
      Parameters:
      generator - an accelerometer + gyroscope + magnetometer measurement generator.
      randomWalkEstimator - a random walk estimator.
    • INSLooselyCoupledKalmanConfigCreator

      public INSLooselyCoupledKalmanConfigCreator(AccelerometerAndGyroscopeIntervalDetectorThresholdFactorOptimizer optimizer, RandomWalkEstimator randomWalkEstimator)
      Constructor.
      Parameters:
      optimizer - an accelerometer and gyroscope threshold factor optimizer.
      randomWalkEstimator - a random walk estimator.
    • INSLooselyCoupledKalmanConfigCreator

      public INSLooselyCoupledKalmanConfigCreator(AccelerometerGyroscopeAndMagnetometerIntervalDetectorThresholdFactorOptimizer optimizer, RandomWalkEstimator randomWalkEstimator)
      Constructor.
      Parameters:
      optimizer - an accelerometer + gyroscope + magnetometer threshold factor optimizer.
      randomWalkEstimator - a random walk estimator.
  • Method Details

    • getAccelerometerNoiseRootPsdSource

      public com.irurueta.navigation.inertial.calibration.AccelerometerNoiseRootPsdSource getAccelerometerNoiseRootPsdSource()
      Gets the source of estimated accelerometer noise root PSD.
      Returns:
      source of estimated accelerometer noise root PSD.
    • setAccelerometerNoiseRootPsdSource

      public void setAccelerometerNoiseRootPsdSource(com.irurueta.navigation.inertial.calibration.AccelerometerNoiseRootPsdSource accelerometerNoiseRootPsdSource)
      Sets source of estimated accelerometer noise root PSD.
      Parameters:
      accelerometerNoiseRootPsdSource - source of estimated accelerometer noise root PSD.
    • getGyroscopeNoiseRootPsdSource

      public com.irurueta.navigation.inertial.calibration.GyroscopeNoiseRootPsdSource getGyroscopeNoiseRootPsdSource()
      Gets the source of estimated gyroscope noise root PSD.
      Returns:
      source of estimated gyroscope noise root PSD.
    • sstGyroscopeNoiseRootPsdSource

      public void sstGyroscopeNoiseRootPsdSource(com.irurueta.navigation.inertial.calibration.GyroscopeNoiseRootPsdSource gyroscopeNoiseRootPsdSource)
      Sets source of estimated gyroscope noise root PSD.
      Parameters:
      gyroscopeNoiseRootPsdSource - source of estimated gyroscope noise root PSD.
    • getAccelerometerBiasRandomWalkSource

      public AccelerometerBiasRandomWalkSource getAccelerometerBiasRandomWalkSource()
      Gets the source of estimated accelerometer bias random walk PSD.
      Returns:
      source of estimated accelerometer bias random walk PSD.
    • setAccelerometerBiasRandomWalkSource

      public void setAccelerometerBiasRandomWalkSource(AccelerometerBiasRandomWalkSource accelerometerBiasRandomWalkSource)
      Sets source of estimated accelerometer bias random walk PSD.
      Parameters:
      accelerometerBiasRandomWalkSource - source of estimated accelerometer bias random walk PSD.
    • getGyroscopeBiasRandomWalkSource

      public GyroscopeBiasRandomWalkSource getGyroscopeBiasRandomWalkSource()
      Gets the source of estimated gyroscope bias random walk PSD.
      Returns:
      source of estimated gyroscope bias random walk PSD.
    • setGyroscopeBiasRandomWalkSource

      public void setGyroscopeBiasRandomWalkSource(GyroscopeBiasRandomWalkSource gyroscopeBiasRandomWalkSource)
      Sets source of estimated gyroscope bias random walk PSD.
      Parameters:
      gyroscopeBiasRandomWalkSource - source of estimated gyroscope bias random walk PSD.
    • getPositionNoiseStandardDeviationSource

      public PositionNoiseStandardDeviationSource getPositionNoiseStandardDeviationSource()
      Gets the source of position noise standard deviation.
      Returns:
      source of position noise standard deviation.
    • setPositionNoiseStandardDeviationSource

      public void setPositionNoiseStandardDeviationSource(PositionNoiseStandardDeviationSource positionUncertaintySource)
      Sets source of position noise standard deviation.
      Parameters:
      positionUncertaintySource - source of position noise standard deviation.
    • getVelocityNoiseStandardDeviationSource

      public VelocityNoiseStandardDeviationSource getVelocityNoiseStandardDeviationSource()
      Gets the source of velocity noise standard deviation.
      Returns:
      source of velocity noise standard deviation.
    • setVelocityNoiseStandardDeviationSource

      public void setVelocityNoiseStandardDeviationSource(VelocityNoiseStandardDeviationSource velocityUncertaintySource)
      Sets source of velocity noise standard deviation.
      Parameters:
      velocityUncertaintySource - source of velocity noise standard deviation.
    • isReady

      public boolean isReady()
      Indicates whether all sources have been provided to be able to create a INSLooselyCoupledKalmanConfig instance.
      Returns:
      true if the creator is ready, false otherwise.
    • create

      public com.irurueta.navigation.inertial.INSLooselyCoupledKalmanConfig create() throws com.irurueta.navigation.NotReadyException
      Creates a INSLooselyCoupledKalmanConfig instance containing estimated parameters during calibration.
      Returns:
      instance containing configuration data.
      Throws:
      com.irurueta.navigation.NotReadyException - if the creator is not ready.