Angular Rate Optimal Design for the Rotary Strapdown Inertial Navigation System
Abstract
: Due to the characteristics of high precision for a long duration, the rotary strapdown inertial navigation system (RSINS) has been widely used in submarines and surface ships. Nowadays, the core technology, the rotating scheme, has been studied by numerous researchers. It is well known that as one of the key technologies, the rotating angular rate seriously influences the effectiveness of the error modulating. In order to design the optimal rotating angular rate of the RSINS, the relationship between the rotating angular rate and the velocity error of the RSINS was analyzed in detail based on the Laplace transform and the inverse Laplace transform in this paper. The analysis results showed that the velocity error of the RSINS depends on not only the sensor error, but also the rotating angular rate. In order to minimize the velocity error, the rotating angular rate of the RSINS should match the sensor error. One optimal design method for the rotating rate of the RSINS was also proposed in this paper. Simulation and experimental results verified the validity and superiority of this optimal design method for the rotating rate of the RSINS.1. Introduction
The operation of an inertial navigation system (INS) depends on Newton' second law [1]. The inertial navigation is the process whereby the measurements of inertial sensors (gyroscopes and accelerometers) calculate the position and velocity of the vehicle. Unlike other types of navigation systems, the INS is an entirely independent navigation system, since it is not dependent on the transmission of signals from the vehicle or reception from an external source. However, the fatal flaw of the INS is that the navigation error caused by the bias of the inertial sensors increases with time. Therefore, the precision of the INS is subject to the precision of inertial sensors [2,3].
For the original INS, the inertial sensors are mounted on a stable platform, which is mechanically isolated from the rotational motion of the vehicle [4]. Due to the mechanical complexity of the platform system, a new type of INS, which is called the strapdown inertial navigation system (SINS), is replacing the traditional platform inertial navigation system. The SINS has the advantages of lower cost, smaller size and greater reliability compared with platform systems, since the inertial sensors are attached rigidly to the body of the vehicle [5].
Since the navigation error caused by the bias of the inertial sensors increases with time, researchers proposed the rotation modulation method to reduce the impact on the SINS, which is installed on the vehicle through the turntable. The rotation modulation method modulates the bias of inertial sensors into a zero-mean and periodical form to inhibit the error propagation, and then, the localization precision of the SINS will be enhanced effectively. This kind of rotary strapdown inertial navigation system (RSINS) has been applied by the U.S. Navy since the 1960s [6-8]. However, the disadvantage of the rotation modulation is that it cannot modulate the installation error and the symmetric scale factor error of the inertial sensors, but it also produces instantaneous velocity error [8-10]. As a result, the design of the rotating angular rate has became a hotspot of rotation modulation.
The RSINS accuracy influenced by the non-uniform rotation angular rate is analyzed by Dr. Che [11]. The rotating scheme design method of the non-uniform rotating angular rate is proposed in [12]. However, until now, no one has been able to figure out an effective optimal rotating angular rate design method of the RSINS in theory. Therefore, in this article, a novel rotating angular rate design discipline, which will fill the gap, was proposed. We focused on the optimal design of the rotating angular rate utilizing the Laplace transform and the inverse Laplace transform in this article, and this paper is organized as follows. In Section 2, the principle of the rotation modulation and the inertial sensor error model are introduced. The design method of the rotating angular rate is proposed in Section 3. Simulations and experiments are carried out in Section 4 and 5, respectively, to verify the correctness of the design method.
2. Principle of the Rotation Modulation and the Error Model
2.2. The Sensor Error Model of the RSINS
The inertial sensor error mainly includes the constant bias, the scale factor error and the installation error of the optical gyroscope and the constant bias of the accelerometer. In Section 2, we will focus on the relationship between the inertial sensor error and the performance of the RSINS.
2.2.1. Constant Bias of Optical Gyroscopes and Accelerometers
The modulated constant bias of the gyroscope and the accelerometer in the n frame can be described by Equations (2) and (3), respectively.
2.2.2. Scale Factor Error of Optical Gyroscopes
The equivalent bias of gyroscopes, ε′, caused by the scale factor asymmetric error of gyroscopes can be described by:
2.2.3. Installation Error of Optical Gyroscopes
The inertial sensors should be installed orthogonally in theory. However, the actually s frame is not orthogonal and cannot coincide with the b frame, as shown in Figure 2. The small-angle δij is defined as the installation error between the i axis of the s frame and the j axis of the b frame. Therefore, the installation error matrix can be described as:
The equivalent bias of gyroscopes, , caused by the installation error can be described by:
Therefore, the modulated equivalent bias of gyroscopes, ε″, in the n frame can be described by:
2.2.4. Error Model of Inertial Sensors in the RSINS
Concerning the study above, the error model of the RSINS can be described as
It can be seen from Equation (10) that the error model of the RSINS is a function that depends on not only the error of inertial sensors, but also the rotating angular rate. Therefore, the performance of the RSINS will be influenced by the rotating angular rate.
3. Optimal Design Method for the Rotating Angular Rate in the RSINS
The previous analysis shows that the error model of the RSINS bears on both the inertial sensor error and the rotating angular rate. Therefore, this section will investigate the relationship between the rotating angular rate and the RSINS performance.
3.1. The Velocity Error Equation of the RSINS
Based on the spherical Earth model, ignoring the movement of the vehicle, suppose the IMU rotates along the vertical axis at ωr; the error model of the RSINS can be described as:
As the values of mj3(j = 1, 2, …, 6) do not affect X(s), the elements of the third column are represented with ‘*’. Wi(s), the expression of Wi(t) in the frequency domain, can be expressed as:
Therefore, the velocity error of the east and north in the frequency domain can be expressed as:
3.1.1. Velocity Error Caused by the Constant Bias of Gyroscopes
The east velocity error caused by the gyroscope constant bias can be expressed in the frequency domain as:
After the inverse Laplace transform and the simplification, we can get the east velocity error caused by the gyroscope constant bias in the time domain shown as:
The amplitude of the east velocity error is expressed as:
The north velocity error caused by the gyroscope constant bias can be expressed in the frequency domain as:
After the inverse Laplace transform and simplification, one can get the north velocity error caused by the gyroscope constant bias in the time domain as:
The amplitude of the north velocity error is expressed as:
It is known that the amplitude of the velocity error caused by the gyroscope constant bias decreases with the increase of the rotating angular rate from Equations (16) and (19). Figure 3 shows the simulation results.
3.1.2. Velocity Error Caused by the Constant Bias of Accelerometers
The east velocity error caused by the accelerometer constant bias can be expressed in the frequency domain as:
After the inverse Laplace transform and simplification, we get the east velocity error caused by the accelerometer constant bias in the time domain and shown as:
The amplitude of the east velocity error is expressed as:
The north velocity error caused by the accelerometer constant bias can be expressed in the frequency domain as:
After the inverse Laplace transform and simplifying Equation (23), we get the east velocity error caused by the accelerometer constant bias in the time domain as:
The amplitude of the east velocity error is expressed as:
The conclusion is obtained from Equations (22) and (25) that the amplitude of the velocity error caused by the accelerometer constant bias decreases with the increase of the rotating angular rate. Figure 4 shows the simulation results.
3.1.3. Velocity Error Caused by the Scale Factor Error
The east velocity error caused by the scale factor error can be expressed in the frequency domain as:
After the inverse Laplace transform and simplifying Equation (26), we get the east velocity error caused by the scale factor error in the time domain as:
The amplitude of the east velocity error is expressed as:
The north velocity error caused by the scale factor error can be expressed in the frequency domain as:
After the inverse Laplace transform and the simplification, we get the east velocity error caused by the scale factor error in the time domain as:
The amplitude of the east velocity error is expressed as:
From Equations (28) and (31), we can draw a conclusion that the amplitude of the velocity error caused by the accelerometer constant bias increases with the increase of the rotating angular rate. Additionally, we plot the relationship between the amplitude of the velocity error, the scale factor error and the rotating angular rate as Figure 5.
3.1.4. Velocity Error Caused by the Installation Error
The east velocity error caused by the installation error can be expressed in the frequency domain as:
After the inverse Laplace transform and simplification, we get the east velocity error caused by the installation error in the time domain as:
The amplitude of the east velocity error is expressed as:
The north velocity error caused by the installation error can be expressed in the frequency domain as:
After the inverse Laplace transform and simplification, we get the north velocity error caused by the installation error in the time domain as:
The amplitude of the north velocity error is expressed as:
From Equations (34) and (37), we can draw a conclusion that the amplitude of the velocity error caused by the installation error increase with the increase of rotating angular rate. Additionally, we plot the relationship between the amplitude of the velocity error, the installation error and the rotating angular rate as Figure 6.
3.2. Optimal Design Method for the Angular Rate
Section 3.1 is focused on the relationship between the velocity error, three different kinds of inertial sensors errors and the rotating angular rate. In this part, we will propose the optimal design method of the rotating angular rate.
When the RSINS rotates at a constant speed, the amplitude of the velocity error can be expressed as:
From the Equation (38), it is known that the amplitude of the velocity error can be expressed as a function of the inertial sensor error and the rotating angular rate. Therefore, for the purpose of ensuring the minimum of the velocity error amplitude, the rotating angular rate should match the error of the inertial sensors. In order to verify and determine this matching relationship, we will design three groups of inertial sensor performances and calculate the optimal rotating angular rate of each group with MATLAB. Taking “MARINS”, a high-precision INS manufactured by IXBlue, as an example, its positioning accuracy is 1 nm/24 h. It can be inferred that the constant bias and the scale factor error of its gyroscopes are lower than 0.01 °/h and 1 × 10-6 (°/h)-1, respectively. On the other hand, considering the real INS, the constant bias accelerometer is lower than 9.8 × 10-4 m/s2, and the installation error of gyroscopes is lower than 1 × 10-9 °/h. Therefore, on the basis of the above, the simulation parameters are set as Tables 1-3, respectively.
Figure 7 depicts the relationship between the amplitude of the velocity error and the rotating angular rate by MATLAB. The value of the horizontal axis corresponding to the minimum of the curve is the optimal rotating angular rate. The optimal rotating angular rates of these three groups are summarized in Table 4.
4. Numerical Simulations
The optimal design method of the rotating angular rate is proposed in Section 3. The theoretical optimal rotating angular rates corresponding to three different groups of inertial sensor errors are obtained in terms of this method. In order to verify the correctness of the former conclusions, simulations are carried out in this section. The rotating scheme is proposed as shown in Figure 8. The turntable rotates the IMU back and forth along the azimuth axis through four orthogonal positions. The dwell time in each position is 45 s [25].
The performances of inertial sensors are described in Tables 1, 2, and 3. The rotating angular rates are designed as 7.2 °/s, 21.6 °/s, 45 °/s and 64.8 °/s; as 21.6 °/s, 64.8 °/s and 7.2 °/s are the optimal rotating rate of Groups 1-3, respectively, and 45 °/s is chosen for comparison.
Figures 9, 10, and 11 show the simulation results of the position error of different groups. The simulation duration is 72 h.
Tables 5, 6, and 7 summarize the simulation results.
It can be seen from Figure 9 and Table 5 that the position error of Group 1 with a rotating angular rate of 21.6 °/s is lower than the other rotating angular rates. From Figure 10 and Table 6, it can be seen that the position error of Group 2 with a rotating angular rate of 64.8 °/s is lower than the other rotating angular rates. From Figure 10 and Table 6, we can see that the position error of Group 3 with a rotating angular rate of 7.2 °/s is lower than the other rotating angular rates. The simulation results are in accordance with the conclusions of Section 3.
5. Experimental Study
In order to verify the effectiveness of the method, experiments were done in Songhuajiang River in Harbin, as shown in Figure 12. Experimental equipment, as shown in Figure 13, included SINS, single-axis turn-table, GPS, computers and a UPS. The SINS is manufactured by Harbin Engineering University, and the main parameters are shown in Tables 8 and 9. The single-axis turn-table is manufactured by Beijing Precision Engineering Institute for Aircraft Industry, and the main parameters are shown in Table 10.
5.1. Experimental Scheme
With the optimal design method proposed in this paper, the optimal angular rate for the experimental system is calculated to be 7 °/s. Therefore, three angular rates, 2 °/s, 7 °/s and 20 °/s, are used in the experiments for comparison. The experimental duration is 72 h, and the rotating scheme is the same as that in Section 4.1.
The rotating angular rate is not constant in a real system, since the IMU needs to reverse the rotating direction. The positioning accuracy of RSINS is influenced by the IMU turned angle in the variable angular rate process [26]. Additionally, the analysis results show that the error will be minimum in the process of the varied angle rate when the IMU's turned angle achieves 0.2π. In order to eliminate the effects of the variable angular rate, the angular accelerations are set as 0.1 °/s2, 0.7 °/s2 and 5.6 °/s2, respectively, in the experiment.
5.2. Experimental Results and Analysis
Figures 14-16 show the position error of three experiments.
From the theoretical analysis of Section 3, it is known that the rotation modulation method can only reduce the amplitude of the oscillation error and the slope of the ramp error, but not eliminate them. Therefore, it can be seen from Figures 14-16 that the resulting position error comprises a ramp error with superimposed Schuler oscillation and Earth rotation oscillation, and the oscillation periods are 84.4 min and 24 h. From Table 11, it can be seen obviously that the position error of Experiment II is much less than the other two. The experimental results are consistent with the theoretical analysis of Section 3.
6. Conclusions and Future Work
This paper presented a rotating angular rate optimal design method of the RSINS. Firstly, the RSINS and the principle of the rotation modulation were introduced, and the inertial sensor errors were modeled. Secondly, the relation between the velocity error and the angular rate was worked out using the Laplace transform and the inverse Laplace transform. The optimal rotating angular rate method was also proposed based on the relationship above. Thirdly, simulations were conducted, and the results confirmed that the optimal rotating angular rate could be computed correctly with this method. Navigation experiments were done, and the results of the positioning error confirmed the effectiveness and correctness of the theoretical analyze. However, the experimental time was just 72 h, because of the limitations of experimental conditions. As a result, we plan to do more further experiments, which will last a longer time, if the experimental conditions permit, in the future. On the other hand, the results of the simulations were superior to that of the experiments. The reason may be that an error of the initial alignment, which is ignored, in the simulations may occur. The initial alignment error is not the main factor of the rotating angular rate optimal design method from the analysis of simulations and experimental results. Even so, we will model the initial alignment error and focus on its impact on the RSINS in the future.
Acknowledgments
The authors would like to acknowledge Jinjun Shan from Department of Earth and Space Science and Engineering of York University and Chongyang Lv from College of Automation of Harbin Engineering University and other reviewers for their helpful comments. This work is also supported by the Fundamental Research Funds for the Central Universities (HEUCFL1411002) and the National Natural Science Foundation of China (51379047).
Author Contributions
Fei Yu provided useful suggestions for this manuscript. Qian Sun designed the experiments and drafted the manuscript. Qian Sun is also the corresponding author who supervised this work and revised the manuscript.
Conflicts of Interest
The authors declare no conflict of interest.
References
- Ishibashi, S.; Tsukioka, S.; Yoshida, H.; Hyakudome, T.; Sawa, T.; Tahara, J.; Aoki, T.; Ishikawa, A. Accuracy Improvement of an Inertial Navigation System Brought about by the Rotational Motion. Proceedings of OCEANS 2007-Europe, Aberdeen, UK, 18–21 June 2007; pp. 1–5.
- Levinson, E.; Ter Horst, J.; Willcocks, M. The Next Generation Marine Inertial Navigator is Here Now. Proceedings of the IEEE Position Location and Navigation Symposium, Las Vegas, NV, USA, 11–15 April 1994; pp. 121–127.
- Tucker, T.; Levinson, E. The AN/WSN-7B Marine Gyrocompass/Navigator. Proceedings of the 2000 National Technical Meeting of the Institute of Navigation, Anaheim, CA, USA, 26–28 January 2000; pp. 348–357.
- Titterton, D.; Weston, J. Strapdown Inertial Navigation Technology, 2nd ed; The Institution of Electronical Engineers: Reston, VA, USA, 2004. [Google Scholar]
- Gao, W.; Zhang, Y.; Wang, J. A Strapdown Interial Navigation System/Beidou/Doppler Velocity Log Integrated Navigation Algorithm Based on a Cubature Kalman Filter. Sensors 2014, 14, 1511–1527. [Google Scholar]
- Lahham, J.; Brazell, J. Acoustic Noise Reduction in the MK 49 Ship's Inertial Navigation System (SINS). Proceedings of the Position Location and Navigation Symposium, 1992. Record. 500 Years After Columbus-Navigation Challenges of Tomorrow. IEEE PLANS'92., IEEE, Monterey, CA, USA, 23–27 March 1992; pp. 32–39.
- Levinson, E.; Majure, R. Accuracy Enhancement Techniques Applied to the Marine Ring Laser Inertial Navigator (MARLIN). Navigation 1987, 34, 64–86. [Google Scholar]
- Gao, Z.Y. Initial Navigation System Technology; Tsinghua University Press: Beijing, China, 2012; p. p. 290. [Google Scholar]
- Heckman, D.W.; Baretela, L. Improved Affordability of High Precision Submarine Inertial Navigation by Insertion of Rapidly Developing Fiber Optic Gyro Technology. Proceedings of the Position Location and Navigation Symposium, IEEE 2000, San Diego, CA, USA, 13–16 March 2000; pp. 404–410.
- Ben, Y.Y.; Chai, Y.L.; Gao, W.; Sun, F. Analysis of Error for a Rotating Strap-Down Inertial Navigation System with Fibro Gyro. J. Mar. Sci. Appl. 2010, 9, 419–424. [Google Scholar]
- Che, L.; Sun, W.; Xu, A. Influence of IMU Rotation Angular Rate on Navigation Accuracy of Rotary SINS. Chin. J. Sci. Instrum. 2012, 33, 1041–1047. [Google Scholar]
- Sun, F.; Wang, Q.; Qi, Z. Effect of Angle Variable Motion on Rotation Strapdown Inertial Navigation Systems. J. Huazhong. Univers. Sci. Technol. 2013, 41, 31–35. [Google Scholar]
- Adams, G.; Gokhale, M. Fiber Optic Gyro Based Precision Navigation for Submarines. Proceedings of the AIAA Guidence, Navigation and Control Conference, Denver, CO, USA, 14–17 August 2000.
- Ben, Y.; Sun, F.; Gao, W.; Yu, F. Generalized Method for Improved Coning Algorithms using Angular Rate. Aerosp. Electron. Syst., IEEE Trans. 2009, 45, 1565–1572. [Google Scholar]
- Zha, F.; Xu, J.N.; Hu, B.Q.; Qin, F.J. Error Analysis for SINS with Different IMU Rotation Scheme. Proceedings of the Informatics in Control, Automation and Robotics (CAR), 2010 2nd International Asia Conference on, Wuhan, China, 6–7 March 2010; pp. 422–425.
- Zha, F.; Hu, B.R.; Qin, F.J.; Luo, Y.B. A Rotating Inertial Navigation System with the Rotating Axis Error Compensation Consisting of Fiber Optic Gyros. Optoelectron. Lett. 2012, 8, 146–149. [Google Scholar]
- Liu, F.; Wang, W.; Wang, L.; Feng, P. Error Analyses and Calibration Methods with Accelerometers for Optical Angle Encoders in Rotational Inertial Navigation Systems. Appl. Opt. 2013, 52, 7724–7731. [Google Scholar]
- Yu, H.; Wu, W.; Wu, M.; Feng, G.; Hao, M. Systematic Angle Random Walk Estimation of the Constant Rate Biased Ring Laser Gyro. Sensors 2013, 13, 2750–2762. [Google Scholar]
- Ishibashi, S. The Improvement of the Prescision of an Inertial Navigation System for AUV based on the Neural Network. Proceedings of the OCEANS 2006-Asia Pacific, Singapore, 16–19 May 2007; pp. 1–6.
- Sun, G.; Wang, M.; Huang, L.; Shen, L. Generating Multi-Scroll Chaotic Attractors via Switched Fractional Systems. Circuits. Syst. Signal. Process. 2011, 30, 1183–1195. [Google Scholar]
- Sun, F.; Lan, H.; Yu, C.; El-Sheimy, N.; Zhou, G.; Cao, T.; Liu, H. A Robust Self-Alignment Method for Ship's Strapdown INS under Mooring Conditions. Sensors 2013, 13, 8103–8139. [Google Scholar]
- Sun, G.; Ge, D.; Wang, S. Induced L2 Norm Control for LPV System with Specified Class of Disturbance Inputs. J. Frankl. Inst. 2013, 350, 331–346. [Google Scholar]
- Wang, B.; Xiao, X.; Xia, Y.; Fu, M. Unscented Particle Filtering for Estimation of Shipboard Deformation Based on Inertial Measurement Units. Sensors 2013, 13, 15656–15672. [Google Scholar]
- Sun, G.; Wang, M.; Wu, L. Unexpected Results of Extended Fractional Kalman Filter for Parameter Identification in Fractional Order Chaotic sSystems. Int. J. Innov. Comput. Inf. Control. 2011, 7, 5341–5352. [Google Scholar]
- Sun, W.; Gao, Y. Fiber-Based Rotary Strapdown Inertial Navigation System. Opt. Eng. 2013, 52, 076106–076106. [Google Scholar]
- Yu, F.; Sun, Q.; Zhang, Y.; Zu, Y. The Optimization Design of the Angular Rate and Acceleration Based on the Rotary SINS. Proceedings of the Control Conference (CCC), 2013 32nd Chinese, Xi'an, China, 26–28 July 2013; pp. 4969–4973.
Sensor Error | Parameter Value |
---|---|
Constant bias of gyroscope | 0.01 (°/h) |
Constant bias of accelerometer | 9.8 × 10-4 (m/s2) |
Scale factor error of gyroscope | 1 × 10-6 (°/h)-1 |
Installation error of gyroscope | 1 × 10-9 (°/h) |
Sensor Error | Parameter Value |
---|---|
Constant bias of gyroscope | 0.05 (°/h) |
Constant bias of accelerometer | 4.9 × 10-3 (m/s2) |
Scale factor error of gyroscope | 0.2 × 10-6 (°/h)-1 |
Installation error of gyroscope | 5 × 10-9 (°/h) |
Sensor Error | Parameter Value |
---|---|
Constant bias of gyroscope | 0.002 (°/h) |
Constant bias of accelerometer | 1.96 × 10-4 (m/s2) |
Scale factor error of gyroscope | 5 × 10-6 (°/h)-1 |
Installation error of gyroscope | 2 × 10-10 (°/h) |
Group | Optimal rotating angular rate |
---|---|
1 | 21.6°/s |
2 | 64.8°/s |
3 | 7.2°/s |
Rotating angular rate (°/s) | 7.2 | 21.6 | 45 | 64.8 |
Position error (nmile/72h) | 1.2 | 0.6 | 1.5 | 1.3 |
Rotating angular rate (°/s) | 7.2 | 21.6 | 45 | 64.8 |
Position error (nmile/72h) | 5.0 | 0.9 | 1.0 | 0.6 |
Rotating angular rate (°/s) | 7.2 | 21.6 | 45 | 64.8 |
Position error (nmile/72h) | 2.5 | 3.0 | 5.0 | 4.2 |
Performance | Parameters |
---|---|
Dynamic range | ±100°/s |
Bias stability | ≤ 0.003 °/h |
Random walk | |
Scale factor error | ≤ 5 ppm |
Performance | Parameters |
---|---|
Dynamic range | ±4g |
Bias stability | ≤ 1 × 10-5 |
Performance | Parameters |
---|---|
Diameter | 450 m |
Carrying capacity | weight 50 kg |
Rotating accuracy | ±2″ |
Rotating range | continues and infinite |
Location accuracy | ±3″ |
Location definition | 0.0001° |
Speed range | 0.005 - 200 °/s |
Speed accuracy | 5 × 10-5 (360°average) |
Speed accuracy | 5 × 10-4 (10°average) |
Speed accuracy | 1 × 10-2 (l°average) |
Rotating angular rate (°/s) | 2 | 7 | 20 | |
Position error (nmile/72h) | 14.7 | 6.4 | 19.6 |
© 2014 by the authors; licensee MDPI, Basel, Switzerland. This article is an open access article distributed under the terms and conditions of the Creative Commons Attribution license ( http://creativecommons.org/licenses/by/3.0/).
Share and Cite
Yu, F.; Sun, Q. Angular Rate Optimal Design for the Rotary Strapdown Inertial Navigation System. Sensors 2014, 14, 7156-7180. https://doi.org/10.3390/s140407156
Yu F, Sun Q. Angular Rate Optimal Design for the Rotary Strapdown Inertial Navigation System. Sensors. 2014; 14(4):7156-7180. https://doi.org/10.3390/s140407156
Chicago/Turabian StyleYu, Fei, and Qian Sun. 2014. "Angular Rate Optimal Design for the Rotary Strapdown Inertial Navigation System" Sensors 14, no. 4: 7156-7180. https://doi.org/10.3390/s140407156
APA StyleYu, F., & Sun, Q. (2014). Angular Rate Optimal Design for the Rotary Strapdown Inertial Navigation System. Sensors, 14(4), 7156-7180. https://doi.org/10.3390/s140407156