Class AccumulatedAngularSpeedMeasurementNoiseEstimator
java.lang.Object
com.irurueta.navigation.inertial.calibration.noise.AccumulatedMeasurementNoiseEstimator<com.irurueta.units.AngularSpeedUnit,com.irurueta.units.AngularSpeed,AccumulatedAngularSpeedMeasurementNoiseEstimator,AccumulatedAngularSpeedMeasurementNoiseEstimatorListener>
com.irurueta.navigation.inertial.calibration.noise.AccumulatedAngularSpeedMeasurementNoiseEstimator
- All Implemented Interfaces:
GyroscopeNoiseRootPsdSource
public class AccumulatedAngularSpeedMeasurementNoiseEstimator
extends AccumulatedMeasurementNoiseEstimator<com.irurueta.units.AngularSpeedUnit,com.irurueta.units.AngularSpeed,AccumulatedAngularSpeedMeasurementNoiseEstimator,AccumulatedAngularSpeedMeasurementNoiseEstimatorListener>
implements GyroscopeNoiseRootPsdSource
Estimates accumulated angular speed noise variances and PSD's (Power Spectral Densities)
along with their average values.
Norms of angular speed triads can be used to estimate noise levels.
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
AccumulatedMeasurementNoiseEstimator.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.
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.AccumulatedMeasurementNoiseEstimator
DEFAULT_TIME_INTERVAL_SECONDS
-
Constructor Summary
ConstructorsConstructorDescriptionConstructor.AccumulatedAngularSpeedMeasurementNoiseEstimator
(AccumulatedAngularSpeedMeasurementNoiseEstimatorListener listener) Constructor. -
Method Summary
Modifier and TypeMethodDescriptionprotected double
convertToDefaultUnit
(com.irurueta.units.AngularSpeed value) Converts provided measurement 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 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.AccumulatedMeasurementNoiseEstimator
addMeasurement, addMeasurement, getAvg, getAvgAsMeasurement, getAvgAsMeasurement, getLastMeasurement, getLastMeasurement, getListener, getNumberOfProcessedSamples, getPsd, getRootPsd, getStandardDeviation, getStandardDeviationAsMeasurement, getStandardDeviationAsMeasurement, getTimeInterval, getTimeIntervalAsTime, getTimeIntervalAsTime, getVariance, isRunning, reset, setListener, setTimeInterval, setTimeInterval
-
Constructor Details
-
AccumulatedAngularSpeedMeasurementNoiseEstimator
public AccumulatedAngularSpeedMeasurementNoiseEstimator()Constructor.
-
-
Method Details
-
getDefaultUnit
protected com.irurueta.units.AngularSpeedUnit getDefaultUnit()Gets default unit for a measurement.- Specified by:
getDefaultUnit
in classAccumulatedMeasurementNoiseEstimator<com.irurueta.units.AngularSpeedUnit,
com.irurueta.units.AngularSpeed, AccumulatedAngularSpeedMeasurementNoiseEstimator, AccumulatedAngularSpeedMeasurementNoiseEstimatorListener> - 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 classAccumulatedMeasurementNoiseEstimator<com.irurueta.units.AngularSpeedUnit,
com.irurueta.units.AngularSpeed, AccumulatedAngularSpeedMeasurementNoiseEstimator, AccumulatedAngularSpeedMeasurementNoiseEstimatorListener> - Parameters:
value
- value to be set.unit
- unit to be set.- Returns:
- created measurement.
-
convertToDefaultUnit
protected double convertToDefaultUnit(com.irurueta.units.AngularSpeed value) Converts provided measurement into default unit.- Specified by:
convertToDefaultUnit
in classAccumulatedMeasurementNoiseEstimator<com.irurueta.units.AngularSpeedUnit,
com.irurueta.units.AngularSpeed, AccumulatedAngularSpeedMeasurementNoiseEstimator, AccumulatedAngularSpeedMeasurementNoiseEstimatorListener> - Parameters:
value
- measurement 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.
-