Class IMUErrors
java.lang.Object
com.irurueta.navigation.inertial.calibration.IMUErrors
- All Implemented Interfaces:
Serializable
,Cloneable
Contains Inertial Measurement Unit (IMU) errors statistics obtained from
calibration.
This data can also be used to generate synthetic IMU data.
IMU errors are related to accelerometer and gyroscope calibration parameters.
- See Also:
-
Field Summary
FieldsModifier and TypeFieldDescriptionstatic final int
Number of components of accelerometer measures.private double[]
Accelerometer biases for each IMU axis expressed in meters per squared second (m/s^2).private double
Accelerometer noise root PSD expressed in (m * s^-1.5).private double
Accelerometer quantization level expressed in meters per squared second (m/s^2).private com.irurueta.algebra.Matrix
Contains accelerometer scale factors and cross coupling errors.private static final int
Number of components minus one.static final int
Number of components og gyro measures.private double[]
Gyro biases for each IMU axis expressed in radians per second (rad/s).private com.irurueta.algebra.Matrix
3x3 matrix containing cross biases introduced by the specific forces sensed by the accelerometer.private double
Gyro noise root PSD expressed in (rad * s^-0.5).private double
Gyro quantization level expressed in radians per second (rad/s).private com.irurueta.algebra.Matrix
Contains gyro scale factors and cross coupling errors.private static final long
Serialization version. -
Constructor Summary
ConstructorsConstructorDescriptionConstructor.IMUErrors
(double[] accelerometerBiases, double[] gyroBiases, com.irurueta.algebra.Matrix accelerometerScaleFactorAndCrossCouplingErrors, com.irurueta.algebra.Matrix gyroScaleFactorAndCrossCouplingErrors, double accelerometerNoiseRootPSD, double gyroNoiseRootPSD) Constructor.IMUErrors
(double[] accelerometerBiases, double[] gyroBiases, com.irurueta.algebra.Matrix accelerometerScaleFactorAndCrossCouplingErrors, com.irurueta.algebra.Matrix gyroScaleFactorAndCrossCouplingErrors, com.irurueta.algebra.Matrix gyroGDependentBiases, double accelerometerNoiseRootPSD, double gyroNoiseRootPSD, double accelerometerQuantizationLevel, double gyroQuantizationLevel) Constructor.IMUErrors
(com.irurueta.algebra.Matrix accelerometerBiases, com.irurueta.algebra.Matrix gyroBiases, com.irurueta.algebra.Matrix accelerometerScaleFactorAndCrossCouplingErrors, com.irurueta.algebra.Matrix gyroScaleFactorAndCrossCouplingErrors, double accelerometerNoiseRootPSD, double gyroNoiseRootPSD) Constructor.IMUErrors
(com.irurueta.algebra.Matrix accelerometerBiases, com.irurueta.algebra.Matrix gyroBiases, com.irurueta.algebra.Matrix accelerometerScaleFactorAndCrossCouplingErrors, com.irurueta.algebra.Matrix gyroScaleFactorAndCrossCouplingErrors, com.irurueta.algebra.Matrix gyroGDependentBiases, double accelerometerNoiseRootPSD, double gyroNoiseRootPSD, double accelerometerQuantizationLevel, double gyroQuantizationLevel) Constructor.Constructor.IMUErrors
(com.irurueta.units.Acceleration[] accelerometerBiases, com.irurueta.units.AngularSpeed[] gyroBiases, com.irurueta.algebra.Matrix accelerometerScaleFactorAndCrossCouplingErrors, com.irurueta.algebra.Matrix gyroScaleFactorAndCrossCouplingErrors, double accelerometerNoiseRootPSD, double gyroNoiseRootPSD) Constructor.IMUErrors
(com.irurueta.units.Acceleration[] accelerometerBiases, com.irurueta.units.AngularSpeed[] gyroBiases, com.irurueta.algebra.Matrix accelerometerScaleFactorAndCrossCouplingErrors, com.irurueta.algebra.Matrix gyroScaleFactorAndCrossCouplingErrors, com.irurueta.algebra.Matrix gyroGDependentBiases, double accelerometerNoiseRootPSD, double gyroNoiseRootPSD, com.irurueta.units.Acceleration accelerometerQuantizationLevel, com.irurueta.units.AngularSpeed gyroQuantizationLevel) Constructor. -
Method Summary
Modifier and TypeMethodDescriptionprotected Object
clone()
Makes a copy of this instance.private double
convertAcceleration
(com.irurueta.units.Acceleration acceleration) Converts acceleration instance to meters per squared second (m/s^2).private double
convertAngularSpeed
(com.irurueta.units.AngularSpeed angularSpeed) Converts angular speed instance to radians per second (rad/s).void
Copies data of provided instance into this instance.void
Copies this instance data into provided instance.boolean
Checks if provided object is an IMUErrors instance having exactly the same contents as this instance.double[]
Gets accelerometer biases for each IMU axis expressed in meters per squared second (m/s^2).void
getAccelerometerBiases
(double[] result) Gets accelerometer biases for each IMU axis expressed in meters per squared second (m/s^2).com.irurueta.units.Acceleration[]
Gets accelerometer biases for each IMU axis.void
getAccelerometerBiasesAsAcceleration
(com.irurueta.units.Acceleration[] result) Gets accelerometer biases for each IMU axis.com.irurueta.algebra.Matrix
Gets accelerometer biases for each IMU axis expressed in meters per squared second (m/s^2) as a column matrix.void
getAccelerometerBiasesAsMatrix
(com.irurueta.algebra.Matrix result) Gets accelerometer biases for each IMU axis expressed in meters per squared second (m/s^2) as a column matrix.double
Gets accelerometer noise PSD expressed in (m^2 * s^-3).double
Gets accelerometer noise root PSD expressed in (m * s^-1.5).double
Gets accelerometer quantization level expressed in meters per squared second (m/s^2).com.irurueta.units.Acceleration
Gets accelerometer quantization level.void
getAccelerometerQuantizationLevelAsAcceleration
(com.irurueta.units.Acceleration result) Gets accelerometer quantization level.com.irurueta.algebra.Matrix
Gets accelerometer scale factors and cross coupling errors.void
getAccelerometerScaleFactorAndCrossCouplingErrors
(com.irurueta.algebra.Matrix result) Gets accelerometer scale factors and cross coupling errors.double[]
Gets gyro biases for each IMU axis expressed in radians per second (rad/s).void
getGyroBiases
(double[] result) Gets gyro biases for each IMU axis expressed in radians per second (rad/s).com.irurueta.units.AngularSpeed[]
Gets gyro biases for each IMU axis.void
getGyroBiasesAsAngularSpeed
(com.irurueta.units.AngularSpeed[] result) Gets gyro biases for each IMU axis.com.irurueta.algebra.Matrix
Gets gyro biases for each IMU axis expressed in radians per second (rad/s) as a column matrix.void
getGyroBiasesAsMatrix
(com.irurueta.algebra.Matrix result) Gets gyro biases for each IMU axis expressed in radians per second (rad/s) as a column matrix.com.irurueta.algebra.Matrix
Gets 3x3 matrix containing cross biases introduced by the specific forces sensed by the accelerometer.void
getGyroGDependentBiases
(com.irurueta.algebra.Matrix result) Gets 3x3 matrix containing cross biases introduced by the specific forces sensed by the accelerometer.double
Gets gyro noise PSD expressed in (rad^2/s).double
Gets gyro noise root PSD expressed in (rad * s^-0.5).double
Gets gyro quantization level expressed in radians per second (rad/s).com.irurueta.units.AngularSpeed
Gets gyro quantization level.void
getGyroQuantizationLevelAsAngularSpeed
(com.irurueta.units.AngularSpeed result) Gets gyro quantization level.com.irurueta.algebra.Matrix
Gets gyro scale factors and cross coupling errors.void
getGyroScaleFactorAndCrossCouplingErrors
(com.irurueta.algebra.Matrix result) Gets gyro scale factors and cross coupling errors.int
hashCode()
Computes and returns hash code for this instance.void
setAccelerometerBiases
(double[] accelerometerBiases) Sets accelerometer biases for each IMU axis expressed in meters per squared second (m/s^2).void
setAccelerometerBiases
(com.irurueta.algebra.Matrix accelerometerBiases) Sets accelerometer biases for each IMU axis expressed in meters per squared second (m/s^2) from a 3x1 column matrix.void
setAccelerometerBiases
(com.irurueta.units.Acceleration[] accelerometerBiases) Sets accelerometer biases for each IMU axis.void
setAccelerometerNoisePSD
(double accelerometerNoisePSD) Sets accelerometer noise PSD expressed in (m^2 * s^-3).void
setAccelerometerNoiseRootPSD
(double accelerometerNoiseRootPSD) Sets accelerometer noise root PSD expressed in (m * s^-1.5)void
setAccelerometerQuantizationLevel
(double accelerometerQuantizationLevel) Sets accelerometer quantization level expressed in meters per squared second (m/s^2).void
setAccelerometerQuantizationLevel
(com.irurueta.units.Acceleration accelerometerQuantizationLevel) Sets accelerometer quantization level.void
setAccelerometerScaleFactorAndCrossCouplingErrors
(com.irurueta.algebra.Matrix accelerometerScaleFactorAndCrossCouplingErrors) Sets accelerometer scale factors and cross coupling errors.void
setGyroBiases
(double[] gyroBiases) Sets gyro biases for each IMU axis expressed in radians per second (rad/s).void
setGyroBiases
(com.irurueta.algebra.Matrix gyroBiases) Sets gyro biases for each IMU axis expressed in radians per second (rad/s) from a 3x1 column matrix.void
setGyroBiases
(com.irurueta.units.AngularSpeed[] gyroBiases) Sets gyro biases for each IMU axis.void
setGyroGDependentBiases
(com.irurueta.algebra.Matrix gyroGDependentBiases) Sets 3x3 matrix containing cross biases introduced by the specific forces sensed by the accelerometer.void
setGyroNoisePSD
(double gyroNoisePSD) Sets gyro noise PSD expressed in (rad^2/s).void
setGyroNoiseRootPSD
(double gyroNoiseRootPSD) Sets gyro noise root PSD expressed in (rad * s^-0.5).void
setGyroQuantizationLevel
(double gyroQuantizationLevel) Sets gyro quantization level expressed in radians per second (rad/s).void
setGyroQuantizationLevel
(com.irurueta.units.AngularSpeed gyroQuantizationLevel) Sets gyro quantization level.void
setGyroScaleFactorAndCrossCouplingErrors
(com.irurueta.algebra.Matrix gyroScaleFactorAndCrossCouplingErrors) Sets gyro scale factors and cross coupling errors.
-
Field Details
-
ACCELEROMETER_COMPONENTS
public static final int ACCELEROMETER_COMPONENTSNumber of components of accelerometer measures.- See Also:
-
GYRO_COMPONENTS
public static final int GYRO_COMPONENTSNumber of components og gyro measures.- See Also:
-
COMPONENTS_MINUS_ONE
private static final int COMPONENTS_MINUS_ONENumber of components minus one.- See Also:
-
serialVersionUID
private static final long serialVersionUIDSerialization version. This is used to ensure compatibility of deserialization of permanently stored serialized instances.- See Also:
-
accelerometerBiases
private double[] accelerometerBiasesAccelerometer biases for each IMU axis expressed in meters per squared second (m/s^2). By default, it is assumed to be all zeros. -
gyroBiases
private double[] gyroBiasesGyro biases for each IMU axis expressed in radians per second (rad/s). By default, it is assumed to be all zeros. -
accelerometerScaleFactorAndCrossCouplingErrors
private com.irurueta.algebra.Matrix accelerometerScaleFactorAndCrossCouplingErrorsContains accelerometer scale factors and cross coupling errors. This is the product of matrix Ta containing cross coupling errors and Ka containing scaling factors. So that:Ma = [sx mxy mxz] = Ta*Ka [myx sy myz] [mzx mzy sz ]
Where:Ka = [sx 0 0 ] [0 sy 0 ] [0 0 sz]
andTa = [1 -alphaXy alphaXz ] [alphaYx 1 -alphaYz] [-alphaZx alphaZy 1 ]
Hence:Ma = [sx mxy mxz] = Ta*Ka = [sx -sy * alphaXy sz * alphaXz ] [myx sy myz] [sx * alphaYx sy -sz * alphaYz] [mzx mzy sz ] [-sx * alphaZx sy * alphaZy sz ]
This instance allows any 3x3 matrix however, typically alphaYx, alphaZx and alphaZy are considered to be zero if the accelerometer z-axis is assumed to be the same as the body z-axis. When this is assumed, myx = mzx = mzy = 0 and the Ma matrix becomes upper diagonal:Ma = [sx mxy mxz] [0 sy myz] [0 0 sz ]
Values of this matrix are unit-less. By default, it is the 3x3 zero matrix. -
gyroScaleFactorAndCrossCouplingErrors
private com.irurueta.algebra.Matrix gyroScaleFactorAndCrossCouplingErrorsContains gyro scale factors and cross coupling errors. This is the product of matrix Tg containing cross coupling errors and Kg containing scaling factors. So that:Mg = [sx mxy mxz] = Tg*Kg [myx sy myz] [mzx mzy sz ]
Where:Kg = [sx 0 0 ] [0 sy 0 ] [0 0 sz]
andTg = [1 -gammaXy gammaXz ] [gammaYx 1 -gammaYz] [-gammaZx gammaZy 1 ]
Hence:Mg = [sx mxy mxz] = Tg*Kg = [sx -sy * gammaXy sz * gammaXz ] [myx sy myz] [sx * gammaYx sy -sz * gammaYz] [mzx mzy sz ] [-sx * gammaZx sy * gammaZy sz ]
This instance allows any 3x3 matrix however, typically gammaYx, gammaZx and gammaZy are considered to be zero if the accelerometer z-axis is assumed to be the same as the body z-axis. When this is assumed, myx = mzx = mzy = 0 and the Ma matrix becomes upper diagonal:Ma = [sx mxy mxz] [0 sy myz] [0 0 sz ]
Values of this matrix are unit-less. By default, it is the 3x3 zero matrix. -
gyroGDependentBiases
private com.irurueta.algebra.Matrix gyroGDependentBiases3x3 matrix containing cross biases introduced by the specific forces sensed by the accelerometer. Values of this matrix are expressed in (rad-sec/m). By default, it is all zeros. -
accelerometerNoiseRootPSD
private double accelerometerNoiseRootPSDAccelerometer noise root PSD expressed in (m * s^-1.5). By default it is zero. -
gyroNoiseRootPSD
private double gyroNoiseRootPSDGyro noise root PSD expressed in (rad * s^-0.5). By default, it is zero. -
accelerometerQuantizationLevel
private double accelerometerQuantizationLevelAccelerometer quantization level expressed in meters per squared second (m/s^2). By default, it is zero when no quantization is assumed. -
gyroQuantizationLevel
private double gyroQuantizationLevelGyro quantization level expressed in radians per second (rad/s). By default, it is zero when no quantization is assumed.
-
-
Constructor Details
-
IMUErrors
public IMUErrors()Constructor. -
IMUErrors
public IMUErrors(double[] accelerometerBiases, double[] gyroBiases, com.irurueta.algebra.Matrix accelerometerScaleFactorAndCrossCouplingErrors, com.irurueta.algebra.Matrix gyroScaleFactorAndCrossCouplingErrors, double accelerometerNoiseRootPSD, double gyroNoiseRootPSD) Constructor.- Parameters:
accelerometerBiases
- accelerometer biases for each IMU axis expressed in meters per squared second (m/s^2). Must have length 3.gyroBiases
- gyro biases for each IMU axis expressed in radians per second (rad/s). Must have length 3.accelerometerScaleFactorAndCrossCouplingErrors
- accelerometer scale factors and cross coupling errors. Must be 3x3.gyroScaleFactorAndCrossCouplingErrors
- gyro scale factors and cross coupling errors. Must be 3x3.accelerometerNoiseRootPSD
- accelerometer noise root PSD expressed in (m * s^-1.5).gyroNoiseRootPSD
- gyro noise root PSD expressed in (rad * s^-0.5).- Throws:
IllegalArgumentException
- if any value is invalid.
-
IMUErrors
public IMUErrors(com.irurueta.algebra.Matrix accelerometerBiases, com.irurueta.algebra.Matrix gyroBiases, com.irurueta.algebra.Matrix accelerometerScaleFactorAndCrossCouplingErrors, com.irurueta.algebra.Matrix gyroScaleFactorAndCrossCouplingErrors, double accelerometerNoiseRootPSD, double gyroNoiseRootPSD) Constructor.- Parameters:
accelerometerBiases
- accelerometer biases for each IMU axis expressed in meters per squared second (m/s^2). Must be 3x1.gyroBiases
- gyro biases for each IMU axis expressed in radians per second (rad/s). Must be 3x1.accelerometerScaleFactorAndCrossCouplingErrors
- accelerometer scale factors and cross coupling errors. Must be 3x3.gyroScaleFactorAndCrossCouplingErrors
- gyro scale factors and cross coupling errors. Must be 3x3.accelerometerNoiseRootPSD
- accelerometer noise root PSD expressed in (m * s^-1.5).gyroNoiseRootPSD
- gyro noise root PSD expressed in (rad * s^-0.5).- Throws:
IllegalArgumentException
- if any value is invalid.
-
IMUErrors
public IMUErrors(com.irurueta.units.Acceleration[] accelerometerBiases, com.irurueta.units.AngularSpeed[] gyroBiases, com.irurueta.algebra.Matrix accelerometerScaleFactorAndCrossCouplingErrors, com.irurueta.algebra.Matrix gyroScaleFactorAndCrossCouplingErrors, double accelerometerNoiseRootPSD, double gyroNoiseRootPSD) Constructor.- Parameters:
accelerometerBiases
- accelerometer biases for each IMU axis. Must have length 3.gyroBiases
- gyro biases for each IMU axis. Must have length 3.accelerometerScaleFactorAndCrossCouplingErrors
- accelerometer scale factors and cross coupling errors. Must be 3x3.gyroScaleFactorAndCrossCouplingErrors
- gyro scale factors and cross coupling errors. Must be 3x3.accelerometerNoiseRootPSD
- accelerometer noise root PSD expressed in (m * s^-1.5).gyroNoiseRootPSD
- gyro noise root PSD expressed in (rad * s^-0.5).- Throws:
IllegalArgumentException
- if any value is invalid.
-
IMUErrors
public IMUErrors(double[] accelerometerBiases, double[] gyroBiases, com.irurueta.algebra.Matrix accelerometerScaleFactorAndCrossCouplingErrors, com.irurueta.algebra.Matrix gyroScaleFactorAndCrossCouplingErrors, com.irurueta.algebra.Matrix gyroGDependentBiases, double accelerometerNoiseRootPSD, double gyroNoiseRootPSD, double accelerometerQuantizationLevel, double gyroQuantizationLevel) Constructor.- Parameters:
accelerometerBiases
- accelerometer biases for each IMU axis expressed in meters per squared second (m/s^2). Must have length 3.gyroBiases
- gyro biases for each IMU axis expressed in radians per second (rad/s). Must have length 3.accelerometerScaleFactorAndCrossCouplingErrors
- accelerometer scale factors and cross coupling errors. Must be 3x3.gyroScaleFactorAndCrossCouplingErrors
- gyro scale factors and cross coupling errors. Must be 3x3.gyroGDependentBiases
- Cross biases introduced by the specific forces sensed by the accelerometer expressed in (rad-sec/m). Must be 3x3.accelerometerNoiseRootPSD
- accelerometer noise root PSD expressed in (m * s^-1.5).gyroNoiseRootPSD
- gyro noise root PSD expressed in (rad * s^-0.5).accelerometerQuantizationLevel
- accelerometer quantization level expressed in meters per squared second (m/s^2).gyroQuantizationLevel
- gyro quantization level expressed in radians per second (rad/s).- Throws:
IllegalArgumentException
- if any value is invalid.
-
IMUErrors
public IMUErrors(com.irurueta.algebra.Matrix accelerometerBiases, com.irurueta.algebra.Matrix gyroBiases, com.irurueta.algebra.Matrix accelerometerScaleFactorAndCrossCouplingErrors, com.irurueta.algebra.Matrix gyroScaleFactorAndCrossCouplingErrors, com.irurueta.algebra.Matrix gyroGDependentBiases, double accelerometerNoiseRootPSD, double gyroNoiseRootPSD, double accelerometerQuantizationLevel, double gyroQuantizationLevel) Constructor.- Parameters:
accelerometerBiases
- accelerometer biases for each IMU axis expressed in meters per squared second (m/s^2). Must be 3x1.gyroBiases
- gyro biases for each IMU axis expressed in radians per second (rad/s). Must be 3x1.accelerometerScaleFactorAndCrossCouplingErrors
- accelerometer scale factors and cross coupling errors. Must be 3x3.gyroScaleFactorAndCrossCouplingErrors
- gyro scale factors and cross coupling errors. Must be 3x3.gyroGDependentBiases
- Cross biases introduced by the specific forces sensed by the accelerometer expressed in (rad-sec/m). Must be 3x3.accelerometerNoiseRootPSD
- accelerometer noise root PSD expressed in (m * s^-1.5).gyroNoiseRootPSD
- gyro noise root PSD expressed in (rad * s^-0.5).accelerometerQuantizationLevel
- accelerometer quantization level expressed in meters per squared second (m/s^2).gyroQuantizationLevel
- gyro quantization level expressed in radians per second (rad/s).- Throws:
IllegalArgumentException
- if any value is invalid.
-
IMUErrors
public IMUErrors(com.irurueta.units.Acceleration[] accelerometerBiases, com.irurueta.units.AngularSpeed[] gyroBiases, com.irurueta.algebra.Matrix accelerometerScaleFactorAndCrossCouplingErrors, com.irurueta.algebra.Matrix gyroScaleFactorAndCrossCouplingErrors, com.irurueta.algebra.Matrix gyroGDependentBiases, double accelerometerNoiseRootPSD, double gyroNoiseRootPSD, com.irurueta.units.Acceleration accelerometerQuantizationLevel, com.irurueta.units.AngularSpeed gyroQuantizationLevel) Constructor.- Parameters:
accelerometerBiases
- accelerometer biases for each IMU axis. Must have length 3.gyroBiases
- gyro biases for each IMU axis. Must have length 3.accelerometerScaleFactorAndCrossCouplingErrors
- accelerometer scale factors and cross coupling errors. Must be 3x3.gyroScaleFactorAndCrossCouplingErrors
- gyro scale factors and cross coupling errors. Must be 3x3.gyroGDependentBiases
- Cross biases introduced by the specific forces sensed by the accelerometer expressed in (rad-sec/m). Must be 3x3.accelerometerNoiseRootPSD
- accelerometer noise root PSD expressed in (m * s^-1.5).gyroNoiseRootPSD
- gyro noise root PSD expressed in (rad * s^-0.5).accelerometerQuantizationLevel
- accelerometer quantization level.gyroQuantizationLevel
- gyro quantization level.- Throws:
IllegalArgumentException
- if any value is invalid.
-
-
Method Details
-
getAccelerometerBiases
public double[] getAccelerometerBiases()Gets accelerometer biases for each IMU axis expressed in meters per squared second (m/s^2). By default, it is assumed to be all zeros.- Returns:
- accelerometer biases for each IMU axis.
-
getAccelerometerBiases
public void getAccelerometerBiases(double[] result) Gets accelerometer biases for each IMU axis expressed in meters per squared second (m/s^2). By default, it is assumed to be all zeros.- Parameters:
result
- instance where data will be stored.- Throws:
IllegalArgumentException
- if provided array does not have length 3.
-
setAccelerometerBiases
public void setAccelerometerBiases(double[] accelerometerBiases) Sets accelerometer biases for each IMU axis expressed in meters per squared second (m/s^2).- Parameters:
accelerometerBiases
- accelerometer biases for each IMU axis.- Throws:
IllegalArgumentException
- if provided array does not have length 3.
-
getAccelerometerBiasesAsMatrix
public com.irurueta.algebra.Matrix getAccelerometerBiasesAsMatrix()Gets accelerometer biases for each IMU axis expressed in meters per squared second (m/s^2) as a column matrix. By default, it is assumed to be all zeros.- Returns:
- 3x1 column matrix containing accelerometer biases for each IMU axis.
-
getAccelerometerBiasesAsMatrix
public void getAccelerometerBiasesAsMatrix(com.irurueta.algebra.Matrix result) Gets accelerometer biases for each IMU axis expressed in meters per squared second (m/s^2) as a column matrix. By default, it is assumed to be all zeros.- Parameters:
result
- instance where data will be stored.- Throws:
IllegalArgumentException
- if provided result matrix is not 3x1.
-
setAccelerometerBiases
public void setAccelerometerBiases(com.irurueta.algebra.Matrix accelerometerBiases) Sets accelerometer biases for each IMU axis expressed in meters per squared second (m/s^2) from a 3x1 column matrix.- Parameters:
accelerometerBiases
- 3x1 column matrix containing values to be set.- Throws:
IllegalArgumentException
- if provided matrix is not 3x1.
-
getAccelerometerBiasesAsAcceleration
public com.irurueta.units.Acceleration[] getAccelerometerBiasesAsAcceleration()Gets accelerometer biases for each IMU axis. By default, it is assumed to be all zeros.- Returns:
- accelerometer biases for each IMU axis.
-
getAccelerometerBiasesAsAcceleration
public void getAccelerometerBiasesAsAcceleration(com.irurueta.units.Acceleration[] result) Gets accelerometer biases for each IMU axis. By default, it is assumed to be all zeros.- Parameters:
result
- instance where data will be copied to.- Throws:
IllegalArgumentException
- if provided array does not have length 3.
-
setAccelerometerBiases
public void setAccelerometerBiases(com.irurueta.units.Acceleration[] accelerometerBiases) Sets accelerometer biases for each IMU axis.- Parameters:
accelerometerBiases
- accelerometer biases to be set.- Throws:
IllegalArgumentException
- if provided array does not have length 3.
-
getGyroBiases
public double[] getGyroBiases()Gets gyro biases for each IMU axis expressed in radians per second (rad/s). By default, it is assumed to be all zeros.- Returns:
- gyro biases for each IMU axis.
-
getGyroBiases
public void getGyroBiases(double[] result) Gets gyro biases for each IMU axis expressed in radians per second (rad/s). By default, it is assumed to be all zeros.- Parameters:
result
- instance where data will be stored.- Throws:
IllegalArgumentException
- if provided array does not have length 3.
-
setGyroBiases
public void setGyroBiases(double[] gyroBiases) Sets gyro biases for each IMU axis expressed in radians per second (rad/s).- Parameters:
gyroBiases
- gyro biases for each IMU axis.- Throws:
IllegalArgumentException
- if provided array does not have length 3.
-
getGyroBiasesAsMatrix
public com.irurueta.algebra.Matrix getGyroBiasesAsMatrix()Gets gyro biases for each IMU axis expressed in radians per second (rad/s) as a column matrix. By default, it is assumed to be all zeros.- Returns:
- 3x1 column matrix containing gyro biases for each IMU axis.
-
getGyroBiasesAsMatrix
public void getGyroBiasesAsMatrix(com.irurueta.algebra.Matrix result) Gets gyro biases for each IMU axis expressed in radians per second (rad/s) as a column matrix. By default, it is assumed to be all zeros.- Parameters:
result
- instance where data will be stored.- Throws:
IllegalArgumentException
- if provided result matrix is not 3x1.
-
setGyroBiases
public void setGyroBiases(com.irurueta.algebra.Matrix gyroBiases) Sets gyro biases for each IMU axis expressed in radians per second (rad/s) from a 3x1 column matrix.- Parameters:
gyroBiases
- 3x1 column matrix containing values to be set.- Throws:
IllegalArgumentException
- if provided matrix is not 3x1.
-
getGyroBiasesAsAngularSpeed
public com.irurueta.units.AngularSpeed[] getGyroBiasesAsAngularSpeed()Gets gyro biases for each IMU axis. By default, it is assumed to be all zeros.- Returns:
- gyro biases for each IMU axis.
-
getGyroBiasesAsAngularSpeed
public void getGyroBiasesAsAngularSpeed(com.irurueta.units.AngularSpeed[] result) Gets gyro biases for each IMU axis. By default, it is assumed to be all zeros.- Parameters:
result
- instance where data will be copied to.- Throws:
IllegalArgumentException
- if provided array does not have length 3.
-
setGyroBiases
public void setGyroBiases(com.irurueta.units.AngularSpeed[] gyroBiases) Sets gyro biases for each IMU axis.- Parameters:
gyroBiases
- gyro biases to be set.- Throws:
IllegalArgumentException
- if provided array does not have length 3.
-
getAccelerometerScaleFactorAndCrossCouplingErrors
public com.irurueta.algebra.Matrix getAccelerometerScaleFactorAndCrossCouplingErrors()Gets accelerometer scale factors and cross coupling errors. This is the product of matrix Ta containing cross coupling errors and Ka containing scaling factors. So that:Ma = [sx mxy mxz] = Ta*Ka [myx sy myz] [mzx mzy sz ]
Where:Ka = [sx 0 0 ] [0 sy 0 ] [0 0 sz]
andTa = [1 -alphaXy alphaXz ] [alphaYx 1 -alphaYz] [-alphaZx alphaZy 1 ]
Hence:Ma = [sx mxy mxz] = Ta*Ka = [sx -sy * alphaXy sz * alphaXz ] [myx sy myz] [sx * alphaYx sy -sz * alphaYz] [mzx mzy sz ] [-sx * alphaZx sy * alphaZy sz ]
This instance allows any 3x3 matrix however, typically alphaYx, alphaZx and alphaZy are considered to be zero if the accelerometer z-axis is assumed to be the same as the body z-axis. When this is assumed, myx = mzx = mzy = 0 and the Ma matrix becomes upper diagonal:Ma = [sx mxy mxz] [0 sy myz] [0 0 sz ]
Values of this matrix are unit-less. By default, it is the 3x3 identity matrix.- Returns:
- accelerometer scale factors and cross coupling errors.
-
getAccelerometerScaleFactorAndCrossCouplingErrors
public void getAccelerometerScaleFactorAndCrossCouplingErrors(com.irurueta.algebra.Matrix result) Gets accelerometer scale factors and cross coupling errors. This is the product of matrix Ta containing cross coupling errors and Ka containing scaling factors. So that:Ma = [sx mxy mxz] = Ta*Ka [myx sy myz] [mzx mzy sz ]
Where:Ka = [sx 0 0 ] [0 sy 0 ] [0 0 sz]
andTa = [1 -alphaXy alphaXz ] [alphaYx 1 -alphaYz] [-alphaZx alphaZy 1 ]
Hence:Ma = [sx mxy mxz] = Ta*Ka = [sx -sy * alphaXy sz * alphaXz ] [myx sy myz] [sx * alphaYx sy -sz * alphaYz] [mzx mzy sz ] [-sx * alphaZx sy * alphaZy sz ]
This instance allows any 3x3 matrix however, typically alphaYx, alphaZx and alphaZy are considered to be zero if the accelerometer z-axis is assumed to be the same as the body z-axis. When this is assumed, myx = mzx = mzy = 0 and the Ma matrix becomes upper diagonal:Ma = [sx mxy mxz] [0 sy myz] [0 0 sz ]
Values of this matrix are unit-less. By default, it is the 3x3 identity matrix.- Parameters:
result
- instance where data of scale factor and cross coupling matrix will be copied to. If needed, result instance will be resized.
-
setAccelerometerScaleFactorAndCrossCouplingErrors
public void setAccelerometerScaleFactorAndCrossCouplingErrors(com.irurueta.algebra.Matrix accelerometerScaleFactorAndCrossCouplingErrors) Sets accelerometer scale factors and cross coupling errors. This is the product of matrix Ta containing cross coupling errors and Ka containing scaling factors. So that:Ma = [sx mxy mxz] = Ta*Ka [myx sy myz] [mzx mzy sz ]
Where:Ka = [sx 0 0 ] [0 sy 0 ] [0 0 sz]
andTa = [1 -alphaXy alphaXz ] [alphaYx 1 -alphaYz] [-alphaZx alphaZy 1 ]
Hence:Ma = [sx mxy mxz] = Ta*Ka = [sx -sy * alphaXy sz * alphaXz ] [myx sy myz] [sx * alphaYx sy -sz * alphaYz] [mzx mzy sz ] [-sx * alphaZx sy * alphaZy sz ]
This instance allows any 3x3 matrix however, typically alphaYx, alphaZx and alphaZy are considered to be zero if the accelerometer z-axis is assumed to be the same as the body z-axis. When this is assumed, myx = mzx = mzy = 0 and the Ma matrix becomes upper diagonal:Ma = [sx mxy mxz] [0 sy myz] [0 0 sz ]
Values of this matrix are unit-less.- Parameters:
accelerometerScaleFactorAndCrossCouplingErrors
- scale factors and cross coupling matrix to be set.- Throws:
IllegalArgumentException
- if provided matrix is not 3x3.
-
getGyroScaleFactorAndCrossCouplingErrors
public com.irurueta.algebra.Matrix getGyroScaleFactorAndCrossCouplingErrors()Gets gyro scale factors and cross coupling errors. This is the product of matrix Tg containing cross coupling errors and Kg containing scaling factors. So that:Mg = [sx mxy mxz] = Tg*Kg [myx sy myz] [mzx mzy sz ]
Where:Kg = [sx 0 0 ] [0 sy 0 ] [0 0 sz]
andTg = [1 -gammaXy gammaXz ] [gammaYx 1 -gammaYz] [-gammaZx gammaZy 1 ]
Hence:Mg = [sx mxy mxz] = Tg*Kg = [sx -sy * gammaXy sz * gammaXz ] [myx sy myz] [sx * gammaYx sy -sz * gammaYz] [mzx mzy sz ] [-sx * gammaZx sy * gammaZy sz ]
This instance allows any 3x3 matrix however, typically gammaYx, gammaZx and gammaZy are considered to be zero if the accelerometer z-axis is assumed to be the same as the body z-axis. When this is assumed, myx = mzx = mzy = 0 and the Ma matrix becomes upper diagonal:Ma = [sx mxy mxz] [0 sy myz] [0 0 sz ]
Values of this matrix are unit-less. By default, it is the 3x3 identity matrix.- Returns:
- gyro scale factors and cross coupling errors.
-
getGyroScaleFactorAndCrossCouplingErrors
public void getGyroScaleFactorAndCrossCouplingErrors(com.irurueta.algebra.Matrix result) Gets gyro scale factors and cross coupling errors. This is the product of matrix Tg containing cross coupling errors and Kg containing scaling factors. So that:Mg = [sx mxy mxz] = Tg*Kg [myx sy myz] [mzx mzy sz ]
Where:Kg = [sx 0 0 ] [0 sy 0 ] [0 0 sz]
andTg = [1 -gammaXy gammaXz ] [gammaYx 1 -gammaYz] [-gammaZx gammaZy 1 ]
Hence:Mg = [sx mxy mxz] = Tg*Kg = [sx -sy * gammaXy sz * gammaXz ] [myx sy myz] [sx * gammaYx sy -sz * gammaYz] [mzx mzy sz ] [-sx * gammaZx sy * gammaZy sz ]
This instance allows any 3x3 matrix however, typically gammaYx, gammaZx and gammaZy are considered to be zero if the accelerometer z-axis is assumed to be the same as the body z-axis. When this is assumed, myx = mzx = mzy = 0 and the Ma matrix becomes upper diagonal:Ma = [sx mxy mxz] [0 sy myz] [0 0 sz ]
Values of this matrix are unit-less. By default, it is the 3x3 identity matrix.- Parameters:
result
- instance where data of scale factor and cross coupling matrix will be copied to. If needed, result instance will be resized.
-
setGyroScaleFactorAndCrossCouplingErrors
public void setGyroScaleFactorAndCrossCouplingErrors(com.irurueta.algebra.Matrix gyroScaleFactorAndCrossCouplingErrors) Sets gyro scale factors and cross coupling errors. This is the product of matrix Tg containing cross coupling errors and Kg containing scaling factors. So that:Mg = [sx mxy mxz] = Tg*Kg [myx sy myz] [mzx mzy sz ]
Where:Kg = [sx 0 0 ] [0 sy 0 ] [0 0 sz]
andTg = [1 -gammaXy gammaXz ] [gammaYx 1 -gammaYz] [-gammaZx gammaZy 1 ]
Hence:Mg = [sx mxy mxz] = Tg*Kg = [sx -sy * gammaXy sz * gammaXz ] [myx sy myz] [sx * gammaYx sy -sz * gammaYz] [mzx mzy sz ] [-sx * gammaZx sy * gammaZy sz ]
This instance allows any 3x3 matrix however, typically gammaYx, gammaZx and gammaZy are considered to be zero if the accelerometer z-axis is assumed to be the same as the body z-axis. When this is assumed, myx = mzx = mzy = 0 and the Ma matrix becomes upper diagonal:Ma = [sx mxy mxz] [0 sy myz] [0 0 sz ]
Values of this matrix are unit-less.- Parameters:
gyroScaleFactorAndCrossCouplingErrors
- scale factors and cross coupling matrix to be set.- Throws:
IllegalArgumentException
- if provided matrix is not 3x3.
-
getGyroGDependentBiases
public com.irurueta.algebra.Matrix getGyroGDependentBiases()Gets 3x3 matrix containing cross biases introduced by the specific forces sensed by the accelerometer. Values of this matrix are expressed in (rad-sec/m). By default, it is all zeros.- Returns:
- cross biases introduced by the specific forces sensed by the accelerometer.
-
getGyroGDependentBiases
public void getGyroGDependentBiases(com.irurueta.algebra.Matrix result) Gets 3x3 matrix containing cross biases introduced by the specific forces sensed by the accelerometer. Values of this matrix are expressed in (rad-sec/m). By default, it is all zeros.- Parameters:
result
- instance where data will be stored. If needed, result instance will be resized.
-
setGyroGDependentBiases
public void setGyroGDependentBiases(com.irurueta.algebra.Matrix gyroGDependentBiases) Sets 3x3 matrix containing cross biases introduced by the specific forces sensed by the accelerometer. Values of this matrix are expressed in (rad-sec/m).- Parameters:
gyroGDependentBiases
- cross biases introduced by the specific forces sensed by the accelerometer to be set.- Throws:
IllegalArgumentException
- if provided matrix is not 3x3.
-
getAccelerometerNoiseRootPSD
public double getAccelerometerNoiseRootPSD()Gets accelerometer noise root PSD expressed in (m * s^-1.5). By default it is zero.- Returns:
- accelerometer noise root PSD.
-
setAccelerometerNoiseRootPSD
public void setAccelerometerNoiseRootPSD(double accelerometerNoiseRootPSD) Sets accelerometer noise root PSD expressed in (m * s^-1.5)- Parameters:
accelerometerNoiseRootPSD
- accelerometer noise root PSD to be set.
-
getAccelerometerNoisePSD
public double getAccelerometerNoisePSD()Gets accelerometer noise PSD expressed in (m^2 * s^-3). By default, it is zero.- Returns:
- accelerometer noise PSD.
-
setAccelerometerNoisePSD
public void setAccelerometerNoisePSD(double accelerometerNoisePSD) Sets accelerometer noise PSD expressed in (m^2 * s^-3).- Parameters:
accelerometerNoisePSD
- accelerometer noise PSD to be set.- Throws:
IllegalArgumentException
- if provided value is negative.
-
getGyroNoiseRootPSD
public double getGyroNoiseRootPSD()Gets gyro noise root PSD expressed in (rad * s^-0.5). By default, it is zero.- Returns:
- gyro noise root PSD.
-
setGyroNoiseRootPSD
public void setGyroNoiseRootPSD(double gyroNoiseRootPSD) Sets gyro noise root PSD expressed in (rad * s^-0.5).- Parameters:
gyroNoiseRootPSD
- gyro noise root PSD to be set.
-
getGyroNoisePSD
public double getGyroNoisePSD()Gets gyro noise PSD expressed in (rad^2/s). By default, it is zero.- Returns:
- gyro noise PSD.
-
setGyroNoisePSD
public void setGyroNoisePSD(double gyroNoisePSD) Sets gyro noise PSD expressed in (rad^2/s).- Parameters:
gyroNoisePSD
- gyro noise PSD.- Throws:
IllegalArgumentException
- if provided value is negative.
-
getAccelerometerQuantizationLevel
public double getAccelerometerQuantizationLevel()Gets accelerometer quantization level expressed in meters per squared second (m/s^2). By default, it is zero when no quantization is assumed.- Returns:
- accelerometer quantization level.
-
setAccelerometerQuantizationLevel
public void setAccelerometerQuantizationLevel(double accelerometerQuantizationLevel) Sets accelerometer quantization level expressed in meters per squared second (m/s^2).- Parameters:
accelerometerQuantizationLevel
- accelerometer quantization level to be set.
-
getAccelerometerQuantizationLevelAsAcceleration
public com.irurueta.units.Acceleration getAccelerometerQuantizationLevelAsAcceleration()Gets accelerometer quantization level. By default, it is zero when no quantization is assumed.- Returns:
- accelerometer quantization level.
-
getAccelerometerQuantizationLevelAsAcceleration
public void getAccelerometerQuantizationLevelAsAcceleration(com.irurueta.units.Acceleration result) Gets accelerometer quantization level. By default, it is zero when no quantization is assumed.- Parameters:
result
- instance where value will be stored.
-
setAccelerometerQuantizationLevel
public void setAccelerometerQuantizationLevel(com.irurueta.units.Acceleration accelerometerQuantizationLevel) Sets accelerometer quantization level.- Parameters:
accelerometerQuantizationLevel
- accelerometer quantization level to be set.
-
getGyroQuantizationLevel
public double getGyroQuantizationLevel()Gets gyro quantization level expressed in radians per second (rad/s). By default, it is zero when no quantization is assumed.- Returns:
- gyro quantization level expressed in radians per second.
-
setGyroQuantizationLevel
public void setGyroQuantizationLevel(double gyroQuantizationLevel) Sets gyro quantization level expressed in radians per second (rad/s).- Parameters:
gyroQuantizationLevel
- gyro quantization level to be set.
-
getGyroQuantizationLevelAsAngularSpeed
public com.irurueta.units.AngularSpeed getGyroQuantizationLevelAsAngularSpeed()Gets gyro quantization level. By default, it is zero when no quantization is assumed.- Returns:
- gyro quantization level.
-
getGyroQuantizationLevelAsAngularSpeed
public void getGyroQuantizationLevelAsAngularSpeed(com.irurueta.units.AngularSpeed result) Gets gyro quantization level. By default, it is zero when no quantization is assumed.- Parameters:
result
- instance where value will be stored.
-
setGyroQuantizationLevel
public void setGyroQuantizationLevel(com.irurueta.units.AngularSpeed gyroQuantizationLevel) Sets gyro quantization level.- Parameters:
gyroQuantizationLevel
- gyro quantization level.
-
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. -
equals
Checks if provided object is an IMUErrors instance having exactly the same contents as this instance. -
clone
Makes a copy of this instance.- Overrides:
clone
in classObject
- Returns:
- a copy of this instance.
- Throws:
CloneNotSupportedException
- if clone fails for some reason.
-
convertAcceleration
private double convertAcceleration(com.irurueta.units.Acceleration acceleration) Converts acceleration instance to meters per squared second (m/s^2).- Parameters:
acceleration
- instance to be converted.- Returns:
- converted value.
-
convertAngularSpeed
private double convertAngularSpeed(com.irurueta.units.AngularSpeed angularSpeed) Converts angular speed instance to radians per second (rad/s).- Parameters:
angularSpeed
- instance ot be converted.- Returns:
- converted value.
-