Class INSTightlyCoupledKalmanConfig

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

public class INSTightlyCoupledKalmanConfig 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
    Receiver clock frequency-drift PSD (Power Spectral Density) expressed in (m^2/s^3).
    private double
    Receiver clock phase-drift PSD (Power Spectral Density) expressed in squared meters per second (m^2/s).
    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
    Pseudo-range measurement noise SD (Standard Deviation) expressed in meters (m).
    private double
    Pseudo-range rate measurement noise SD (Standard Deviation) expressed in meters per second (m/s).
    private static final long
    Serialization version.
  • Constructor Summary

    Constructors
    Constructor
    Description
    Constructor.
    INSTightlyCoupledKalmanConfig(double gyroNoisePSD, double accelerometerNoisePSD, double accelerometerBiasPSD, double gyroBiasPSD, double clockFrequencyPSD, double clockPhasePSD, double pseudoRangeSD, double rangeRateSD)
    Constructor.
    INSTightlyCoupledKalmanConfig(double gyroNoisePSD, double accelerometerNoisePSD, double accelerometerBiasPSD, double gyroBiasPSD, double clockFrequencyPSD, double clockPhasePSD, com.irurueta.units.Distance pseudoRangeSD, com.irurueta.units.Speed rangeRateSD)
    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(INSTightlyCoupledKalmanConfig 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 INSTightlyCoupledKalmanConfig 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 receiver clock frequency-drift PSD (Power Spectral Density) expressed in (m^2/s^3).
    double
    Gets receiver clock phase-drift PSD (Power Spectral Density) expressed in squared meters per second (m^2/s).
    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 pseudo-range measurement noise SD (Standard Deviation) expressed in meters (m).
    com.irurueta.units.Distance
    Gets pseudo-range measurement noise SD (Standard Deviation).
    void
    getPseudoRangeSDDistance(com.irurueta.units.Distance result)
    Gets pseudo-range measurement noise SD (Standard Deviation).
    double
    Gets pseudo-range rate measurement noise SD (Standard Deviation) expressed in meters per second (m/s).
    com.irurueta.units.Speed
    Gets pseudo-range rate measurement noise SD (Standard Deviation).
    void
    getRangeRateSDSpeed(com.irurueta.units.Speed result)
    Gets pseudo-range rate measurement noise SD (Standard Deviation).
    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 * se^-3).
    void
    setClockFrequencyPSD(double clockFrequencyPSD)
    Sets receiver clock frequency-drift PSD (Power Spectral Density) expressed in (m^2/s^3).
    void
    setClockPhasePSD(double clockPhasePSD)
    Sets receiver clock phase-drift PSD (Power Spectral Density) expressed in squared meters per second (m^2/s).
    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
    setPseudoRangeSD(double pseudoRangeSD)
    Sets pseudo-range measurement noise SD (Standard Deviation) expressed in meters (m).
    void
    setPseudoRangeSD(com.irurueta.units.Distance pseudoRangeSD)
    Sets pseudo-range measurement noise SD (Standard Deviation).
    void
    setRangeRateSD(double rangeRateSD)
    Sets pseudo-range rate measurement noise SD (Standard Deviation) expressed in meters per second (m/s).
    void
    setRangeRateSD(com.irurueta.units.Speed rangeRateSD)
    Sets pseudo-range rate measurement noise SD (Standard Deviation).
    void
    setValues(double gyroNoisePSD, double accelerometerNoisePSD, double accelerometerBiasPSD, double gyroBiasPSD, double clockFrequencyPSD, double clockPhasePSD, double pseudoRangeSD, double rangeRateSD)
    Sets configuration parameters.
    void
    setValues(double gyroNoisePSD, double accelerometerNoisePSD, double accelerometerBiasPSD, double gyroBiasPSD, double clockFrequencyPSD, double clockPhasePSD, com.irurueta.units.Distance pseudoRangeSD, com.irurueta.units.Speed rangeRateSD)
    Sets configuration parameters.

    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).
    • clockFrequencyPSD

      private double clockFrequencyPSD
      Receiver clock frequency-drift PSD (Power Spectral Density) expressed in (m^2/s^3).
    • clockPhasePSD

      private double clockPhasePSD
      Receiver clock phase-drift PSD (Power Spectral Density) expressed in squared meters per second (m^2/s).
    • pseudoRangeSD

      private double pseudoRangeSD
      Pseudo-range measurement noise SD (Standard Deviation) expressed in meters (m).
    • rangeRateSD

      private double rangeRateSD
      Pseudo-range rate measurement noise SD (Standard Deviation) expressed in meters per second (m/s).
  • Constructor Details

    • INSTightlyCoupledKalmanConfig

      public INSTightlyCoupledKalmanConfig()
      Constructor.
    • INSTightlyCoupledKalmanConfig

      public INSTightlyCoupledKalmanConfig(double gyroNoisePSD, double accelerometerNoisePSD, double accelerometerBiasPSD, double gyroBiasPSD, double clockFrequencyPSD, double clockPhasePSD, double pseudoRangeSD, double rangeRateSD)
      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).
      clockFrequencyPSD - receiver clock frequency-drift PSD (Power Spectral Density) expressed in (m^2/s^3).
      clockPhasePSD - receiver clock phase-drift PSD (Power Spectral Density) expressed in squared meters per second (m^2/s).
      pseudoRangeSD - pseudo-range measurement noise SD (Standard Deviation) expressed in meters (m).
      rangeRateSD - pseudo-range rate measurement noise SD (Standard Deviation) expressed in meters per second (m/s).
    • INSTightlyCoupledKalmanConfig

      public INSTightlyCoupledKalmanConfig(double gyroNoisePSD, double accelerometerNoisePSD, double accelerometerBiasPSD, double gyroBiasPSD, double clockFrequencyPSD, double clockPhasePSD, com.irurueta.units.Distance pseudoRangeSD, com.irurueta.units.Speed rangeRateSD)
      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).
      clockFrequencyPSD - receiver clock frequency-drift PSD (Power Spectral Density) expressed in (m^2/s^3).
      clockPhasePSD - receiver clock phase-drift PSD (Power Spectral Density) expressed in squared meters per second (m^2/s).
      pseudoRangeSD - pseudo-range measurement noise SD (Standard Deviation) expressed in meters (m).
      rangeRateSD - pseudo-range rate measurement noise SD (Standard Deviation) expressed in meters per second (m/s).
    • INSTightlyCoupledKalmanConfig

      public INSTightlyCoupledKalmanConfig(INSTightlyCoupledKalmanConfig 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 * se^-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.
    • getClockFrequencyPSD

      public double getClockFrequencyPSD()
      Gets receiver clock frequency-drift PSD (Power Spectral Density) expressed in (m^2/s^3).
      Returns:
      receiver clock frequency-drift PSD.
    • setClockFrequencyPSD

      public void setClockFrequencyPSD(double clockFrequencyPSD)
      Sets receiver clock frequency-drift PSD (Power Spectral Density) expressed in (m^2/s^3).
      Parameters:
      clockFrequencyPSD - clock frequency-drift PSD.
    • getClockPhasePSD

      public double getClockPhasePSD()
      Gets receiver clock phase-drift PSD (Power Spectral Density) expressed in squared meters per second (m^2/s).
      Returns:
      receiver clock phase-drift PSD.
    • setClockPhasePSD

      public void setClockPhasePSD(double clockPhasePSD)
      Sets receiver clock phase-drift PSD (Power Spectral Density) expressed in squared meters per second (m^2/s).
      Parameters:
      clockPhasePSD - receiver clock phase-drift PSD.
    • getPseudoRangeSD

      public double getPseudoRangeSD()
      Gets pseudo-range measurement noise SD (Standard Deviation) expressed in meters (m).
      Returns:
      pseudo-range measurement noise SD.
    • setPseudoRangeSD

      public void setPseudoRangeSD(double pseudoRangeSD)
      Sets pseudo-range measurement noise SD (Standard Deviation) expressed in meters (m).
      Parameters:
      pseudoRangeSD - pseudo-range measurement noise SD.
    • getRangeRateSD

      public double getRangeRateSD()
      Gets pseudo-range rate measurement noise SD (Standard Deviation) expressed in meters per second (m/s).
      Returns:
      pseudo-range rate measurement noise SD.
    • setRangeRateSD

      public void setRangeRateSD(double rangeRateSD)
      Sets pseudo-range rate measurement noise SD (Standard Deviation) expressed in meters per second (m/s).
      Parameters:
      rangeRateSD - pseudo-range rate measurement noise SD.
    • setValues

      public void setValues(double gyroNoisePSD, double accelerometerNoisePSD, double accelerometerBiasPSD, double gyroBiasPSD, double clockFrequencyPSD, double clockPhasePSD, double pseudoRangeSD, double rangeRateSD)
      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).
      clockFrequencyPSD - receiver clock frequency-drift PSD (Power Spectral Density) expressed in (m^2/s^3).
      clockPhasePSD - receiver clock phase-drift PSD (Power Spectral Density) expressed in squared meters per second (m^2/s).
      pseudoRangeSD - pseudo-range measurement noise SD (Standard Deviation) expressed in meters (m).
      rangeRateSD - pseudo-range rate measurement noise SD (Standard Deviation) expressed in meters per second (m/s).
    • getPseudoRangeSDDistance

      public void getPseudoRangeSDDistance(com.irurueta.units.Distance result)
      Gets pseudo-range measurement noise SD (Standard Deviation).
      Parameters:
      result - instance where pseudo-range measurement noise SD will be stored.
    • getPseudoRangeSDDistance

      public com.irurueta.units.Distance getPseudoRangeSDDistance()
      Gets pseudo-range measurement noise SD (Standard Deviation).
      Returns:
      pseudo-range measurement noise SD.
    • setPseudoRangeSD

      public void setPseudoRangeSD(com.irurueta.units.Distance pseudoRangeSD)
      Sets pseudo-range measurement noise SD (Standard Deviation).
      Parameters:
      pseudoRangeSD - pseudo-range measurement noise SD.
    • getRangeRateSDSpeed

      public void getRangeRateSDSpeed(com.irurueta.units.Speed result)
      Gets pseudo-range rate measurement noise SD (Standard Deviation).
      Parameters:
      result - instance where pseudo-range rate measurement noise SD will be stored.
    • getRangeRateSDSpeed

      public com.irurueta.units.Speed getRangeRateSDSpeed()
      Gets pseudo-range rate measurement noise SD (Standard Deviation).
      Returns:
      pseudo-range rate measurement noise SD.
    • setRangeRateSD

      public void setRangeRateSD(com.irurueta.units.Speed rangeRateSD)
      Sets pseudo-range rate measurement noise SD (Standard Deviation).
      Parameters:
      rangeRateSD - pseudo-range rate measurement noise SD.
    • setValues

      public void setValues(double gyroNoisePSD, double accelerometerNoisePSD, double accelerometerBiasPSD, double gyroBiasPSD, double clockFrequencyPSD, double clockPhasePSD, com.irurueta.units.Distance pseudoRangeSD, com.irurueta.units.Speed rangeRateSD)
      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).
      clockFrequencyPSD - receiver clock frequency-drift PSD (Power Spectral Density) expressed in (m^2/s^3).
      clockPhasePSD - receiver clock phase-drift PSD (Power Spectral Density) expressed in squared meters per second (m^2/s).
      pseudoRangeSD - pseudo-range measurement noise SD (Standard Deviation) expressed in meters (m).
      rangeRateSD - pseudo-range rate measurement noise SD (Standard Deviation) expressed in meters per second (m/s).
    • copyTo

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

      public void copyFrom(INSTightlyCoupledKalmanConfig 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 INSTightlyCoupledKalmanConfig 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(INSTightlyCoupledKalmanConfig 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(INSTightlyCoupledKalmanConfig 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.