Class WindowedAngularSpeedTriadNoiseEstimator
java.lang.Object
com.irurueta.navigation.inertial.calibration.noise.WindowedTriadNoiseEstimator<com.irurueta.units.AngularSpeedUnit,com.irurueta.units.AngularSpeed,AngularSpeedTriad,WindowedAngularSpeedTriadNoiseEstimator,WindowedAngularSpeedTriadNoiseEstimatorListener>
com.irurueta.navigation.inertial.calibration.noise.WindowedAngularSpeedTriadNoiseEstimator
- All Implemented Interfaces:
GyroscopeNoiseRootPsdSource
public class WindowedAngularSpeedTriadNoiseEstimator
extends WindowedTriadNoiseEstimator<com.irurueta.units.AngularSpeedUnit,com.irurueta.units.AngularSpeed,AngularSpeedTriad,WindowedAngularSpeedTriadNoiseEstimator,WindowedAngularSpeedTriadNoiseEstimatorListener>
implements GyroscopeNoiseRootPsdSource
Estimates angular speed noise variances and PSD's (Power Spectral Densities)
along with the gyroscope average values for a windowed amount of samples.
This estimator must be used when the body where the gyroscope is attached
remains static on the same position with zero velocity while capturing data.
To compute PSD's, this estimator assumes that gyroscope samples are
obtained at a constant provided rate equal to
WindowedTriadNoiseEstimator.getTimeInterval()
seconds.
If not available, gyroscope sampling rate average can be estimated using
TimeIntervalEstimator
.
This estimator does NOT require the knowledge of current location and body
orientation.
Because body location and orientation is not known, estimated average values
cannot be used to determine biases. Only norm of noise estimations can be
safely used as an indication of variation of overall rotation rate (which is
indicated by norm of estimated average).
Notice that if there are less than WindowedTriadNoiseEstimator.getWindowSize()
processed
samples in the window, this estimator will assume that the remaining ones
until the window is completed have zero values.
This implementation of noise estimator will use the following units:
- radians per second (rad/s) for angular speed, average or standard deviation values.
- (rad^2/s^2) fr angular speed variances.
- (rad^2/s) for gyroscope PSD (Power Spectral Density).
- (rad * s^-0.5) for gyroscope root PSD (Power Spectral Density).-
Field Summary
Fields inherited from class com.irurueta.navigation.inertial.calibration.noise.WindowedTriadNoiseEstimator
DEFAULT_TIME_INTERVAL_SECONDS, DEFAULT_WINDOW_SIZE, MIN_WINDOW_SIZE
-
Constructor Summary
ConstructorsConstructorDescriptionConstructor.Constructor. -
Method Summary
Modifier and TypeMethodDescriptionprotected AngularSpeedTriad
copyTriad
(AngularSpeedTriad input) Creates a copy of a triad.protected com.irurueta.units.AngularSpeed
createMeasurement
(double value, com.irurueta.units.AngularSpeedUnit unit) Creates a measurement with provided value and unit.protected AngularSpeedTriad
createTriad
(double valueX, double valueY, double valueZ, com.irurueta.units.AngularSpeedUnit unit) Creates a triad with provided values and unit.protected AngularSpeedTriad
createTriad
(com.irurueta.units.AngularSpeed valueX, com.irurueta.units.AngularSpeed valueY, com.irurueta.units.AngularSpeed valueZ) Creates a triad with provided values.protected com.irurueta.units.AngularSpeedUnit
Gets default unit for a measurement.double
Gets gyroscope base noise level root PSD (Power Spectral Density) expressed in (rad * s^-0.5)Methods inherited from class com.irurueta.navigation.inertial.calibration.noise.WindowedTriadNoiseEstimator
addTriad, addTriad, addTriad, addTriadAndProcess, addTriadAndProcess, addTriadAndProcess, getAverageStandardDeviation, getAverageStandardDeviationAsMeasurement, getAverageStandardDeviationAsMeasurement, getAvgNoisePsd, getAvgNorm, getAvgNormAsMeasurement, getAvgNormAsMeasurement, getAvgTriad, getAvgTriad, getAvgX, getAvgXAsMeasurement, getAvgXAsMeasurement, getAvgY, getAvgYAsMeasurement, getAvgYAsMeasurement, getAvgZ, getAvgZAsMeasurement, getAvgZAsMeasurement, getFirstWindowedTriad, getFirstWindowedTriad, getLastWindowedTriad, getLastWindowedTriad, getListener, getNoiseRootPsdNorm, getNumberOfProcessedSamples, getNumberOfSamplesInWindow, getPsdX, getPsdY, getPsdZ, getRootPsdX, getRootPsdY, getRootPsdZ, getStandardDeviationNorm, getStandardDeviationNormAsMeasurement, getStandardDeviationNormAsMeasurement, getStandardDeviationTriad, getStandardDeviationTriad, getStandardDeviationX, getStandardDeviationXAsMeasurement, getStandardDeviationXAsMeasurement, getStandardDeviationY, getStandardDeviationYAsMeasurement, getStandardDeviationYAsMeasurement, getStandardDeviationZ, getStandardDeviationZAsMeasurement, getStandardDeviationZAsMeasurement, getTimeInterval, getTimeIntervalAsTime, getTimeIntervalAsTime, getVarianceX, getVarianceY, getVarianceZ, getWindowSize, isRunning, isWindowFilled, reset, setListener, setTimeInterval, setTimeInterval, setWindowSize
-
Constructor Details
-
WindowedAngularSpeedTriadNoiseEstimator
public WindowedAngularSpeedTriadNoiseEstimator()Constructor.
-
-
Method Details
-
createTriad
protected AngularSpeedTriad createTriad(double valueX, double valueY, double valueZ, com.irurueta.units.AngularSpeedUnit unit) Creates a triad with provided values and unit.- Specified by:
createTriad
in classWindowedTriadNoiseEstimator<com.irurueta.units.AngularSpeedUnit,
com.irurueta.units.AngularSpeed, AngularSpeedTriad, WindowedAngularSpeedTriadNoiseEstimator, WindowedAngularSpeedTriadNoiseEstimatorListener> - Parameters:
valueX
- x coordinate value.valueY
- y coordinate value.valueZ
- z coordinate value.unit
- unit.- Returns:
- created triad.
-
createTriad
protected AngularSpeedTriad createTriad(com.irurueta.units.AngularSpeed valueX, com.irurueta.units.AngularSpeed valueY, com.irurueta.units.AngularSpeed valueZ) Creates a triad with provided values.- Specified by:
createTriad
in classWindowedTriadNoiseEstimator<com.irurueta.units.AngularSpeedUnit,
com.irurueta.units.AngularSpeed, AngularSpeedTriad, WindowedAngularSpeedTriadNoiseEstimator, WindowedAngularSpeedTriadNoiseEstimatorListener> - Parameters:
valueX
- x coordinate value.valueY
- y coordinate value.valueZ
- z coordinate value.- Returns:
- created triad.
-
getDefaultUnit
protected com.irurueta.units.AngularSpeedUnit getDefaultUnit()Gets default unit for a measurement.- Specified by:
getDefaultUnit
in classWindowedTriadNoiseEstimator<com.irurueta.units.AngularSpeedUnit,
com.irurueta.units.AngularSpeed, AngularSpeedTriad, WindowedAngularSpeedTriadNoiseEstimator, WindowedAngularSpeedTriadNoiseEstimatorListener> - Returns:
- default unit for a measurement.
-
createMeasurement
protected com.irurueta.units.AngularSpeed createMeasurement(double value, com.irurueta.units.AngularSpeedUnit unit) Creates a measurement with provided value and unit.- Specified by:
createMeasurement
in classWindowedTriadNoiseEstimator<com.irurueta.units.AngularSpeedUnit,
com.irurueta.units.AngularSpeed, AngularSpeedTriad, WindowedAngularSpeedTriadNoiseEstimator, WindowedAngularSpeedTriadNoiseEstimatorListener> - Parameters:
value
- value to be set.unit
- unit to be set.- Returns:
- created measurement.
-
getGyroscopeBaseNoiseLevelRootPsd
public double getGyroscopeBaseNoiseLevelRootPsd()Gets gyroscope base noise level root PSD (Power Spectral Density) expressed in (rad * s^-0.5)- Specified by:
getGyroscopeBaseNoiseLevelRootPsd
in interfaceGyroscopeNoiseRootPsdSource
- Returns:
- gyroscope base noise level root PSD.