Class AccumulatedAngularSpeedTriadNoiseEstimator
java.lang.Object
com.irurueta.navigation.inertial.calibration.noise.AccumulatedTriadNoiseEstimator<com.irurueta.units.AngularSpeedUnit,com.irurueta.units.AngularSpeed,AngularSpeedTriad,AccumulatedAngularSpeedTriadNoiseEstimator,AccumulatedAngularSpeedTriadNoiseEstimatorListener>
com.irurueta.navigation.inertial.calibration.noise.AccumulatedAngularSpeedTriadNoiseEstimator
- All Implemented Interfaces:
GyroscopeNoiseRootPsdSource
public class AccumulatedAngularSpeedTriadNoiseEstimator
extends AccumulatedTriadNoiseEstimator<com.irurueta.units.AngularSpeedUnit,com.irurueta.units.AngularSpeed,AngularSpeedTriad,AccumulatedAngularSpeedTriadNoiseEstimator,AccumulatedAngularSpeedTriadNoiseEstimatorListener>
implements GyroscopeNoiseRootPsdSource
Estimates accumulated angular speed noise variances and PSD's (Power Spectral Densities)
along with their average values.
This estimator must be used when the body where the gyroscope is attached to
keeps a constant angular speed while capturing data (i.e. when body is static has
a constant overall angular speed due to Earth rotation).
To compute PSD's, this estimator assumes that measurement samples are obtained
at a constant provided rate equal to
AccumulatedTriadNoiseEstimator.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
(variance or standard deviation) can be safely used.
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.AccumulatedTriadNoiseEstimator
DEFAULT_TIME_INTERVAL_SECONDS
-
Constructor Summary
ConstructorsConstructorDescriptionConstructor.AccumulatedAngularSpeedTriadNoiseEstimator
(AccumulatedAngularSpeedTriadNoiseEstimatorListener listener) Constructor. -
Method Summary
Modifier and TypeMethodDescriptionprotected double
convertToDefaultUnit
(double value, com.irurueta.units.AngularSpeedUnit unit) Converts provided value and unit into default unit.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 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.AccumulatedTriadNoiseEstimator
addTriad, addTriad, addTriad, getAverageStandardDeviation, getAverageStandardDeviationAsMeasurement, getAverageStandardDeviationAsMeasurement, getAvgNoisePsd, getAvgNorm, getAvgNormAsMeasurement, getAvgNormAsMeasurement, getAvgTriad, getAvgTriad, getAvgX, getAvgXAsMeasurement, getAvgXAsMeasurement, getAvgY, getAvgYAsMeasurement, getAvgYAsMeasurement, getAvgZ, getAvgZAsMeasurement, getAvgZAsMeasurement, getLastTriad, getLastTriad, getListener, getNoiseRootPsdNorm, getNumberOfProcessedSamples, 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, isRunning, reset, setListener, setTimeInterval, setTimeInterval
-
Constructor Details
-
AccumulatedAngularSpeedTriadNoiseEstimator
public AccumulatedAngularSpeedTriadNoiseEstimator()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 classAccumulatedTriadNoiseEstimator<com.irurueta.units.AngularSpeedUnit,
com.irurueta.units.AngularSpeed, AngularSpeedTriad, AccumulatedAngularSpeedTriadNoiseEstimator, AccumulatedAngularSpeedTriadNoiseEstimatorListener> - Parameters:
valueX
- x coordinate value.valueY
- y coordinate value.valueZ
- z coordinate value.unit
- unit.- Returns:
- created triad.
-
getDefaultUnit
protected com.irurueta.units.AngularSpeedUnit getDefaultUnit()Gets default unit for a measurement.- Specified by:
getDefaultUnit
in classAccumulatedTriadNoiseEstimator<com.irurueta.units.AngularSpeedUnit,
com.irurueta.units.AngularSpeed, AngularSpeedTriad, AccumulatedAngularSpeedTriadNoiseEstimator, AccumulatedAngularSpeedTriadNoiseEstimatorListener> - 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 classAccumulatedTriadNoiseEstimator<com.irurueta.units.AngularSpeedUnit,
com.irurueta.units.AngularSpeed, AngularSpeedTriad, AccumulatedAngularSpeedTriadNoiseEstimator, AccumulatedAngularSpeedTriadNoiseEstimatorListener> - Parameters:
value
- value to be set.unit
- unit to be set.- Returns:
- created measurement.
-
convertToDefaultUnit
protected double convertToDefaultUnit(double value, com.irurueta.units.AngularSpeedUnit unit) Converts provided value and unit into default unit.- Specified by:
convertToDefaultUnit
in classAccumulatedTriadNoiseEstimator<com.irurueta.units.AngularSpeedUnit,
com.irurueta.units.AngularSpeed, AngularSpeedTriad, AccumulatedAngularSpeedTriadNoiseEstimator, AccumulatedAngularSpeedTriadNoiseEstimatorListener> - Parameters:
value
- measurement value to be converted.unit
- unit of measurement value to be converted.- Returns:
- converted value.
-
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.
-