Abstract
This paper presents an enhanced algorithm for inertial gyrocompassing using strapdown sensors, which performs faster than the other available ones. The proposed algorithm is based on differential errors in an inertial navigation system and requires only the output of the inertial measurement unit while extracting and compensating for the inertial sensor errors. After eliminating the error of the inertial sensors, which is accomplished swiftly, the coarse alignment algorithm performs with error-compensated sensors, and the true north is extracted accurately. The number of non-observable parameters of the algorithm is equal to that of the fine alignment algorithm; therefore, its accuracy is the same as that of a well-tuned fine alignment. Numerical simulations and lab experiments demonstrate that the proposed method performs heading estimation in the time required to perform the coarse alignment, which is faster than the existing fine alignment algorithms.
Introduction
Flying vehicles usually use ‘initial alignment’ as the first step of navigation1; this means that they correct their directions at the beginning of a flight. Alignment means the relationship between the Body (B) and the Navigation (N) coordinate system2. The word ‘leveling’ refers to calculating the angles of roll and pitch, which are the vehicle deviation from the horizon. The meaning of ‘gyrocompassing’ is finding the direction of the geographic north.
Inaccurate initial alignment causes imprecise navigation. Thus, achieving a high degree of alignment over a short time is necessary. If the initial alignment is accomplished in a stationary mode, the level angles (ϕ and θ) extraction is performed by the accelerometers; Thus, the trouble of the alignment procedure will be gyrocompassing (north-finding). Usually, there is a limited time to calculate the heading angle, however most gyrocompassing algorithms are time-consuming. Therefore, it is necessary to access a gyrocompassing algorithm with a short time and high accuracy.
Various alignment techniques can be divided into inertial, non-inertial, and hybrid methods. The inertial methods use inertial sensors to generate the transformation matrix from the body to the navigation coordinate system and work based on gravity and Earth rate measurements. Non-inertial methods are based on other physical properties; For example, the magnetic compass utilizes the Earth’s magnetic field and finds the magnetic north instead of the true north. Hybrid methods integrate the information from the inertial and non-inertial methods and have the advantage of these two categories simultaneously.
In inertial alignment, the goal is to determine the level and heading angles by strapdown inertial sensors, including three gyros and three accelerometers, and use an algorithm implemented in the processor. The alignment algorithm estimates the navigation system errors (including inertial sensor, numerical computation, and initial condition errors) and corrects the navigation solution.
In general, it can be stated that inertial alignment is categorized as ‘stationary alignment’ and ‘in-motion alignment’. Stationary alignment (the subject of this study) is completed in two successive phases, and accuracy is improved at each phase. These steps are ‘Coarse alignment’3 and ‘Fine alignment’4. The first phase (coarse alignment) provides a rough estimate of initial attitudes. In the second phase (fine alignment), a filter (regularly Kaman filters/KF) is used to refine the alignment and estimate inertial sensor errors before flight5. In this paper we have proposed a new algorithm which combines the advantages of the two conventional alignment algorithms (i.e., coarse and fine). The new algorithm is as fast as the coarse alignment and as accurate as the fine alignment. In other words, the new alignment algorithm is fast and accurate.
Reference6 proposes an algorithm for the stationary alignment of rocket navigation systems. A filter is utilized to decrease the noise in the inertial measurement. Reference7 proposes an approach based on the expansion of the measurements, where the sensors’ biases are estimated more quickly and accurately. Despite the effectiveness of the proposed approach, it could not improve the convergence rate of the platform misalignments; since it depends directly on the unobservable uncompensated biases, which the Kalman filter cannot estimate.
In Ref.8, a new method is proposed for the initial alignment. A Kalman Filter is applied for the fine alignment, while the horizontal acceleration of gravity is also taken into the measurement equations. This approach enhances the tracking ability of the KF for the attitude angle’s change. In Ref.9, a multi-rate self-alignment algorithm enhances the KF capability in estimating biases. In Ref.10, the design principle of a dual-axis rotating SINS is proposed to improve the slow convergence rate and the low accuracy during the initial alignment and self-calibration.
Reference11 presents a SINS error analysis of coarse alignment formulations. The proposed formulation does not imply normality and orthogonality errors. In Ref.12 general expression for the SINS coarse alignment errors is derived, which is valid regardless of the inertial measurement unit (IMU) orientation.
The fine alignment problem has been studied in many references, such as13,14,15,16,17,18,19. Reference20 provides a quick method for accurate alignment; in this method, the roll and pitch rates are used to estimate the heading angle. In Ref.21, the navigation block is triggered with a particular mechanical motion, increasing precision and reducing fine alignment time. In Ref.22, the ‘multi-position’ technique is described in fine alignment; In the proposed method, the attitude of the IMU carrier is changed, and consequently, the observability of the inertial navigation system is improved. This technique reduces the alignment error.
A free IMU can perform fine alignment algorithms in a stationary mode without external aids. ‘Self-alignment’ is a process that is independent of external aiding navigation systems23. The advantage of this method is the independence of the INS from any external data; the disadvantages are as follows: some parameters become non-observable, sensitivity to noise of the inertial sensors is high, and the time required for the convergence of the algorithm is about 5–10 min.
As mentioned, the coarse alignment algorithm is fast and imprecise, while the fine alignment algorithm is slow and accurate. The algorithm presented in this paper is fast as the coarse alignment and accurate as the fine alignment. In other words, the proposed algorithm has the advantages of both traditional algorithms.
The organization of this paper is as follows: in “Rotation of small angles”, the relation between the small rotation angles and the Euler angles is derived. In “The proposed algorithm formulation”, the mathematical formulation of the new algorithm is presented. In “Methods”, the proposed algorithm is simulated and verified numerically, and lastly, the conclusion is made in “Simulation and experiments”.
Rotation of small angles
The following relation holds between two frames when the rotation angles are small24:
In the above equation, \({\mathbf{R}}^{{{\hat{\text{N}}\text{N}}}}\) is the rotation tensor of the estimated navigation frame (\({\hat{\text{N}}}\)) relative to the true navigation frame (N); E is the identity tensor and \({\upvarepsilon }{\mathbf{R}}^{{{\hat{\text{N}}\text{N}}}}\) is the skew-symmetric form of the perturbation tensor (\({\upvarepsilon }{\mathbf{r}}^{{{\hat{\text{N}}\text{N}}}}\)), which is modeled as follows:
where \({\upvarepsilon }\varphi\), \({\upvarepsilon }\theta\) and \({\upvarepsilon }\psi\) represent three small rotation angles. According to Ref.24, \([{\mathbf{R}}^{{{\hat{\text{N}}\text{N}}}} ]^{{\text{N}}} = [\overline{{\text{T}}} ]^{{{\hat{\text{N}}\text{N}}}}\) where \([{\text{T}}]^{{{\hat{\text{N}}\text{N}}}}\) is the transformation matrix of the N frame to the \({\hat{\text{N}}}\) frame; Utilizing this property, Eq. (1) can be expressed in the navigation frame:
Transposing Eq. (3) results in:
Now suppose that \([{\text{T}}]^{{{\text{BN}}}} = f(\overset{\lower0.5em\hbox{$\smash{\scriptscriptstyle\frown}$}}{\psi } ,\overset{\lower0.5em\hbox{$\smash{\scriptscriptstyle\frown}$}}{\theta } ,\overset{\lower0.5em\hbox{$\smash{\scriptscriptstyle\frown}$}}{\varphi } )\) and \([{\text{T}}]^{{{{\text{B}\hat{\text{N}}}}}} = f(\hat{\psi },\hat{\theta },\hat{\varphi })\); where \(\overset{\lower0.5em\hbox{$\smash{\scriptscriptstyle\frown}$}}{\psi } ,\,\overset{\lower0.5em\hbox{$\smash{\scriptscriptstyle\frown}$}}{\theta } ,\,\overset{\lower0.5em\hbox{$\smash{\scriptscriptstyle\frown}$}}{\varphi }\) are true and \(\hat{\psi },\,\hat{\theta },\,\hat{\varphi }\) are estimated Euler angles and ‘f’ is a matrix function that transforms navigation to body frame and is defined as follows24:
Now consider the following definitions:
where \(\Delta\) defines the difference between the true and estimated value of a parameter. Utilizing Eq. (6), Eq. (4) can be written as follows:
Expanding the above equation, \([{\upvarepsilon }{\mathbf{R}}^{{{\hat{\text{N}}\text{N}}}} ]^{{\text{N}}}\) can be found as:
The above equation can be written as Eqs. (9) or (10):
According to Eq. (6), Eq. (10) is rewritten as follows:
The above equation demonstrates the relationship between the small rotation angles and the Euler angles. The expanded form of Eq. (11) is also as follows:
In the next section, the above equation is used to extract the error of IMU sensors in a stand-alone mode.
The proposed algorithm formulation
Consider the set of velocity and attitude navigation error equations. These equations are given in Ref.25 as follows:
where \(\lambda\), \(\ell\), \(v_{{\text{n}}}\), \(v_{{\text{e}}}\) and \(v_{{\text{d}}}\) denote latitude, longitude, and north, east, and down terrestrial velocities, respectively. \({\text{R}}_{{\text{e}}}\) is the radius of the Earth and \({\upvarepsilon }\) is the perturbation operator. The attitude error between the true and computed navigation frames is defined by \({\upvarepsilon }\phi\), \({\upvarepsilon }\theta\) and \({\upvarepsilon }\psi\). Also, \({\upomega }^{{{\text{EI}}}}\) is the Earth’s angular velocity and \({\upomega }_{{\text{n}}}\), \({\upomega }_{{\text{d}}}\), \(f_{{\text{n}}}\), \(f_{{\text{e}}}\) and \(f_{{\text{d}}}\) are defined as follows:
Applying stationary conditions (\([{\mathbf{v}}_{{\text{B}}}^{{\text{E}}} ]^{{\text{N}}} = [\begin{array}{*{20}c} 0 & 0 & 0 \\ \end{array} ]^{{\text{T}}}\) and \([{\mathbf{f}}]^{{\text{N}}} = [ - {\mathbf{g}}]^{{\text{N}}} = [\begin{array}{*{20}c} 0 & 0 & { - {\text{g}}} \\ \end{array} ]^{{\text{T}}}\)) to Eqs. (13)–(14), assuming spherical Earth, neglecting position parameters (\({\upvarepsilon }\lambda\) and \({\upvarepsilon }h\)), ignoring the gravity model error (\({\delta g} = {0}\)), navigation error equations are simplified as follows:
IMU calibration
Calibration of inertial sensors is an important procedure which affects the performance of navigation products. Due to stochastic nature of sensor’s noises, factory calibration is not a perfect process. Performing in-motion or in-run calibration may increase the IMU accuracy. In this section, a new method for IMU calibration is proposed and its application in initial alignment is discussed.
The problem of IMU calibration is investigated by many researchers. Reference26 explores the present state and upcoming directions of MEMS inertial sensor calibration technology. It discusses the existing advancements in this field while shedding light on potential future trends. The authors analyze the significance of accurate calibration for MEMS sensors and highlight the challenges involved. Reference27 presents a systematic method for calibrating inertial sensors on gravity recovery satellites. The authors introduce a comprehensive approach for achieving accurate calibration, emphasizing its importance for gravity recovery missions. The study outlines the calibration process and its benefits. This work contributes to the enhancement of satellite-based gravity recovery systems through robust inertial sensor calibration techniques.
Reference28 introduces a novel self-calibration method for inertial measurement units (IMUs) utilizing distributed inertial sensors. The authors propose an innovative approach that leverages multiple sensors to calibrate IMUs autonomously. This method enhances the accuracy and reliability of IMU measurements by exploiting distributed information. The study outlines the self-calibration process and its benefits, highlighting its potential to improve IMU performance in various applications.
Reference29 focuses on the extrinsic calibration of visual and inertial sensors for autonomous vehicles. The authors present a method for accurately calibrating the relative positions and orientations of both types of sensors to facilitate robust perception and navigation. The study emphasizes the importance of precise extrinsic calibration in enhancing the perception capabilities of autonomous vehicles. Reference30 presents a self-calibration method for arrays of inertial sensors. The authors propose an innovative approach that enables the automatic calibration of multiple inertial sensors within an array. This method aims to enhance the accuracy and reliability of sensor measurements by leveraging inter-sensor correlations and spatial relationships.
Accelerometers calibration
Consider the velocity error in Eq. (17) and assume that \({\upvarepsilon }\theta = {\upvarepsilon }\phi = 0\), the following simplified equations are obtained:
Integrating the above equations in the time domain leads to:
The above equation is expanded as follows:
Assuming \({\upvarepsilon }v_{{\text{n}}} (0) = {\upvarepsilon }v_{{\text{e}}} (0) = {\upvarepsilon }v_{{\text{d}}} (0) = 0\), The above equation is simplified as follows:
Based on the definition of the \({\upvarepsilon }\) operator (Appendix A) and that the true velocity is zero in stationary mode, \({\upvarepsilon }v_{i} \,\,(i = {\text{n,}}\,{\text{e,}}\,{\text{d)}}\) will be simplified as:
Based on the above relation, Eq. (21) is rewritten as follows:
According to the above equation, the projection of accelerometers error in the navigation coordinate is obtained; these errors can be compensated, and thus the IMU accuracy is improved.
Gyros calibration
Consider the attitude error terms in Eq. (17) and integrating them over time leads to:
Equation (24) is rewritten as follows:
Now consider the following assumptions which come from the stationary condition:
Replacing Eqs. (12) and (28) into Eq. (25) leads to:
Replacing Eqs. (12) and (28) into Eq. (26) leads to:
Replacing Eqs. (12) and (28) into Eq. (27) leads to:
According to Eqs. (29)–(31), the projection of gyros error in the navigation coordinate are obtained; these errors can be compensated, and thus the IMU accuracy is improved. In the next section, the extracted equations are simulated and verified.
Methods
The objective of this section is to provide a detailed explanation of a novel algorithm that aligns SINS systems fast and precisely. The main innovation of this algorithm lies in its use of analytical relations to identify bias errors of gyroscopes and then eliminate them from IMU outputs. Unlike traditional initial alignment algorithms that involve a laborious fine alignment phase, the proposed approach can estimate initial Euler angles by substituting the fine alignment phase with a conventional coarse alignment process. This results in a substantial reduction in the time required to achieve a high level of accuracy. In other words, the proposed algorithm gains the fast computation time of inaccurate conventional coarse alignment phase and accuracy of traditional time-consuming fine alignment techniques at the same time. Figure 1 illustrates a general view of the suggested alignment algorithm. It should be mentioned that the proposed algorithm is operational in the stationary alignment condition.
This algorithm consists of three stages, with the first and third stages being single-shot processes, while the second stage is an iterative process that has a maximum iteration time of Tf. The first stage involves a conventional coarse alignment algorithm while the second stage is the primary contribution of this paper and calculates bias errors in accelerometers and gyroscopes using analytical relations derived in the previous section. Once the second stage reaches its maximum running time condition, the third stage begins by subtracting calculated biases from gyros and accelerometers output and then running a conventional coarse alignment, similar to the first stage. The proposed alignment requires a time period which equals the time required by the coarse alignment and achieves an accuracy which is given by the fine alignment. The algorithm utilizes analytical explicit formulas and there is no tuning procedure as in the fine alignment.
In the proposed algorithm, at first, the average value of the IMU’s outputs are computed. This averaging is done to remove the noise effects and causes six numbers (three for accelerometers and three for gyros). The following procedure is then performed:
-
1.
Coarse alignment is executed (by the six numbers from the averaged IMU’s outputs).
-
2.
Differential calibration is done (by the six numbers from the averaged IMU’s outputs and three numbers from the coarse alignment output as the initial condition for roll, pitch and yaw).
-
3.
Another coarse alignment is performed (using the six numbers from the averaged IMU’s outputs and six numbers from the differential calibration output as the biases of accelerometers and gyros).
In above procedure, calibration of inertial sensors (step 2) is performed to remove biases from the six averaged numbers; The averaged numbers are used in steps 1, 2 and 3. In steps 1 and 2, the averaged numbers are contaminated to biases. In step 3, biases are removed from the averaged numbers.
Simulation and experiments
In this section, the relations extracted in the previous section are simulated and verified. The error model of accelerometers and gyroscopes, including misalignment error, scale factor, bias, and noise are assumed as the following:
To verify Eqs. (23), (29)–(31), various scenarios have been created according to Tables 1, 2 and 3. In Table 1, 50 different conditions for the inertial block are generated randomly (including latitude, longitude, altitude, and Euler angles). The calibration error coefficient for accelerometers and gyros are generated in Tables 2 and 3, respectively. Based on Tables 1, 2 and 3, 50 different scenarios are produced.
In Fig. 2, the results of the proposed algorithm are compared with the ‘coarse’ and ‘fine’ alignment methods. For this purpose, a coarse alignment is run at first. Then, the proposed algorithm is run, and the IMU error is compensated. Lastly, another coarse alignment is run by the error-compensated IMU. Results show that the proposed algorithm has achieved fine alignment accuracy in a limited time. In Fig. 3, the values of the accelerometer errors calculated by the proposed algorithm are shown. It is observed that the accelerometer errors are calculated accurately. In Fig. 4, the error values of gyros are shown. It is observed that the proposed algorithm cannot estimate the gyroscope error of the east channel, but in the north and down channels, the errors of the gyros are estimated accurately. It should be mentioned that according to Ref.31, east gyro error is not observable and thus not estimable.
In the subsequent tests, the FOG100 gyrocompass data produced by GEM Elettronica, Italy, was utilized to validate the performance of the proposed alignment technique in real conditions. This system consists of three optical fiber gyroscopes with an accuracy of 0.02 deg/h and three quartz accelerometers with an accuracy of 50 µg. The data sampling frequency was 100 Hz. maximum iteration time, Tf, was set by try and error to Tf = 0.05 s. The device was placed on a rate table, and stationary outputs were recorded. This procedure was repeated ten times, and in each trial, five points were selected randomly (fifty points in total). The table was also used to calculate the bias of the sensors by subtracting the measured values from the nominal values.
Figure 5 indicates that the proposed alignment error in gyrocompassing is very similar to the fine alignment approach. According to Appendix B, the accuracy of the proposed algorithm is the same as the fine alignment algorithm. In this figure, the errors represent the difference between the table orientation and the alignment techniques' output. Figure 6 depicts the bias of the accelerometers in the navigation frame, as well as their estimates by the proposed alignment method. According to Ref.31, the bias of the vertical accelerometer is observable; therefore, this bias is precisely calculated. The bias of the gyroscopes in the navigation frame is seen in Fig. 7. The north and vertical gyros biases are observable and thus they are accurately determined.
Conclusion
This paper proposes a novel algorithm for inertial gyrocompassing in the stationary stand-alone mode. The proposed algorithm only uses an IMU to solve the initial alignment problem quickly, accurately, and reasonably. The new algorithm is fast as the ‘coarse alignment’ and accurate as the ‘fine alignment’ algorithms. For this purpose, the mathematical relation between the ‘small rotation angles’ and the ‘navigation error equations’ was extracted and used to calculate the error of IMU sensors. These errors can be compensated, and consequently, the accuracy of the IMU is improved; This, in turn, causes the initial alignment procedure to be performed more accurately. Simulations and experiments show that the proposed algorithm can achieve the accuracy of fine alignment in a short time (the same time as needed by the coarse alignment). Therefore, the proposed algorithm is superior to the two standard initial alignment algorithms (coarse and fine alignment).
Data availability
The datasets used and/or analyzed during the current study available from the corresponding author on reasonable request.
Abbreviations
- \({\text{B}}\) :
-
Body frame
- \({\text{N}}\) :
-
Navigation frame
- \({\hat{\text{N}}}\) :
-
Estimated navigation frame
- \({\text{R}}_{{\text{e}}}\) :
-
Radius of earth
- \({\mathbf{E}}\) :
-
Identity tensor
- \(f_{{\text{x}}} ,\,f_{{\text{y}}} ,\,f_{{\text{z}}}\) :
-
Accelerometers output in x, y, and z channels of the body frame
- \({\updelta }f_{{\text{x}}} ,\,{\updelta }f_{{\text{y}}} ,\,{\updelta }f_{{\text{z}}}\) :
-
The error of accelerometers in the x, y, and z channels of the body frame
- \({\mathbf{R}}^{{{\hat{\text{N}}\text{N}}}}\) :
-
Rotation tensor of the frame \({\hat{\text{N}}}\) relative to frame N
- \(v_{{\text{n}}} ,\,v_{{\text{e}}} ,\,v_{{\text{d}}}\) :
-
Velocities in north, east, and down channels
- \(\lambda ,\,\ell ,\,h\) :
-
Latitude, longitude, and height
- \({\upomega }_{{\text{n}}} ,\,{\upomega }_{{\text{d}}}\) :
-
Components of Earth's angular velocity in the north and down channels
- \({\upvarepsilon }\) :
-
‘Component perturbation’ operator
- \({\updelta }\) :
-
‘Total perturbation’ operator
- \(\omega_{{\text{x}}} ,\,\omega_{{\text{y}}} ,\,\omega_{{\text{z}}}\) :
-
Gyros output in x, y, and z channels of the body frame
- \({\updelta }\omega_{{\text{x}}} ,\,{\updelta }\omega_{{\text{y}}} ,\,{\updelta }\omega_{{\text{z}}}\) :
-
The error of gyros in the x, y, and z channels of the body frame
- \({\upvarepsilon }{\mathbf{r}}^{{{\hat{\text{N}}\text{N}}}}\) :
-
Perturbation of the rotation vector of the frame \({\hat{\text{N}}}\) relative to frame N
- \({\upvarepsilon }{\mathbf{R}}^{{{\hat{\text{N}}\text{N}}}}\) :
-
Skew symmetric form of \({\upvarepsilon }{\mathbf{r}}^{{{\hat{\text{N}}\text{N}}}}\)
- \(\phi ,\,\theta ,\,\psi\) :
-
Roll, pitch, and yaw angles
- \(\hat{\phi },\,\hat{\theta },\,\hat{\psi }\) :
-
Estimated roll, pitch, and yaw angles
- \(\overset{\lower0.5em\hbox{$\smash{\scriptscriptstyle\frown}$}}{\varphi } ,\,\overset{\lower0.5em\hbox{$\smash{\scriptscriptstyle\frown}$}}{\theta } ,\,\overset{\lower0.5em\hbox{$\smash{\scriptscriptstyle\frown}$}}{\psi }\) :
-
Actual roll, pitch, and yaw angles
- \({\upvarepsilon }\phi ,\,{\upvarepsilon }\theta ,\,{\upvarepsilon }\psi\) :
-
Small rotation angles
- \(\Delta \phi ,\,\Delta \theta ,\,\Delta \psi\) :
-
The error in roll, pitch, and yaw angles
- \([{\text{T}}]^{{{\text{BN}}}}\) :
-
Transformation matrix of the navigation frame to the body frame
- \([{\hat{\text{T}}}]^{{{\text{BN}}}}\) :
-
Estimation of \([{\text{T}}]^{{{\text{BN}}}}\)
References
Rogers, R. M. Applied Mathematics in Integrated Navigation Systems (American Institute of Aeronautics and Astronautics (AIAA), 2007).
Li, W., Wu, W., Wang, J. & Lu, L. A fast SINS initial alignment scheme for underwater vehicle applications. J. Navig. 66, 181–198 (2012).
Zhu, L. & Cheng, X. An improved initial alignment method for rocket navigation systems. J. Navig. 66, 737–749 (2013).
Silva, F. O. E., Hemerly, E. M., Filho, W. D. C. L., Chagas, R. A. J. An improved stationary fine self-alignment approach for SINS using measurement augmentation. In Anais do XX Congresso Brasileiro de Automática, Belo Horizonte (2014).
Park, C. G. & Lee, J. G. An overlapping decomposed filter for INS initial alignment. J. Korean Soc. Aeronaut. Space Sci. 19(3), 65–76 (1991).
Ramanandan, A., Chen, A. & Farrell, J. Inertial navigation aiding by stationary updates. Intell. Transport. Syst. IEEE Trans. 13(1), 235–248 (2012).
Huang, X., Wang, Z. Adaptive unscented Kalman filter in Inertial Navigation System alignment. In ICICIP, 2nd International Conference on (2011).
Li, H., Pan, Q., Wang, X., Jiang, X. & Deng, L. Kalman filter design for initial precision alignment of a strapdown inertial navigation system on a rocking base. J. Navig. 68, 184–195 (2014).
Silva, F. O., Filho, W. C. L., Hemerly, E. M. Design of a stationary self-alignment algorithm for strapdown inertial. In International Federation of Automatic Control (2015).
Gao, W., Zhang, Y. & Wang, J. Research on initial alignment and self-calibration of rotary strapdown inertial navigation systems. Sensors 15, 3154–3171 (2015).
Silva, F. O., Hemerly, E. M. & Filho, W. C. L. Error analysis of analytical coarse alignment formulations for stationary SINS. IEEE Trans. Aerosp. Electron. Syst. 52(4), 1777–1796 (2016).
Silva, F. O. Generalized error analysis of analytical coarse alignment formulations for stationary SINS. Aerosp. Sci. Technol. 79, 500–505 (2017).
Li, J., Xu, J., Chang, L. & Zha, F. An improved optimal method for initial alignment. J. Navig. 67, 727–736 (2014).
Lü, S., Xie, L. & Chen, J. New techniques for initial alignment of strapdown inertial navigation system. J. Franklin Inst. 346(10), 1021–1037 (2009).
Fei, Y. & Feng, S. Application of H∞ filtering in the initial alignment of strapdown inertial navigation system. J. Mar. Sci. Appl. 4(1), 50–53 (2005).
Li, A., Chang, G. B., Qin, F. J., Li, H. W. Improvedprecision of strapdown inertial navigation system brought by dual-axis continuous rotation of inertial measurement unit. In Informatics in Control, Automation and Robotics (CAR), 2nd International Asia Conference (2010).
Lee, G. Multiposition alignment of strapdown inertial navigation system. IEEE Trans. Aerosp. Electron. Syst. 29(4), 1323–1328 (1993).
Acharya, A., Sadhu, S., Ghoshal, T. K. Improving self-alignment of strapdown INS using measurement augmentation. In FUSION 12th International Conference on (IEEE, 2009).
Titterton, D., Weston, J. L. Strapdown Inertial Navigation Technology, vol. 17 (IET, 2004).
Ali, J., Jiancheng, F. Alignment of Strapdown Inertial Navigation System: A Literature Survey Spanned Over the Last 14 Years (Beijing University of Aeronautics and Astronautics, 2004).
Fang, J. C. & Wan, D. J. A fast initial alignment method for strapdown inertial navigation system on stationary base. Aerosp. Electron. Syst. IEEE Trans. 32(4), 1501–1504 (1996).
Jiang, Y. F. & Lin, Y. P. Error estimation of INS ground alignment through observability analysis. Aerosp. Electron. Syst. IEEE Trans. 28(1), 92–97 (1992).
Zhao, L., Guan, D., Cheng, J., Xu, X. & Fei, Z. Coarse alignment of marine strapdown INS based on the trajectory fitting of gravity movement in the inertial space. Sensors 16, 1714 (2016).
Zipfel, P. H. Modeling and Simulation of Aerospace Vehicle Dynamics (AIAA, 2007).
M. Liu, Y. Gao, G. Li, X. Guang and S. Li, “An Improved Alignment Method for the Strapdown Inertial Navigation System (SINS),” sensors, vol. 16, 2016.
Ru, X. et al. MEMS inertial sensor calibration technology: Current status and future trends. Micromachines 13(6), 879 (2022).
Zhang, H. et al. A systematic approach for inertial sensor calibration of gravity recovery satellites and its application to Taiji-1 mission. Remote Sens. 15(15), 3817 (2023).
Guner, U. & Dasdemir, J. Novel self-calibration method for imu using distributed inertial sensors. IEEE Sens. J. 23(2), 1527–1540 (2022).
Wang, Z. et al. Extrinsic calibration of visual and inertial sensors for the autonomous vehicle. IEEE Sens. J. 23, 15934–15941 (2023).
Carlsson, H., Skog, I. & Jaldén, J. Self-calibration of inertial sensor arrays. IEEE Sens. J. 21(6), 8451–8463 (2021).
Bar-Itzhack, I. Y. & Berman, N. Control theoretic approach to inertial navigation systems. J. Guid. Control Dyn. 11(3), 237–245 (1988).
Author information
Authors and Affiliations
Contributions
This article is a part of M.E. PhD thesis which was supervised by H.M. and M.A.A.
Corresponding author
Ethics declarations
Competing interests
The authors declare no competing interests.
Additional information
Publisher's note
Springer Nature remains neutral with regard to jurisdictional claims in published maps and institutional affiliations.
Supplementary Information
Rights and permissions
Open Access This article is licensed under a Creative Commons Attribution 4.0 International License, which permits use, sharing, adaptation, distribution and reproduction in any medium or format, as long as you give appropriate credit to the original author(s) and the source, provide a link to the Creative Commons licence, and indicate if changes were made. The images or other third party material in this article are included in the article's Creative Commons licence, unless indicated otherwise in a credit line to the material. If material is not included in the article's Creative Commons licence and your intended use is not permitted by statutory regulation or exceeds the permitted use, you will need to obtain permission directly from the copyright holder. To view a copy of this licence, visit http://creativecommons.org/licenses/by/4.0/.
About this article
Cite this article
Atashgah, M.A.A., Mohammadkarimi, H. & Ebrahimi, M. A fast strapdown gyrocompassing algorithm based on INS differential errors. Sci Rep 13, 15297 (2023). https://doi.org/10.1038/s41598-023-42235-6
Received:
Accepted:
Published:
DOI: https://doi.org/10.1038/s41598-023-42235-6
Comments
By submitting a comment you agree to abide by our Terms and Community Guidelines. If you find something abusive or that does not comply with our terms or guidelines please flag it as inappropriate.