public class BodyKinematicsGeneratorextends Object
Generates body kinematic instances from true body kinematic values taking into
account provided IMU errors for a calibrated IMU.
This implementation is based on the equations defined in "Principles of GNSS, Inertial, and Multisensor
Integrated Navigation Systems, Second Edition" and on the companion software available at:
https://github.com/ymjdz/MATLAB-Codes/blob/master/IMU_model.m
Internally generates an uncalibrated body kinematics instance containing a certain
level of noise for provided ground-truth body kinematics and IMU errors.
Generates uncalibrated body kinematics instances containing a certain level
of noise for provided ground-truth body kinematics and IMU errors.
This method ignores IMU quantization levels.
Parameters:
timeInterval - time interval between epochs.
trueKinematics - collection of ground-truth kinematics.
errors - IMU errors containing calibration data.
random - a random number generator to generate noise.
Returns:
a new collection containing generated uncalibrated kinematics
for each provided ground-truth one.
Generates uncalibrated body kinematics instances containing a certain level
of noise for provided ground-truth body kinematics and IMU errors.
This method ignores IMU quantization levels.
Parameters:
timeInterval - time interval between epochs.
trueKinematics - collection of ground-truth kinematics.
errors - IMU errors containing calibration data.
random - a random number generator to generate noise.
result - collection where generated uncalibrated kinematics
for each provided ground-truth one will be stored.
Generates uncalibrated body kinematics instances containing a certain level
of noise for provided ground-truth body kinematics and IMU errors.
This method ignores IMU quantization levels.
Parameters:
timeInterval - time interval between epochs expressed in seconds (s).
trueKinematics - collection of ground-truth kinematics.
errors - IMU errors containing calibration data.
random - a random number generator to generate noise.
Returns:
a new collection containing generated uncalibrated kinematics
for each provided ground-truth one.
Generates uncalibrated body kinematics instances containing a certain level
of noise for provided ground-truth body kinematics and IMU errors.
This method ignores IMU quantization levels.
Parameters:
timeInterval - time interval between epochs expressed in seconds (s).
trueKinematics - collection of ground-truth kinematics.
errors - IMU errors containing calibration data.
random - a random number generator to generate noise.
result - collection where generated uncalibrated kinematics
for each provided ground-truth one will be stored.
Generates an uncalibrated body kinematics instance containing a certain level
of noise for provided ground-truth body kinematics and IMU errors.
Parameters:
timeInterval - time interval between epochs expressed in seconds (s).
trueKinematics - ground-truth kinematics.
errors - IMU errors containing calibration data.
random - a random number generator to generate noise.
result - instance where uncalibrated body kinematics will be stored.
generate
public staticBodyKinematicsgenerate(com.irurueta.units.Time timeInterval,
BodyKinematics trueKinematics,
IMUErrors errors,
Random random,
double[] oldQuantizationResiduals,
double[] quantizationResiduals)
Generates an uncalibrated body kinematics instance containing a certain level
of noise for provided ground-truth body kinematics and IMU errors.
Parameters:
timeInterval - time interval between epochs.
trueKinematics - ground-truth kinematics.
errors - IMU errors containing calibration data.
random - a random number generator to generate noise.
oldQuantizationResiduals - previous quantization residuals from previous
executions. Optional. If provided, must have
length 6, if not provided quantization levels
are ignored.
quantizationResiduals - generated quantization residuals. Optional.
If provided, must have length 6.
Returns:
generated uncalibrated body kinematics.
Throws:
IllegalArgumentException - if either oldQuantizationResiduals or
quantizationResiduals are not length 6.
generate
public staticvoidgenerate(com.irurueta.units.Time timeInterval,
BodyKinematics trueKinematics,
IMUErrors errors,
Random random,
double[] oldQuantizationResiduals,
BodyKinematics result,
double[] quantizationResiduals)
Generates an uncalibrated body kinematics instance containing a certain level
of noise for provided ground-truth body kinematics and IMU errors.
Parameters:
timeInterval - time interval between epochs.
trueKinematics - ground-truth kinematics.
errors - IMU errors containing calibration data.
random - a random number generator to generate noise.
oldQuantizationResiduals - previous quantization residuals from previous
executions. Optional. If provided, must have
length 6, if not provided quantization levels
are ignored.
result - instance where uncalibrated body kinematics will be stored.
quantizationResiduals - generated quantization residuals. Optional.
If provided, must have length 6.
Throws:
IllegalArgumentException - if either oldQuantizationResiduals or
quantizationResiduals are not length 6.
generate
public staticBodyKinematicsgenerate(double timeInterval,
BodyKinematics trueKinematics,
IMUErrors errors,
Random random,
double[] oldQuantizationResiduals,
double[] quantizationResiduals)
Generates an uncalibrated body kinematics instance containing a certain level
of noise for provided ground-truth body kinematics and IMU errors.
Parameters:
timeInterval - time interval between epochs expressed in seconds (s).
trueKinematics - ground-truth kinematics.
errors - IMU errors containing calibration data.
random - a random number generator to generate noise.
oldQuantizationResiduals - previous quantization residuals from previous
executions. Optional. If provided, must have
length 6, if not provided quantization levels
are ignored.
quantizationResiduals - generated quantization residuals. Optional.
If provided, must have length 6.
Returns:
generated uncalibrated body kinematics.
Throws:
IllegalArgumentException - if either oldQuantizationResiduals or
quantizationResiduals are not length 6.
generate
public staticvoidgenerate(double timeInterval,
BodyKinematics trueKinematics,
IMUErrors errors,
Random random,
double[] oldQuantizationResiduals,
BodyKinematics result,
double[] quantizationResiduals)
Generates an uncalibrated body kinematics instance containing a certain level
of noise for provided ground-truth body kinematics and IMU errors.
Parameters:
timeInterval - time interval between epochs expressed in seconds (s).
trueKinematics - ground-truth kinematics.
errors - IMU errors containing calibration data.
random - a random number generator to generate noise.
oldQuantizationResiduals - previous quantization residuals from previous
executions. Optional. If provided, must have
length 6, if not provided quantization levels
are ignored.
result - instance where uncalibrated body kinematics will be stored.
quantizationResiduals - generated quantization residuals. Optional.
If provided, must have length 6.
Throws:
IllegalArgumentException - if either oldQuantizationResiduals or
quantizationResiduals are not length 6.
Internally generates an uncalibrated body kinematics instance containing a certain
level of noise for provided ground-truth body kinematics and IMU errors.
Parameters:
timeInterval - time interval between epochs expressed in seconds (s).
trueKinematics - ground-truth kinematics.
errors - IMU errors containing calibration data.
random - a random number generator to generate noise.
oldQuantizationResiduals - previous quantization residuals from previous
executions. Optional. If provided, must have
length 6, if not provided quantization levels
are ignored.
result - instance where uncalibrated body kinematics will be stored.
quantizationResiduals - generated quantization residuals. Optional.
If provided, must have length 6.
trueFibb - 3x1 matrix to be reused for specific force storage.
ma - 3x3 matrix to be reused for accelerometer scaling and
cross coupling errors.
ba - 3x1 matrix to be reused for accelerometer biases.
trueOmegaibb - 3x1 matrix to be reused for angular rates storage.
mg - 3x3 matrix to be reused for gyro scaling and cross
coupling errors.
bg - 3x1 matrix to be reused for gyro biases.
gg - 3x3 matrix to be reused for gyro dependant cross
coupling errors.
identity - 3x3 identity matrix to be reused.
tmp33 - 3x3 matrix to be reused.
tmp31a - 3x1 matrix to be reused.
tmp31b - 3x1 matrix to be reused.
Throws:
com.irurueta.algebra.WrongSizeException - if any of provided matrices has invalid size.
IllegalArgumentException - if either oldQuantizationResiduals or
quantizationResiduals are not length 6.