Class INSLooselyCoupledKalmanConfig

java.lang.Object
com.irurueta.navigation.inertial.INSLooselyCoupledKalmanConfig
All Implemented Interfaces:
Serializable, Cloneable

public class INSLooselyCoupledKalmanConfig extends Object implements Serializable, Cloneable
Contains configuration parameters (usually obtained through calibration) for INS/GNSS Loosely Coupled Kalman filter.
See Also:
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    private double
    Accelerometer bias random walk PSD (Power Spectral Density) expressed in (m^2 * s^-5).
    private double
    Accelerometer noise PSD (Power Spectral Density) expressed in (m^2 * s^-3).
    private double
    Gyro bias random walk PSD (Power Spectral Density) expressed in (rad^2 * s^-3).
    private double
    Gyro noise PSD (Power Spectral Density) expressed in squared radians per second (rad^2/s).
    private double
    Position measurement noise SD (Standard Deviation) per axis expressed in meters (m).
    private static final long
    Serialization version.
    private double
    Velocity measurement noise SD (Standard Deviation) per axis expressed in meters per second (m/s).
  • Constructor Summary

    Constructors
    Constructor
    Description
    Constructor.
    INSLooselyCoupledKalmanConfig(double gyroNoisePSD, double accelerometerNoisePSD, double accelerometerBiasPSD, double gyroBiasPSD, double positionNoiseSD, double velocityNoiseSD)
    Constructor.
    INSLooselyCoupledKalmanConfig(double gyroNoisePSD, double accelerometerNoisePSD, double accelerometerBiasPSD, double gyroBiasPSD, com.irurueta.units.Distance positionNoiseSD, com.irurueta.units.Speed velocityNoiseSD)
    Constructor.
    Copy constructor.
  • Method Summary

    Modifier and Type
    Method
    Description
    protected Object
    Makes a copy of this instance.
    void
    Copies data of provided instance into this instance.
    void
    Copies this instance data into provided instance.
    boolean
    Checks if provided instance has exactly the same contents as this instance.
    boolean
    equals(INSLooselyCoupledKalmanConfig other, double threshold)
    Checks if provided instance has contents similar to this instance up to provided threshold value.
    boolean
    Checks if provided object is a INSLooselyCoupledKalmanConfig having exactly the same contents as this instance.
    double
    Gets accelerometer bias random walk PSD (Power Spectral Density) expressed in (m^2 * s^-5).
    double
    Gets accelerometer noise PSD (Power Spectral Density) expressed in (m^2 * s^-3).
    double
    Gets gyro bias random walk PSD (Power Spectral Density) expressed in (rad^2 * s^-3).
    double
    Gets gyro noise PSD (Power Spectral Density) expressed in squared radians per second (rad^2/s).
    double
    Gets position measurement noise SD (Standard Deviation) per axis expressed in meters (m).
    com.irurueta.units.Distance
    Gets position measurement noise SD (Standard Deviation) per axis.
    void
    getPositionNoiseSDAsDistance(com.irurueta.units.Distance result)
    Gets position measurement noise SD (Standard Deviation) per axis.
    double
    Gets velocity measurement noise SD (Standard Deviation) per axis expressed in meters per second (m/s).
    com.irurueta.units.Speed
    Gets velocity measurement noise SD (Standard Deviation) per axis.
    void
    getVelocityNoiseSDAsSpeed(com.irurueta.units.Speed result)
    Gets velocity measurement noise SD (Standard Deviation) per axis.
    int
    Computes and returns hash code for this instance.
    void
    setAccelerometerBiasPSD(double accelerometerBiasPSD)
    Sets accelerometer bias random walk PSD (Power Spectral Density) expressed in (m^2 * s^-5).
    void
    setAccelerometerNoisePSD(double accelerometerNoisePSD)
    Sets accelerometer noise PSD (Power Spectral Density) expressed in (m^2 * s^-3).
    void
    setGyroBiasPSD(double gyroBiasPSD)
    Sets gyro bias random walk PSD (Power Spectral Density) expressed in (rad^2 * s^-3).
    void
    setGyroNoisePSD(double gyroNoisePSD)
    Sets gyro noise PSD (Power Spectral Density) expressed in squared radians per second (rad^2/s).
    void
    setPositionNoiseSD(double positionNoiseSD)
    Sets position measurement noise SD (Standard Deviation) per axis expressed in meters (m).
    void
    setPositionNoiseSD(com.irurueta.units.Distance positionNoiseSD)
    Sets position measurement noise SD (Standard Deviation) per axis.
    void
    setValues(double gyroNoisePSD, double accelerometerNoisePSD, double accelerometerBiasPSD, double gyroBiasPSD, double positionNoiseSD, double velocityNoiseSD)
    Sets configuration parameters.
    void
    setValues(double gyroNoisePSD, double accelerometerNoisePSD, double accelerometerBiasPSD, double gyroBiasPSD, com.irurueta.units.Distance positionNoiseSD, com.irurueta.units.Speed velocityNoiseSD)
    Sets configuration parameters.
    void
    setVelocityNoiseSD(double velocityNoiseSD)
    Sets velocity measurement noise SD (Standard Deviation) per axis expressed in meters per second (m/s).
    void
    setVelocityNoiseSD(com.irurueta.units.Speed velocityNoiseSD)
    Sets velocity measurement noise SD (Standard Deviation) per axis.

    Methods inherited from class java.lang.Object

    finalize, getClass, notify, notifyAll, toString, wait, wait, wait
  • Field Details

    • serialVersionUID

      private static final long serialVersionUID
      Serialization version. This is used to ensure compatibility of deserialization of permanently stored serialized instances.
      See Also:
    • gyroNoisePSD

      private double gyroNoisePSD
      Gyro noise PSD (Power Spectral Density) expressed in squared radians per second (rad^2/s).
    • accelerometerNoisePSD

      private double accelerometerNoisePSD
      Accelerometer noise PSD (Power Spectral Density) expressed in (m^2 * s^-3).
    • accelerometerBiasPSD

      private double accelerometerBiasPSD
      Accelerometer bias random walk PSD (Power Spectral Density) expressed in (m^2 * s^-5).
    • gyroBiasPSD

      private double gyroBiasPSD
      Gyro bias random walk PSD (Power Spectral Density) expressed in (rad^2 * s^-3).
    • positionNoiseSD

      private double positionNoiseSD
      Position measurement noise SD (Standard Deviation) per axis expressed in meters (m).
    • velocityNoiseSD

      private double velocityNoiseSD
      Velocity measurement noise SD (Standard Deviation) per axis expressed in meters per second (m/s).
  • Constructor Details

    • INSLooselyCoupledKalmanConfig

      public INSLooselyCoupledKalmanConfig()
      Constructor.
    • INSLooselyCoupledKalmanConfig

      public INSLooselyCoupledKalmanConfig(double gyroNoisePSD, double accelerometerNoisePSD, double accelerometerBiasPSD, double gyroBiasPSD, double positionNoiseSD, double velocityNoiseSD)
      Constructor.
      Parameters:
      gyroNoisePSD - gyro noise PSD (Power Spectral Density) expressed in squared radians per second (rad^2/s).
      accelerometerNoisePSD - accelerometer noise PSD (Power Spectral Density) expressed in (m^2 * s^-3).
      accelerometerBiasPSD - accelerometer bias random walk PSD (Power Spectral Density) expressed in (m^2 * s^-5).
      gyroBiasPSD - gyro bias random walk PSD (Power Spectral Density) expressed in (rad^2 * s^-3).
      positionNoiseSD - position measurement noise SD (Standard Deviation) per axis expressed in meters (m).
      velocityNoiseSD - velocity measurement noise SD (Standard Deviation) per axis expressed in meters per second (m/s).
    • INSLooselyCoupledKalmanConfig

      public INSLooselyCoupledKalmanConfig(double gyroNoisePSD, double accelerometerNoisePSD, double accelerometerBiasPSD, double gyroBiasPSD, com.irurueta.units.Distance positionNoiseSD, com.irurueta.units.Speed velocityNoiseSD)
      Constructor.
      Parameters:
      gyroNoisePSD - gyro noise PSD (Power Spectral Density) expressed in squared radians per second (rad^2/s).
      accelerometerNoisePSD - accelerometer noise PSD (Power Spectral Density) expressed in (m^2 * s^-3).
      accelerometerBiasPSD - accelerometer bias random walk PSD (Power Spectral Density) expressed in (m^2 * s^-5).
      gyroBiasPSD - gyro bias random walk PSD (Power Spectral Density) expressed in (rad^2 * s^-3).
      positionNoiseSD - position measurement noise SD (Standard Deviation) per axis.
      velocityNoiseSD - velocity measurement noise SD (Standard Deviation) per axis.
    • INSLooselyCoupledKalmanConfig

      public INSLooselyCoupledKalmanConfig(INSLooselyCoupledKalmanConfig input)
      Copy constructor.
      Parameters:
      input - input instance to copy data from.
  • Method Details

    • getGyroNoisePSD

      public double getGyroNoisePSD()
      Gets gyro noise PSD (Power Spectral Density) expressed in squared radians per second (rad^2/s).
      Returns:
      gyro noise PSD.
    • setGyroNoisePSD

      public void setGyroNoisePSD(double gyroNoisePSD)
      Sets gyro noise PSD (Power Spectral Density) expressed in squared radians per second (rad^2/s).
      Parameters:
      gyroNoisePSD - gyro noise PSD.
    • getAccelerometerNoisePSD

      public double getAccelerometerNoisePSD()
      Gets accelerometer noise PSD (Power Spectral Density) expressed in (m^2 * s^-3).
      Returns:
      accelerometer noise PSD.
    • setAccelerometerNoisePSD

      public void setAccelerometerNoisePSD(double accelerometerNoisePSD)
      Sets accelerometer noise PSD (Power Spectral Density) expressed in (m^2 * s^-3).
      Parameters:
      accelerometerNoisePSD - accelerometer noise PSD.
    • getAccelerometerBiasPSD

      public double getAccelerometerBiasPSD()
      Gets accelerometer bias random walk PSD (Power Spectral Density) expressed in (m^2 * s^-5).
      Returns:
      accelerometer bias random walk PSD.
    • setAccelerometerBiasPSD

      public void setAccelerometerBiasPSD(double accelerometerBiasPSD)
      Sets accelerometer bias random walk PSD (Power Spectral Density) expressed in (m^2 * s^-5).
      Parameters:
      accelerometerBiasPSD - accelerometer bias random walk PSD.
    • getGyroBiasPSD

      public double getGyroBiasPSD()
      Gets gyro bias random walk PSD (Power Spectral Density) expressed in (rad^2 * s^-3).
      Returns:
      gyro bias random walk PSD.
    • setGyroBiasPSD

      public void setGyroBiasPSD(double gyroBiasPSD)
      Sets gyro bias random walk PSD (Power Spectral Density) expressed in (rad^2 * s^-3).
      Parameters:
      gyroBiasPSD - gyro bias random walk PSD.
    • getPositionNoiseSD

      public double getPositionNoiseSD()
      Gets position measurement noise SD (Standard Deviation) per axis expressed in meters (m).
      Returns:
      position measurement noise SD.
    • setPositionNoiseSD

      public void setPositionNoiseSD(double positionNoiseSD)
      Sets position measurement noise SD (Standard Deviation) per axis expressed in meters (m).
      Parameters:
      positionNoiseSD - position measurement noise SD.
    • getVelocityNoiseSD

      public double getVelocityNoiseSD()
      Gets velocity measurement noise SD (Standard Deviation) per axis expressed in meters per second (m/s).
      Returns:
      velocity measurement noise SD.
    • setVelocityNoiseSD

      public void setVelocityNoiseSD(double velocityNoiseSD)
      Sets velocity measurement noise SD (Standard Deviation) per axis expressed in meters per second (m/s).
      Parameters:
      velocityNoiseSD - velocity measurement noise SD.
    • setValues

      public void setValues(double gyroNoisePSD, double accelerometerNoisePSD, double accelerometerBiasPSD, double gyroBiasPSD, double positionNoiseSD, double velocityNoiseSD)
      Sets configuration parameters.
      Parameters:
      gyroNoisePSD - gyro noise PSD (Power Spectral Density) expressed in squared radians per second (rad^2/s).
      accelerometerNoisePSD - accelerometer noise PSD (Power Spectral Density) expressed in (m^2 * s^-3).
      accelerometerBiasPSD - accelerometer bias random walk PSD (Power Spectral Density) expressed in (m^2 * s^-5).
      gyroBiasPSD - gyro bias random walk PSD (Power Spectral Density) expressed in (rad^2 * s^-3).
      positionNoiseSD - position measurement noise SD (Standard Deviation) per axis expressed in meters (m).
      velocityNoiseSD - velocity measurement noise SD (Standard Deviation) per axis expressed in meters per second (m/s).
    • getPositionNoiseSDAsDistance

      public void getPositionNoiseSDAsDistance(com.irurueta.units.Distance result)
      Gets position measurement noise SD (Standard Deviation) per axis.
      Parameters:
      result - instance where position measurement noise SD will be stored.
    • getPositionNoiseSDAsDistance

      public com.irurueta.units.Distance getPositionNoiseSDAsDistance()
      Gets position measurement noise SD (Standard Deviation) per axis.
      Returns:
      position measurement noise SD.
    • setPositionNoiseSD

      public void setPositionNoiseSD(com.irurueta.units.Distance positionNoiseSD)
      Sets position measurement noise SD (Standard Deviation) per axis.
      Parameters:
      positionNoiseSD - position measurement noise SD.
    • getVelocityNoiseSDAsSpeed

      public void getVelocityNoiseSDAsSpeed(com.irurueta.units.Speed result)
      Gets velocity measurement noise SD (Standard Deviation) per axis.
      Parameters:
      result - instance where velocity measurement noise SD will be stored.
    • getVelocityNoiseSDAsSpeed

      public com.irurueta.units.Speed getVelocityNoiseSDAsSpeed()
      Gets velocity measurement noise SD (Standard Deviation) per axis.
      Returns:
      velocity measurement noise SD per axis.
    • setVelocityNoiseSD

      public void setVelocityNoiseSD(com.irurueta.units.Speed velocityNoiseSD)
      Sets velocity measurement noise SD (Standard Deviation) per axis.
      Parameters:
      velocityNoiseSD - velocity measurement noise SD per axis.
    • setValues

      public void setValues(double gyroNoisePSD, double accelerometerNoisePSD, double accelerometerBiasPSD, double gyroBiasPSD, com.irurueta.units.Distance positionNoiseSD, com.irurueta.units.Speed velocityNoiseSD)
      Sets configuration parameters.
      Parameters:
      gyroNoisePSD - gyro noise PSD (Power Spectral Density) expressed in squared radians per second (rad^2/s).
      accelerometerNoisePSD - accelerometer noise PSD (Power Spectral Density) expressed in (m^2 * s^-3).
      accelerometerBiasPSD - accelerometer bias random walk PSD (Power Spectral Density) expressed in (m^2 * s^-5).
      gyroBiasPSD - gyro bias random walk PSD (Power Spectral Density) expressed in (rad^2 * s^-3).
      positionNoiseSD - position measurement noise SD (Standard Deviation) per axis.
      velocityNoiseSD - velocity measurement noise SD (Standard Deviation) per axis.
    • copyTo

      public void copyTo(INSLooselyCoupledKalmanConfig output)
      Copies this instance data into provided instance.
      Parameters:
      output - destination instance where data will be copied to.
    • copyFrom

      public void copyFrom(INSLooselyCoupledKalmanConfig input)
      Copies data of provided instance into this instance.
      Parameters:
      input - instance to copy data from.
    • hashCode

      public int hashCode()
      Computes and returns hash code for this instance. Hash codes are almost unique values that are useful for fast classification and storage of objects in collections.
      Overrides:
      hashCode in class Object
      Returns:
      Hash code.
    • equals

      public boolean equals(Object obj)
      Checks if provided object is a INSLooselyCoupledKalmanConfig having exactly the same contents as this instance.
      Overrides:
      equals in class Object
      Parameters:
      obj - Object to be compared.
      Returns:
      true if both objects are considered to be equal, false otherwise.
    • equals

      public boolean equals(INSLooselyCoupledKalmanConfig other)
      Checks if provided instance has exactly the same contents as this instance.
      Parameters:
      other - instance to be compared.
      Returns:
      true if both instances are considered to be equal, false otherwise.
    • equals

      public boolean equals(INSLooselyCoupledKalmanConfig other, double threshold)
      Checks if provided instance has contents similar to this instance up to provided threshold value.
      Parameters:
      other - instance to be compared.
      threshold - maximum difference allowed for values.
      Returns:
      true if both instances are considered to be equal (up to provided threshold), false otherwise.
    • clone

      protected Object clone() throws CloneNotSupportedException
      Makes a copy of this instance.
      Overrides:
      clone in class Object
      Returns:
      a copy of this instance.
      Throws:
      CloneNotSupportedException - if clone fails for some reason.