Class WindowedAccelerationMeasurementNoiseEstimator
java.lang.Object
com.irurueta.navigation.inertial.calibration.noise.WindowedMeasurementNoiseEstimator<com.irurueta.units.AccelerationUnit,com.irurueta.units.Acceleration,WindowedAccelerationMeasurementNoiseEstimator,WindowedAccelerationMeasurementNoiseEstimatorListener>
com.irurueta.navigation.inertial.calibration.noise.WindowedAccelerationMeasurementNoiseEstimator
- All Implemented Interfaces:
AccelerometerNoiseRootPsdSource
public class WindowedAccelerationMeasurementNoiseEstimator
extends WindowedMeasurementNoiseEstimator<com.irurueta.units.AccelerationUnit,com.irurueta.units.Acceleration,WindowedAccelerationMeasurementNoiseEstimator,WindowedAccelerationMeasurementNoiseEstimatorListener>
implements AccelerometerNoiseRootPsdSource
Estimates acceleration noise variances and PSD's (Power Spectral Density)
along with acceleration average value for a windowed amount of samples.
This estimator must be used when the body where the accelerometer is attached
remains static on the same position with zero velocity while capturing data.
To compute PSD's, this estimator assumes that accelerometer samples are
obtained at a constant provided rate equal to
WindowedMeasurementNoiseEstimator.getTimeInterval()
seconds.
If not available, accelerometer sampling rate average can be estimated using
TimeIntervalEstimator
.
Notice that if there are less than WindowedMeasurementNoiseEstimator.getWindowSize()
processed
samples in the window, this estimator will assume that the remaining ones
until the window is completed have zero values.
This estimator does NOT require the knowledge of current location and body
orientation.
This implementation of noise estimator will use the following units:
- meters per squared second (m/s^2) for acceleration, average or standard deviation values.
- (m^2/s^4) for acceleration variances.
- (m^2 * s^-3) for acceleration PSD (Power Spectral Density).
- (m * s^-1.5) for acceleration root PSD (Power Spectral Density).-
Field Summary
Fields inherited from class com.irurueta.navigation.inertial.calibration.noise.WindowedMeasurementNoiseEstimator
DEFAULT_TIME_INTERVAL_SECONDS, DEFAULT_WINDOW_SIZE, MIN_WINDOW_SIZE
-
Constructor Summary
ConstructorsConstructorDescriptionConstructor.WindowedAccelerationMeasurementNoiseEstimator
(WindowedAccelerationMeasurementNoiseEstimatorListener listener) Constructor. -
Method Summary
Modifier and TypeMethodDescriptionprotected double
convertToDefaultUnit
(com.irurueta.units.Acceleration value) Converts provided measurement into default unit.protected com.irurueta.units.Acceleration
createMeasurement
(double value, com.irurueta.units.AccelerationUnit unit) Creates a measurement with provided value and unit.double
Gets accelerometer base noise level root PSD (Power Spectral Density) expressed in (m * s^-1.5).protected com.irurueta.units.AccelerationUnit
Gets default unit for a measurement.Methods inherited from class com.irurueta.navigation.inertial.calibration.noise.WindowedMeasurementNoiseEstimator
addMeasurement, addMeasurement, addMeasurementAndProcess, addMeasurementAndProcess, getAvg, getAvgAsMeasurement, getAvgAsMeasurement, getFirstWindowedMeasurement, getFirstWindowedMeasurement, getFirstWindowedMeasurementValue, getLastWindowedMeasurement, getLastWindowedMeasurement, getLastWindowedMeasurementValue, getListener, getNumberOfAddedSamples, getNumberOfProcessedSamples, getNumberOfSamplesInWindow, getPsd, getRootPsd, getStandardDeviation, getStandardDeviationAsMeasurement, getStandardDeviationAsMeasurement, getTimeInterval, getTimeIntervalAsTime, getTimeIntervalAsTime, getVariance, getWindowSize, isRunning, isWindowFilled, reset, setListener, setTimeInterval, setTimeInterval, setWindowSize
-
Constructor Details
-
WindowedAccelerationMeasurementNoiseEstimator
public WindowedAccelerationMeasurementNoiseEstimator()Constructor.
-
-
Method Details
-
getDefaultUnit
protected com.irurueta.units.AccelerationUnit getDefaultUnit()Gets default unit for a measurement.- Specified by:
getDefaultUnit
in classWindowedMeasurementNoiseEstimator<com.irurueta.units.AccelerationUnit,
com.irurueta.units.Acceleration, WindowedAccelerationMeasurementNoiseEstimator, WindowedAccelerationMeasurementNoiseEstimatorListener> - Returns:
- default unit for a measurement.
-
createMeasurement
protected com.irurueta.units.Acceleration createMeasurement(double value, com.irurueta.units.AccelerationUnit unit) Creates a measurement with provided value and unit.- Specified by:
createMeasurement
in classWindowedMeasurementNoiseEstimator<com.irurueta.units.AccelerationUnit,
com.irurueta.units.Acceleration, WindowedAccelerationMeasurementNoiseEstimator, WindowedAccelerationMeasurementNoiseEstimatorListener> - Parameters:
value
- value to be set.unit
- unit to be set.- Returns:
- created measurement.
-
convertToDefaultUnit
protected double convertToDefaultUnit(com.irurueta.units.Acceleration value) Converts provided measurement into default unit.- Specified by:
convertToDefaultUnit
in classWindowedMeasurementNoiseEstimator<com.irurueta.units.AccelerationUnit,
com.irurueta.units.Acceleration, WindowedAccelerationMeasurementNoiseEstimator, WindowedAccelerationMeasurementNoiseEstimatorListener> - Parameters:
value
- measurement to be converted.- Returns:
- converted value.
-
getAccelerometerBaseNoiseLevelRootPsd
public double getAccelerometerBaseNoiseLevelRootPsd()Gets accelerometer base noise level root PSD (Power Spectral Density) expressed in (m * s^-1.5).- Specified by:
getAccelerometerBaseNoiseLevelRootPsd
in interfaceAccelerometerNoiseRootPsdSource
- Returns:
- accelerometer base noise level root PSD.
-