Calibration of Deterministic IMU Errors
Calibration of Deterministic IMU Errors
Spring 2015
This Article is brought to you for free and open access by the Honors Program at Scholarly Commons. It has been
accepted for inclusion in College of Engineering by an authorized administrator of Scholarly Commons. For more
information, please contact commons@erau.edu.
Prescott, Arizona Campus
Department of Electrical and Computer Engineering
Instructor:
Dr. Stephen Bruder
Final Report
“Calibration of Deterministic IMU Errors”
Contact Information:
Jeff Ferguson
fergusj5@my.erau.edu Grade:
EE 495 Final Report: “Calibration of Deterministic IMU Errors” Spring 2015
1. Abstract .................................................................................................................................... 4
1.i. Objectives ......................................................................................................................... 4
2. Introduction & Background ..................................................................................................... 4
2.i. Deterministic Error Characteristics .................................................................................. 4
2.ii. IMU Measurement Error Model ...................................................................................... 6
2.iii. IMU Mechanization ...................................................................................................... 7
3. Methods and Approach ............................................................................................................ 7
3.i. Calibrating the Accelerometer ......................................................................................... 7
3.ii. Calibrating the Gyroscope ................................................................................................ 9
4. Review of Results .................................................................................................................. 10
4.i. Calibration Calculations ................................................................................................. 10
4.ii. Comparing Calibrated and Non-Calibrated Performance .............................................. 14
5. Conclusion/Summary ............................................................................................................ 18
6. Appendix A: Accelerometer Calibration Data ...................................................................... 19
7. Appendix B: Gyroscope Calibration Data ............................................................................. 20
8. Appendix C: Known Stimulus Test Data .............................................................................. 22
9. Appendix D: main_data_collection.m ................................................................................... 23
10. Appendix E: main_calc_plot.m ......................................................................................... 26
11. Appendix F: proj_final.m................................................................................................... 33
12. References .......................................................................................................................... 37
Figure 8: Plotted errors, for fixed position, known rotation test ................................................... 17
Figure 9: Accelerometer Calibration Data .................................................................................... 19
Figure 10: Gyro Fixed Bias Calibration Data ............................................................................... 20
Figure 11: Gyro Scale Factor and Misalignment Calibration Data .............................................. 21
Figure 12: Known Stimulus Test Data.......................................................................................... 22
LIST OF SYMBOLS
b Measurement bias vector
bFB Measurement fixed bias vector
f ibb Inertial specific force vector in the body frame
gl Local gravity
Gg G-dependent bias
M Scale-factor and misalignment error matrix
m A, B Single misalignment term. A onto B.
sA Single scale factor term. Axis A.
b
ib Inertial angular rate vector in the body frame
Angular rate vector
w White noise vector
1. ABSTRACT
The VectorNav VN-200 is a MEMS navigation system that includes an accelerometer and
gyroscope, as well as other navigation sensors. The accelerometer and gyroscope alone make up
a commercial grade inertial measurement unit (IMU). Commercial grade IMUs produce poor
performance on their own, and when used in navigation systems they can accumulate significant
errors in less than a minute of operation. However, large increases in IMU accuracy can be
achieved by properly calibrating out some of the IMUs deterministic errors. In this paper,
methods are discussed for removing fixed biases, scale factor errors, and misalignment errors in
both accelerometers and gyroscopes using a rate table. After discussing the methods for
calibration, data collected from a VN-200 is used to calibrate the IMU. With the VN-200
calibrated, two separate tests using data collected from the sensor are performed to measure the
increase in performance of the IMU as a dead-reckoning navigation system. In the two tests, the
calibration reduced the calculated position error by 94.4% and 92.7% and the calculated attitude
error by 96.6% and 94.7%. This substantial increase in accuracy by performing a simple
calibration is so beneficial, it should performed for all accelerometers and gyroscopes whenever
possible. At the very least, sensors should have their fixed biases removed before being used in
navigation.
1.i. Objectives
Calibrate the VN-200 to find the measurement errors due to fixed biases, scale factor
errors, and misalignment errors.
Run an IMU mechanization using data collected from the VN-200 following a known
course. Confirm that calibrating the VN-200 improves the mechanization’s estimation of
position, velocity, and attitude.
gyroscope respectively, are errors in the measurement that are present regardless of the forces or
rates induced on the sensor. Biases can be further broken down into three types: fixed, stability,
and instability. The fixed biases, or offsets, in the IMU measurements, ba , FB and bg , FB , are the
only biases that are deterministic in nature and can be calibrated out. Stability biases change
randomly from run-to-run of the IMU, and instability biases change as a random process that is a
function of time. Fixed biases can create one of the largest errors in an IMU mechanization; the
errors increase at as a function of time squared for the accelerometer and time cubed for the
gyroscope.
Scale factor errors describe how well the output of the sensor corresponds to a force or rate
input. It allows for a way of modeling the difference between the ideal input-output slope of one
and the linear measurement slope produced by the IMU. IMUs are often modeled with a linear
response to simplify the calculation of measurements, but non-linearities can add further error to
a measurement. The concept of scale factor error is illustrated in Figure 1: Scale Factor Error.
10
5
Output
-5
Instrument output
-10 Output = Input
Output error due to scale factor
-15
-10 -5 0 5 10
Input
sa , x ma , xy ma , xz sg , x mg , xy mg , xz
M a ma , yx sa , y ma , yz M g mg , yx sg , y mg , yz (2.1)
ma , zx ma , zy sa , z mg , zx mg , zy sg , z
Ignoring the white noise and two of the bias terms from Equation (2.2) reduces the
measurement model to error terms that are deterministic. Equation (2.3) estimates the
measurement model using just the terms that can be calibrated out.
An estimate of the actual specific force can be calculated by rearranging Equation (2.3) to
solve for the specific force in terms of the measurement and error terms. The estimate in
Equation (2.4) is the calibration model for the accelerometer.
ˆ ˆ
fibb ( I3 x 3 Mˆ a )1 ( fibb ba , FB ) (2.4)
A similar process can be taken for finding the calibration model of the gyroscope. Equation
(2.5) [2] shows how different errors sources each contribute to skewing the gyroscope
measurements away from the true angular rates incident on the IMU.
Eliminating the non-deterministic terms and the g-sensitivity term in Equation (2.5) produces
Equation (2.6). The g-sensitivity term is deterministic and can be calibrated on some IMUs.
However, VectorNav does not list an expected g-sensitivity for the VN-200 and does not offer
any direction for calibrating the g-sensitivity of their gyroscopes.
Because the profiles for testing the calibration and mechanization do not include large specific
forces, the g-sensitivity term would, at most, create small errors, and little harm will come from
ignoring it.
ˆ
ˆibb ( I3 x3 Mˆ g )1 (ibb bg , FB ) (2.7)
f b , f b ,
ib , x ib , x
ˆ b , 1
ba , FB fib , y fib , y
b ,
(3.1)
2
f b , f b ,
ib , z ib , z
This test works with the assumption that the fixed bias is the same regardless of the
orientation or forces on the sensor. By adding the two opposing measurements together, the
opposite gravity measurements will cancel each other out and twice the fixed bias will be left
behind.
b, b,
sˆa , x 0 0 fib , x fib , x 0 0
1 I3x3
0 sˆa , y 0 0 fibb,,y fibb,,y 0 (3.2)
2 gl
0 0 sˆa , z 0 0 b, b ,
fib, z fib , z
By subtracting the two measurement averages, the effects of the fixed bias are removed, and
the sensor’s output due to gravity are doubled. Because the input force, local gravity, is known,
the input-to-output ratio can be calculated. The scale factor error is derived from this ratio.
This set of measurements requires setting the rate-table to rotate at a known rate around each
of the sense-axes. This known rate, , is then divided out of the measurements to calculate the
input-to-output error.
4. REVIEW OF RESULTS
Using the rate table in the space systems lab at Embry-Riddle Aeronautical University, data
was collected to calibrate the gyroscope and accelerometer in the VN-200. The accelerometer
measurements from the 6-point tumble test are plotted in Appendix A: Accelerometer
Calibration Data. The gyroscope measurements from the 6-point tumble test and the known rate
rotation test are plotted in Appendix B: Gyroscope Calibration Data. The MATLAB file used to
calculated all of the deterministic errors from the IMU data is included in Appendix E:
main_calc_plot.m
1.2471
ba , FB 0.2228 mg
ˆ
6.6710
The scale factor error is presented below in parts per million. A linear extrapolation of the
scale factor error is plotted in Figure 3: Accelerometer Scale Factor. Across the range of the
sensor, the maximum error due to scale factor error is a quarter of a meter per second squared.
1,551 0 0
sˆa 0 1, 633 0 ppm
0 0 214
Scale Factor Error (x) Scale Factor Error (y) Scale Factor Error (z)
0.3 0.3 0.3
Error (m/s 2)
Error (m/s 2)
0 0 0
The misalignment values required one more calculation beyond that given in Equation (3.3),
because the misalignment matrix should be a skew symmetric matrix. The values for the
alignment of axis A to axis B should be the negative of the values for the alignment of axis B to
A. This property was ensured in the calculation by averaging the measurement for the cross-
coupled axes. A plot of the estimated axes (RGB) versus the body frame (black) is shown in
Figure 4: Accelerometer Misalignment.
Accelerometer Misalignment
0.8
0.6
Z
0.4
0.2
0
0
0.2
0.5 0.4
0.6
0.8
1 1
X
Y
According to the VectorNav datasheet, the accelerometer should have a scale factor error
between ±0.05˚ [5]. As seen below, the calculated misalignment was slightly greater than the
range listed in the VN-200 specification. This could be due to incorrect assumptions and
methods used for ensuring the misalignment matrix was skew symmetric.
0 0.4604 0.0243
mˆ a 0.4604 0 0.0485 degrees
0.0243 0.0485 0
1,826
bg , FB 1, 714 degrees/hour
ˆ
2, 791
For the known rate tests to calibrate the scale factor and misalignment errors, the VN-200 was
rotated at ±30 degrees per second around the x- and y-axes, and at ±60 degrees around the z-axis.
The different rates were chosen due to the different axes utilized on the rate table. The z-axis
could be rotated on the first-axis rotational table, while the x- and y-axes had to be rotated using
the second-axis yoke. The first axis put less stress on the data-collection cable, so the VN-200
could be rotated at a higher rate safely.
The scale factor error is presented below in parts per million. A linear extrapolation of the
scale factor error is plotted in Figure 5: Gyroscope Scale Factor. Across the range of the sensor,
the maximum error due to scale factor error is three degrees per second
1, 691 0 0
sˆa 0 979 0 ppm
0 0 227
Scale Factor Error (x) Scale Factor Error (y) Scale Factor Error (z)
4 4 4
2 2 2
Error (/sec)
Error (/sec)
Error (/sec)
0 0 0
-2 -2 -2
-4 -4 -4
-2000 0 2000 -2000 0 2000 -2000 0 2000
Angular Rate (/sec) Angular Rate (/sec) Angular Rate (/sec)
The misalignment for the gyroscope was calculated the same way it was calculated for the
accelerometer. A plot of the estimated axes (RGB) versus the body frame (black) is shown in
Figure 6: Gyroscope Misalignment. According to the VectorNav datasheet, the gyroscope should
have a misalignment error between ±0.05˚ [5]. Once again, the calculated misalignment was
slightly greater than the range listed in the VN-200 specification, especially in the x-y coupling.
This consistent result between the gyroscope and accelerometer could indicate a flaw in the
alignment of the test setup.
0 0.4579 0.0374
mˆ a 0.4579 0 0.0581 degrees
0.0374 0.0581 0
Gyroscope Misalignment
0.8
0.6
Z 0.4
0.2
0
0
0.2
0.5 0.4
0.6
0.8
1 1
X
Y
For both the accelerometer and the gyroscope, the scale factor and misalignment errors are
relatively small compared to the fixed bias errors. This result indicates that the biggest increase
in performance will come from calibrating out the fixed bias, not the misalignment and scale
factor.
The results from the first test profile are listed in Table 2: Errors after 20 Seconds (Fixed
Position/Fixed Attitude). As seen in the table, the error with complete calibration of deterministic
errors had the smallest errors after 20 seconds. It can also be seen that the fixed bias calibration
had the largest effect on correcting the measurements from the IMU. The scale factor and
misalignment matrices had little effect on the overall error in the mechanization. In the complete
mechanization, they improved the error, but without removing the fixed bias, they actually made
the error worse.
The results from the second test profile are listed in Table 3: Errors after 20 Seconds (Fixed
Position/Rotating Attitude). These results are similar to the results observed in the first test
profile. Like the first test, the fixed bias had the most significant role in improving the errors in
the mechanization and the scale factor and misalignment calibration were only positive when the
fixed bias had been removed.
The next two sections show the error plots for each of the two trial runs before and after
calibration. For both trial runs it can clearly be seen that the full calibration aided the IMU
mechanization immensely.
rx (m)
0
-1
Position Error
-50 -2
0 2 4 6 8 10 12 14 16 18 20 0 2 4 6 8 10 12 14 16 18 20
0 1
RSSerror =1568m RSSerror =17m
ry (m)
ry (m)
-50 0.5
-100 0
0 2 4 6 8 10 12 14 16 18 20 0 2 4 6 8 10 12 14 16 18 20
0 0
RSSerror =2131m RSSerror=170m
-50
rz (m)
rz (m)
-5
-100
-150 -10
0 2 4 6 8 10 12 14 16 18 20 0 2 4 6 8 10 12 14 16 18 20
Time (sec) Time (sec)
ECEF Mechanization: Velocity Error veeb ECEF Mechanization: Velocity Error veeb
10 0.2
vx (m/s)
vx (m/s)
5
0
0
Velocity Error
-5 -0.2
0 2 4 6 8 10 12 14 16 18 20 0 2 4 6 8 10 12 14 16 18 20
0 0.1
vy (m/s)
vy (m/s)
-5 0.05
-10 0
-15 -0.05
0 2 4 6 8 10 12 14 16 18 20 0 2 4 6 8 10 12 14 16 18 20
0 0
vz (m/s)
vz (m/s)
-10 -0.5
-20 -1
0 2 4 6 8 10 12 14 16 18 20 0 2 4 6 8 10 12 14 16 18 20
Time (sec) Time (sec)
ECEF Mechanization: Attitude Error Ceb as a vector ECEF Mechanization: Attitude Error Ceb as a vector
0 1
0.5
x (°)
x (°)
-5
0
Attitude Error
-10 -0.5
0 2 4 6 8 10 12 14 16 18 20 0 2 4 6 8 10 12 14 16 18 20
0 0.4
0.2
y (°)
y (°)
-10
0
-20 -0.2
0 2 4 6 8 10 12 14 16 18 20 0 2 4 6 8 10 12 14 16 18 20
15 0.1
10
z (°)
z (°)
0
5
0 -0.1
0 2 4 6 8 10 12 14 16 18 20 0 2 4 6 8 10 12 14 16 18 20
Time (sec) Time (sec)
rx (m)
0
-0.5
Position Error
-2 -1
0 2 4 6 8 10 12 14 16 18 20 0 2 4 6 8 10 12 14 16 18 20
0 0.5
RSSerror=595m RSSerror =21m
ry (m)
ry (m)
0
-20
-0.5
-40 -1
0 2 4 6 8 10 12 14 16 18 20 0 2 4 6 8 10 12 14 16 18 20
60 4
RSSerror=843m RSSerror =80m
40
rz (m)
rz (m)
2
20
0 0
0 2 4 6 8 10 12 14 16 18 20 0 2 4 6 8 10 12 14 16 18 20
Time (sec) Time (sec)
ECEF Mechanization: Velocity Error veeb ECEF Mechanization: Velocity Error veeb
1 0.1
vx (m/s)
vx (m/s)
0.5
0
0
Velocity Error
-0.5 -0.1
0 2 4 6 8 10 12 14 16 18 20 0 2 4 6 8 10 12 14 16 18 20
0 0.1
vy (m/s)
vy (m/s)
-2 0
-4 -0.1
0 2 4 6 8 10 12 14 16 18 20 0 2 4 6 8 10 12 14 16 18 20
6 0.4
vz (m/s)
vz (m/s)
4
0.2
2
0 0
0 2 4 6 8 10 12 14 16 18 20 0 2 4 6 8 10 12 14 16 18 20
Time (sec) Time (sec)
ECEF Mechanization: Attitude Error Ceb as a vector ECEF Mechanization: Attitude Error Ceb as a vector
10 1
0
x (°)
x (°)
0.5
-10
Attitude Error
-20 0
0 2 4 6 8 10 12 14 16 18 20 0 2 4 6 8 10 12 14 16 18 20
5 0.2
0
y (°)
y (°)
0.1
-5
-10 0
0 2 4 6 8 10 12 14 16 18 20 0 2 4 6 8 10 12 14 16 18 20
2 0.5
0
z (°)
z (°)
0
-0.5
-2 -1
0 2 4 6 8 10 12 14 16 18 20 0 2 4 6 8 10 12 14 16 18 20
Time (sec) Time (sec)
5. CONCLUSION/SUMMARY
Calibration of the VectorNav VN-200 produced massive increases in performance over the
short 20 second test runs of the IMU. The position, velocity, and attitude improvements for each
of the tests are listed in Table 4: Improvements in PVA after Calibration.
The greatest improvement in the errors calculated by the mechanization came from removing
the fixed biases in the sensors. Removing the scale-factor and misalignment terms did little to
improve the accuracy of the measurements. This could be due to several factors. First, the
calculated scale-factor and misalignment terms were relatively insignificant compared to the
errors in fixed bias. The axes were fairly well aligned and scaled to begin with. Also, the two
sample profiles did not test many of the situations where the scale-factor and misalignment
would have a large effect. If the VN-200 were subjected to greater, and more varying, forces and
angular rates than it was, the terms in the M matrix might have played a large role in improving
the IMU measurements.
The improvements due to calibration are not quite as good as the 95-98% improvements
advertised on VectorNav’s calibration page [4], but they are in a very similar range. Further
improvements in the calibration could be achieved by performing the measurements at different
regulated temperatures and over shorter periods of time. In the twenty minutes that were spent
collecting all the data, random errors could have found their way into the IMU measurements.
The calibration, however, did produce satisfactory results in decreasing the IMU measurement
errors.
Positive G Negative G
Gravity aligned with +x-axis Gravity aligned with -x-axis
10 2
8 0
6 -2
Specific Force (m/s2)
4 -4
2 -6
0 -8
-2 -10
0 10 20 30 40 50 60 70 80 90 100 0 10 20 30 40 50 60 70 80 90 100
Samples Samples
8 0
6 -2
Specific Force (m/s2)
4 -4
2 -6
0 -8
-2 -10
0 10 20 30 40 50 60 70 80 90 100 0 10 20 30 40 50 60 70 80 90 100
Samples Samples
8 0
6 -2
Specific Force (m/s2)
4 -4
2 -6
0 -8
-2 -10
0 10 20 30 40 50 60 70 80 90 100 0 10 20 30 40 50 60 70 80 90 100
Samples Samples
Positive G Negative G
Gravity aligned with +x-axis Gravity aligned with -x-axis
0.015 0.015
0.014 0.014
0.013
0.013
0.012
Angular Rate (rad/sec)
0.011
0.01
0.01
0.009
0.009
0.008
0.008
0.007
0.007 0.006
0.006 0.005
0 10 20 30 40 50 60 70 80 90 100 0 10 20 30 40 50 60 70 80 90 100
Samples Samples
0.015
0.014
0.014
0.013
Angular Rate (rad/sec)
0.012
0.012
y-axis
0.011 0.01
0.01
0.008
0.009
0.008
0.006
0.007
0.006 0.004
0 10 20 30 40 50 60 70 80 90 100 0 10 20 30 40 50 60 70 80 90 100
Samples Samples
0.015
0.016
0.014
0.013
Angular Rate (rad/sec)
0.014
0.012
z-axis
0.012 0.011
0.01
0.01
0.009
0.008
0.008
0.007
0.006 0.006
0 10 20 30 40 50 60 70 80 90 100 0 10 20 30 40 50 60 70 80 90 100
Samples Samples
30 0
-5
25
Angular Rate (/sec)
20
-15
15
-20
10
-25
5 -30
0 -35
0 10 20 30 40 50 60 70 80 90 100 0 10 20 30 40 50 60 70 80 90 100
Samples Samples
30 0
-5
25
Angular Rate (/sec)
-10
y-axis
20
-15
15
-20
10
-25
5 -30
0 -35
0 10 20 30 40 50 60 70 80 90 100 0 10 20 30 40 50 60 70 80 90 100
Samples Samples
60 0
50 -10
Angular Rate (/sec)
40 -20
30 -30
20 -40
10 -50
0 -60
0 10 20 30 40 50 60 70 80 90 100 0 10 20 30 40 50 60 70 80 90 100
Samples Samples
0 0
-2 -2
Specific Force (m/s2)
-6 -6
-8 -8
-10 -10
0 2 4 6 8 10 12 14 16 18 20 0 2 4 6 8 10 12 14 16 18 20
Time (sec) Time (sec)
Known Stimulus Test: Sitting still Known Stimulus Test: Rotating 30/sec
0.016 35
0.015
30
0.014
Gyroscope Data
0.013 25
Angular Rate (/sec)
0.012
20
0.011
15
0.01
0.009 10
0.008
5
0.007
0.006 0
0 2 4 6 8 10 12 14 16 18 20 0 2 4 6 8 10 12 14 16 18 20
Time (sec) Time (sec)
9. APPENDIX D: MAIN_DATA_COLLECTION.M
% Procesing the VN200 IMU data
clear all; % Clear all variables from the workspace
close all; % Close all windows
clc; % "Clean" the command window
%% z-axis data
display('Collect data: z-axis aligned with positive G (space to continue)');
pause % Wait for user input to continue
d_z_pos_g = zeros(N,11); % Initialize space for the data-set
for i=1:N % Collect N number of samples
d_z_pos_g(i,:) = VNreadregister(s, 'IMU'); % Read the IMU data
if mod(i,25) == 0
disp([' Samples = ', num2str(i)]);
end
end
save('d_z_pos_g.mat','d_z_pos_g');
fprintf(' Data written to ''d_z_pos_g.mat''\n\n');
%% x-axis data
display('Collect data: x-axis aligned with positive G (space to continue)');
pause % Wait for user input to continue
d_x_pos_g = zeros(N,11); % Initialize space for the data-set
for i=1:N % Collect N number of samples
d_x_pos_g(i,:) = VNreadregister(s, 'IMU'); % Read the IMU data
if mod(i,25) == 0
disp([' Samples = ', num2str(i)]);
end
end
save('d_x_pos_g.mat','d_x_pos_g');
fprintf(' Data written to ''d_x_pos_g.mat''\n\n');
%% y-axis data
display('Collect data: y-axis aligned with positive G (space to continue)');
pause % Wait for user input to continue
d_y_pos_g = zeros(N,11); % Initialize space for the data-set
for i=1:N % Collect N number of samples
d_y_pos_g(i,:) = VNreadregister(s, 'IMU'); % Read the IMU data
if mod(i,25) == 0
disp([' Samples = ', num2str(i)]);
end
end
save('d_y_pos_g.mat','d_y_pos_g');
fprintf(' Data written to ''d_y_pos_g.mat''\n\n');
%% Define variables
local_g = gravity(34.61453654,1582); % Calculate local gravity (m/s^2)
g = 9.80665; % Standard gravity constant (m/s^2)
fixed_rate_30 = 30*pi/180; % Rate table rate in (rad/sec)
fixed_rate_60 = 60*pi/180; % Rate table rate in (rad/sec)
% Display results
display(accel_b_x);
display(accel_b_y);
display(accel_b_z);
% Display results
display(accel_sf_x);
display(accel_sf_y);
display(accel_sf_z);
% Plot Results
asfe = figure;
set(asfe,'Position',[10 200 800 250]);
xlim_asfe = [-16 16];
xlabel_asfe = 'Acceleration (g)';
ylim_asfe = [-0.3 0.3];
ylabel_asfe = 'Error (m/s^2)';
stdg = 9.80665;
x = xlim_asfe(1):1:xlim_asfe(2);
y = x*stdg;
ys_x = y*accel_sp_x;
ys_y = y*accel_sp_y;
ys_z = y*accel_sp_z;
subplot(1,3,1);
hold on;
plot(x,y-ys_x,'r');
xlim(xlim_asfe);
xlabel(xlabel_asfe);
ylim(ylim_asfe);
ylabel(ylabel_asfe);
title('Scale Factor Error (x)');
subplot(1,3,2);
hold on;
plot(x,y-ys_y,'g');
xlim(xlim_asfe);
xlabel(xlabel_asfe);
ylim(ylim_asfe);
ylabel(ylabel_asfe);
title('Scale Factor Error (y)');
subplot(1,3,3);
hold on;
plot(x,y-ys_z,'b');
xlim(xlim_asfe);
xlabel(xlabel_asfe);
ylim(ylim_asfe);
ylabel(ylabel_asfe);
title('Scale Factor Error (z)');
%% Accelerometer Misalignment
a_m_yx = atand((x_pos_g(:,5) - x_neg_g(:,5)) / (2*local_g));
a_m_zx = atand((x_pos_g(:,6) - x_neg_g(:,6)) / (2*local_g));
a_m_xy = atand((y_pos_g(:,4) - y_neg_g(:,4)) / (2*local_g));
a_m_zy = atand((y_pos_g(:,6) - y_neg_g(:,6)) / (2*local_g));
a_m_xz = atand((z_pos_g(:,4) - z_neg_g(:,4)) / (2*local_g));
a_m_yz = atand((z_pos_g(:,5) - z_neg_g(:,5)) / (2*local_g));
accel_m_yx = (a_m_yx - a_m_xy)/2;
accel_m_zx = (a_m_zx - a_m_xz)/2;
accel_m_xy = (a_m_xy - a_m_yx)/2;
accel_m_zy = (a_m_zy - a_m_yz)/2;
accel_m_xz = (a_m_xz - a_m_zx)/2;
accel_m_yz = (a_m_yz - a_m_zy)/2;
% Display results
display(accel_m_xy)
display(accel_m_xz)
display(accel_m_yx)
display(accel_m_yz)
display(accel_m_zx)
display(accel_m_zy)
% Plot figure
figure;
hold on;
title('Accelerometer Misalignment');
% Display results
display(gyro_b_x);
display(gyro_b_y);
display(gyro_b_z);
% Display results
display(gyro_sf_x);
display(gyro_sf_y);
display(gyro_sf_z);
% Plot Results
gsfe = figure;
set(gsfe,'Position',[10 200 800 250]);
xlim_gsfe = [-2000 2000];
xlabel_gsfe = 'Angular Rate (\circ/sec)';
ylim_gsfe = [-4 4];
ylabel_gsfe = 'Error (\circ/sec)';
xg = xlim_gsfe(1):1:xlim_gsfe(2);
ygs_x = xg*gyro_sp_x;
ygs_y = xg*gyro_sp_y;
ygs_z = xg*gyro_sp_z;
subplot(1,3,1);
hold on;
plot(xg,xg-ygs_x,'r');
xlim(xlim_gsfe);
xlabel(xlabel_gsfe);
ylim(ylim_gsfe);
ylabel(ylabel_gsfe);
title('Scale Factor Error (x)');
subplot(1,3,2);
hold on;
plot(xg,xg-ygs_y,'g');
xlim(xlim_gsfe);
xlabel(xlabel_gsfe);
ylim(ylim_gsfe);
ylabel(ylabel_gsfe);
title('Scale Factor Error (y)');
subplot(1,3,3);
hold on;
plot(xg,xg-ygs_z,'b');
xlim(xlim_gsfe);
xlabel(xlabel_gsfe);
ylim(ylim_gsfe);
ylabel(ylabel_gsfe);
title('Scale Factor Error (z)');
%% Gyroscope Misalignment
g_m_yx = atand((rot_pos_x(:,8) - rot_neg_x(:,8)) / (2*fixed_rate_30));
g_m_zx = atand((rot_pos_x(:,9) - rot_neg_x(:,9)) / (2*fixed_rate_30));
g_m_xy = atand((rot_pos_y(:,7) - rot_neg_y(:,7)) / (2*fixed_rate_30));
g_m_zy = atand((rot_pos_y(:,9) - rot_neg_y(:,9)) / (2*fixed_rate_30));
g_m_xz = atand((rot_pos_z(:,7) - rot_neg_z(:,7)) / (2*fixed_rate_60));
g_m_yz = atand((rot_pos_z(:,8) - rot_neg_z(:,8)) / (2*fixed_rate_60));
gyro_m_yx = (g_m_yx - g_m_xy)/2;
gyro_m_zx = (g_m_zx - g_m_xz)/2;
gyro_m_xy = (g_m_xy - g_m_yx)/2;
gyro_m_zy = (g_m_zy - g_m_yz)/2;
gyro_m_xz = (g_m_xz - g_m_zx)/2;
gyro_m_yz = (g_m_yz - g_m_zy)/2;
% Display results
display(gyro_m_xy)
display(gyro_m_xz)
display(gyro_m_yx)
display(gyro_m_yz)
display(gyro_m_zx)
display(gyro_m_zy)
% Plot figure
figure;
hold on;
title('Gyroscope Misalignment');
% figure;
% plot(d_rot_neg_x(:,7:9).*180./pi)
% title('Rotating -30\circ/sec about x-axis');
% xlabel('Samples');
% ylabel('Angular Rate (\circ/sec)');
%
% figure;
% plot(d_rot_neg_y(:,7:9).*180./pi)
% title('Rotating -30\circ/sec about y-axis');
% xlabel('Samples');
% ylabel('Angular Rate (\circ/sec)');
%
% figure;
% plot(d_rot_neg_z(:,7:9).*180./pi)
% title('Rotating -60\circ/sec about z-axis');
% xlabel('Samples');
% ylabel('Angular Rate (\circ/sec)');
%
% figure;
% plot(d_rot_pos_x(:,7:9).*180./pi)
% title('Rotating +30\circ/sec about x-axis');
% xlabel('Samples');
% ylabel('Angular Rate (\circ/sec)');
%
% figure;
% plot(d_rot_pos_y(:,7:9).*180./pi)
% title('Rotating +30\circ/sec about y-axis');
% xlabel('Samples');
% ylabel('Angular Rate (\circ/sec)');
%
% figure;
% plot(d_rot_pos_z(:,7:9).*180./pi)
% title('Rotating +60\circ/sec about z-axis');
% xlabel('Samples');
% ylabel('Angular Rate (\circ/sec)');
%
% figure;
% plot(d_x_neg_g(:,4:6))
% title('dxnegg');
% title('Gravity aligned with -x-axis');
% xlabel('Samples');
% ylabel('Specific Force (m/s^2)');
%
% figure;
% plot(d_y_neg_g(:,4:6))
% title('Gravity aligned with -y-axis');
% xlabel('Samples');
% ylabel('Specific Force (m/s^2)');
%
% figure;
% plot(d_z_neg_g(:,4:6))
% title('Gravity aligned with -z-axis');
% xlabel('Samples');
% ylabel('Specific Force (m/s^2)');
%
% figure;
% plot(d_x_pos_g(:,4:6))
% title('Gravity aligned with +x-axis');
% xlabel('Samples');
% ylabel('Specific Force (m/s^2)');
%
% figure;
% plot(d_y_pos_g(:,4:6))
% title('Gravity aligned with +y-axis');
% xlabel('Samples');
% ylabel('Specific Force (m/s^2)');
%
% figure;
% plot(d_z_pos_g(:,4:6))
% title('Gravity aligned with +z-axis');
% xlabel('Samples');
% ylabel('Specific Force (m/s^2)');
%
% figure;
% plot(d_x_neg_g(:,7:9))
% title('dxnegg');
% title('Gravity aligned with -x-axis');
% xlabel('Samples');
% ylabel('Angular Rate (rad/sec)');
%
% figure;
% plot(d_y_neg_g(:,7:9))
% title('Gravity aligned with -y-axis');
% xlabel('Samples');
% ylabel('Angular Rate (rad/sec)');
%
% figure;
% plot(d_z_neg_g(:,7:9))
% title('Gravity aligned with -z-axis');
% xlabel('Samples');
% ylabel('Angular Rate (rad/sec)');
%
% figure;
% plot(d_x_pos_g(:,7:9))
% title('Gravity aligned with +x-axis');
% xlabel('Samples');
% ylabel('Angular Rate (rad/sec)');
%
% figure;
% plot(d_y_pos_g(:,7:9))
% title('Gravity aligned with +y-axis');
% xlabel('Samples');
% ylabel('Angular Rate (rad/sec)');
%
% figure;
% plot(d_z_pos_g(:,7:9))
% title('Gravity aligned with +z-axis');
% xlabel('Samples');
% ylabel('Angular Rate (rad/sec)');
%
% figure;
% plot(0.01:0.01:20,d_t_still(:,4:6))
% title('Known Stimulus Test: Sitting still');
% xlabel('Time (sec)');
% ylabel('Specific Force (m/s^2)');
%
% figure;
% plot(0.01:0.01:20,d_t_still(:,7:9))
% title('Known Stimulus Test: Sitting still');
% xlabel('Time (sec)');
% ylabel('Angular Rate (\circ/sec)');
%
% figure;
% plot(0.01:0.01:20,d_t_rot(:,4:6))
% title('Known Stimulus Test: Rotating 30\circ/sec');
% xlabel('Time (sec)');
% ylabel('Specific Force (m/s^2)');
%
% figure;
% plot(0.01:0.01:20,d_t_rot(:,7:9).*180./pi)
% title('Known Stimulus Test: Rotating 30\circ/sec');
% xlabel('Time (sec)');
% ylabel('Angular Rate (\circ/sec)');
save('calibration.mat','b_a_FB','M_a','b_g_FB','M_g')
clear all % Remove all items from workspace - release system memory
close all % Close all open figures (i.e. plots)
clc % Clear the command window
%**************************************************************************
% ****** Generate the ground truth data *******************************
%**************************************************************************
%--------------------------------------------------------------------------
%% ECI to ECEF Coordinate Frame
%--------------------------------------------------------------------------
% Generate Angular Velocity
w_ie = constants.w_ie; % WGS84 Earth rate (rad/s)
w_i__i_e = [0; 0; w_ie]; % Angular velocity of {e} wrt {i} resolved in {i} (rad/s)
Ohm_i__i_e = [ 0 , -w_ie, 0; ... % Skew symmetric version of w_i__i_e (rad/s)
w_ie, 0 , 0; ...
0 , 0 , 0];
constants.Ohm_i__i_e = Ohm_i__i_e; % will need later (rad/s)
% Generate PVA
r_i__i_e = [0; 0; 0]; % Position of the origin of {e} wrt origin of {i} resolved in {i} (m)
v_i__i_e = [0; 0; 0]; % Velocity of e-frame wrt i-frame (m/s)
a_i__i_e = [0; 0; 0]; % Acceleration of e-frame wrt i-frame (m/s^2)
%--------------------------------------------------------------------------
%% ECEF to Navigation Coordinate Frame
%--------------------------------------------------------------------------
% The curvlinear coordinates of the origin of the fixed frame
L_f = 34.61453654*ones(1,N); % Geodetic Latitude of the fixed frame (rad)
lambda_f = -112.4502933*ones(1,N); % Geodetic Longitude of the fixed frame (rad)
h_f = 1582*ones(1,N); % Geodetic height of the fixed frame (m)
% frame
r_e__e_f = zeros(3,N);
for i=1:N
r_e__e_f(:,i) = llh2xyz(L_f(i), lambda_f(i), h_f(i)); % Position of the origin of the radar
tracking frame wrt e-frame org resolved in the e-frame (m)
end
r_f__f_b = zeros(3,N); % Position of the origin of {b} wrt {f} org resolved in {f} (m)
% Orientation of the Nav frame of the ship at the start wrt the ECEF frame
C_e__n_IMU_start = [ -cos(lambda_f(1))*sin(L_f(1)), -sin(lambda_f(1)) , -
cos(lambda_f(1))*cos(L_f(1));
-sin(lambda_f(1))*sin(L_f(1)), cos(lambda_f(1)) , -sin(lambda_f(1))*cos(L_f(1));
cos(L_f(1)) , 0 , -sin(L_f(1))];
C_e__f = C_e__n_IMU_start; % The orientation of the tracker frame stays constant wrt ECEF
r_e__e_b = r_e__e_f + C_e__f * r_f__f_b; % Position of the origin of the b-frame wrt e-frame org
resolved in the e-frame (m)
r_e__e_n = r_e__e_b; % The origin of the Nav frame = origin of the body frame (m)
% Generate Orientation
C_e__n = zeros(3,3,N); % Orientation of n-frame wrt e-frame
C_i__n = zeros(3,3,N); % Orientation of n-frame wrt i-frame
for i=1:N
C_e__n(:,:,i) = [ -cos(lambda_b(i))*sin(L_b(i)), -sin(lambda_b(i)) , -
cos(lambda_b(i))*cos(L_b(i));
-sin(lambda_b(i))*sin(L_b(i)), cos(lambda_b(i)) , -sin(lambda_b(i))*cos(L_b(i));
cos(L_b(i)), 0 , -sin(L_b(i))];
C_i__n(:,:,i) = C_i__e(:,:,i) * C_e__n(:,:,i);
end
% Generate Position
r_i__i_n = zeros(3,N); % Position of n-frame wrt i-frame resolved in {i}
for i=1:N
r_i__i_n(:,i) = C_i__e(:,:,i) * r_e__e_n(:,i); % r_i__i_n = r_i__i_e + C_i__e * r_e__e_n ->
Eqn 2.96
end
% Generate Velocity
v_e__e_n = zeros(3,N); % Velocity of n-frame wrt e-frame resolved in the e-
frame
for i=1:N
RN = (1 - e^2) * R0 / (1 - e^2*sin(L_b(i))^2)^(3/2); % Meridian radius of curvature
(m)
RE = R0 / sqrt(1 - e^2*sin(L_b(i))^2); % Transverse radius of curvature
(m)
v_n__e_n = [ (RN + h_b(i)) * L_b_dot(i);
% Generate Acceleration
a_e__e_n = (v_e__e_n(:,2:end) - v_e__e_n(:,1:end-1))/dt; % Acceleration (numerically) of n-frame
wrt e-frame in the e-frame
a_e__e_n = [a_e__e_n, a_e__e_n(:,end)];
a_i__i_n = zeros(3,N); % Acceleration of n-frame wrt i-frame in the i-frame
for i=1:N
a_i__i_n(:,i) = C_i__e(:,:,i)*(a_e__e_n(:,i) + 2*Ohm_i__i_e*v_e__e_n(:,i) +
Ohm_i__i_e*Ohm_i__i_e*r_e__e_n(:,i)); % Eqn 2.96
end
%--------------------------------------------------------------------------
%% Navigation to Body frame
%--------------------------------------------------------------------------
% Generate Orientation
C_i__b = zeros(3,3,N); % Orientation of b-frame wrt i-frame
C_e__b = zeros(3,3,N); % Orientation of b-frame wrt e-frame
C_n__b = zeros(3,3,N); % Orientation of b-frame wrt n-frame
switch test
case 1 % Fixed Position, No Rotation
load('data/d_t_still.mat'); % Load in IMU data
w_b__i_b = d_t_still(:,7:9)';
f_b__i_b = d_t_still(:,4:6)';
% Recall that the Navigation and body frames have the same origins
% Generate Position
r_n__n_b = [0; 0; 0]; % Position of b-frame wrt n-frame
v_n__n_b = [0; 0; 0]; % Velocity of b-frame wrt n-frame
a_n__n_b = [0; 0; 0]; % Acceleration of b-frame wrt n-frame
%**************************************************************************
%% ********* IMU measurements ******************************************
%**************************************************************************
load('calibration.mat');
switch calibration
case 1 % No calibration case
%--------------------------------------------------------------------------
%% ECEF Mechanization
%--------------------------------------------------------------------------
r_e__e_b_INS = zeros(3,N);
v_e__e_b_INS = zeros(3,N);
C_e__b_INS = zeros(3,3,N);
% % Plot the ECEF PVA Ground truth, INS derived PVA, & Error betw the two
plot_PVA_Jeff(r_e__e_n, v_e__e_n, C_e__b, r_e__e_b_INS, v_e__e_b_INS, C_e__b_INS, 'ECEF',
fidelity, N, t_sec)
12. REFERENCES
[1] Bruder, S. (n.d.). Inertial Sensors & Errors. Retrieved February 11, 2015, from
http://mercury.pr.erau.edu/~bruders/teaching/2015_spring/EE495/lectures/lecture
14_Inertial_Sensor_Errors.pdf
[2] Groves, P. (2013). Principles of GNSS, inertial, and multisensor integrated navigation
systems (Second ed.).
[3] Gulf Coast Data Concepts, LLC. (2014). Calibrating 3-Axis Accelerometers. Retrieved April
15, 2015, from http://www.gcdataconcepts.com/calibration.html
[4] VectorNav. (n.d.). Calibration - VectorNav Library. Retrieved April 15, 2015, from
http://www.vectornav.com/support/library/calibration
[5] VectorNav. (n.d.). VN-200 Rugged Specifications. Retrieved April 15, 2015, from
http://www.vectornav.com/products/vn200-rugged/specifications