Abstract

Sculling motion is a standard input to evaluate the performance of the velocity algorithm in a highly dynamic environment. Conventional sculling algorithms usually adopt incremental angle/specific force increments or angular rate/specific force as algorithm inputs. However modern inertial sensors have different output types now, which do not correspond to the inputs of those traditional algorithms. For example, some inertial sensors have the integrated angular rate (incremental angle)/specific force outputs or angular rate/specific force increments outputs. Hence the conventional sculling algorithms cannot be easily applied to these situations. A novel sculling algorithm using incremental angle/specific force inputs or angular rate/specific force increments inputs is developed in this paper. The advantage of the novel algorithm is that it can calculate the carrier velocity directly without converting the dimension of inertial sensor outputs values. Theoretical analysis, digital simulations, and a trial study are carried out to verify our algorithm. The results demonstrate that for corresponding types of strapdown inertial navigation systems (SINS) the novel sculling algorithm exhibits better performance than the conventional sculling velocity algorithms.

1. Introduction

Improvements in maneuverability of flight vehicles necessitate SINS capable of efficiency in highly dynamic environments. To improve the precision of SINS, sculling motion is usually employed as a standard input to evaluate the performance of the velocity algorithm in a dynamic environment. Savage provided an analytical description of sculling motion in two forms [1, 2]. In that study a digital algorithm capable of calculating the sculling integral term was described. An analytical model for the evaluation of error build-up under band-limited random process input for the digital integration algorithm was developed in a later study [3]. It was demonstrated that the digital integration process introduced a random walk type error in the output that was directly proportional to the root-mean-square input amplitude, directly proportional to the square-root of the input bandwidth, and inversely proportional to the digital integration update frequency. Ignagni derived a class of optimized sculling algorithms and demonstrated a duality between the derived class of sculling algorithms and a previously derived class of coning algorithms [4]. Kelly developed a generic equivalency between coning and sculling integrals and algorithms. The equivalency allows a coning algorithm based on incremental angle input to be converted to its corresponding sculling algorithm using a simple mathematical formula [5]. In [6] two alternative approaches were developed for deriving strapdown navigation sculling algorithms. A key point of the two approaches is the use of additional gyro/accelerometer output signals which are the increments of the angular rate/specific force multiple integrals over the iteration interval. However, all these conventional velocity algorithms adopt incremental angle/specific force increments or angular rate/specific force as algorithm inputs. However modern inertial sensors produce different types of output now. For example, certain fiber optic gyros (FOGs) and the microelectromechanical systems (MEMS) gyros have angular rate sampled output, but the laser gyro usually has integrated angular rate output. The quartz accelerometer output is usually specific force, but some other type of accelerometer output carrier’s specific force increments. If the SINS use a gyro with an output of angular rate and an accelerometer with an output of specific force increments, these conventional sculling velocity algorithms are no longer very applicable. To solve this problem, a novel sculling algorithm using incremental angle/specific force inputs or angular rate/specific force increments inputs is developed in this paper. The novel algorithm can calculate out the carrier velocity directly without converting the dimension of inertial sensor outputs values. Owing to this, the precision of the algorithm is considerably high.

2. Conventional Sculling Algorithms

Velocity rate equation is

The carrier velocity in navigation coordinates at time is then obtained as the integral of (1) from time , evaluated at time as [1]where is the computer cycle index, Vsfm is the integrated transformed specific force increment, and Vg/corn is the gravity/Carioles velocity increment. Calculating Vg/corn is a relatively simple process and is therefore omitted. Vsfm can be expanded as [5]where

In (3) Vrotm is the velocity rotation correction and Vsculm is the sculling correction. Vsculm in (3) is a continuous integral form. The discrete algorithm for Vsculm, which is usually referred to as sculling algorithm, can be obtained from the coning algorithm using a simple duality formula [4, 5, 7]. For example, the 2-interval optimal sculling algorithm using incremental angle/specific force increments inputs is [5, 810]

Its coning algorithm counterpart, namely, the 2-interval optimal coning algorithm using incremental angle input, is [11]

The 2-interval optimal sculling algorithm using angular rate/specific force inputs is [12, 13]where is the attitude and velocity update period . Its coning algorithm counterpart using angular rate input is [14]where is the algorithm iteration interval. In a 2-interval algorithm there is H=2h.

3. Sculling Algorithm Using Incremental Angle/Specific Force Input

If the inertial sensors produce integrated angular rate (incremental angle)/specific force outputs, the conventional sculling algorithms such as (5) and (7) cannot calculate out the carrier’s velocity directly. The velocity algorithm must include a step for conversion of integrated angular rate (incremental angle) into angular rate by digital differentiation in order to use (7) or else convert specific force into specific force increments by digital integration in order to use (5). These steps will increase computational error. To solve this problem we have developed a novel sculling algorithm using incremental angle/specific force input.

3.1. Generalized Sculling Algorithm

For a 2-interval sculling velocity algorithm, there are two sample gyro outputs θi (i=1, 2) at time , , and three sample accelerometer outputs (j=1, 2, 3) at times , , and over an update period (, ). Assume that the incremental angle θ and specific force can be approximated by the second-order polynomial: where a, b, A, B, and are the polynomials coefficients. Then

Substituting (9) into Vsculm given by (3) gives

Substituting (10) into (11) gives

This is the 2-interval generalized sculling algorithm using incremental angle/specific force input.

3.2. Optimal Sculling Algorithm

A typical sculling motion is defined as [15]where is the amplitude of the angular vibration, c is the amplitude of the specific force vibration, J, K are the unit vectors along the two body axes (y, z) about which the oscillations are occurring, and Ω is the frequency associated with the angular and specific force oscillations.

The incremental angle and specific force increments of the sculling motion are

Substituting (13) and (14) into the Vsculm term in (3) yields the truth sculling correction:

As is seen in (15), in a sculling environment the true sculling correction Vsculm is a constant value. For a 2-interval system, the outputs of inertial sensors over a velocity update period are

The generalized form of the sculling correction using incremental angle/specific input can be given aswhere is the number of iteration intervals over the velocity update period. For a 2-interval algorithm, N=2. It follows from (16) that

Obviously, the sculling correction Vsculm is only determined by j-i. Therefore (17) can be simplified as

For a 2-interval sculling algorithm, N=2. Substituting (18) into (19) gives

Sculling correction should be equal to the true sculling correction , . Using (19) and (15), the simultaneous equation for the unknown parameter can be obtained. Then the equation can be simplified by Taylor expanding “ΩH”:

The solution for is =1/3. Hence the 2-interval optimal sculling algorithm using incremental angle/specific force input is derived:

The per-unit time algorithm error is

In (2) and (3), the integrated transformed specific force increment Vsfm is composed of Vsculm, Vrotm, and Vm. Vm and θm in (3) can be calculated by digital integration:

Substituting (24) into (3) gives

Substituting (22), (24), and (25) into (3) gives the integrated transformed specific force increments:

As described previously, Vg/corn in (2) can be calculated out easily; indeed it can be calculated approximatively as a constant during one update period and omitted here. in (2), i.e., the carrier velocity at , has been calculated out during the last algorithm update period. Thus the carrier velocity at time can be calculated out by substituting (26) into (2).

3.3. Formalized Optimal Sculling Algorithm

For an N-interval sculling velocity algorithm using incremental angle/specific force input, the sample number of the accelerometer outputs (specific force) is N+1, and the number of the gyro outputs (integrated angular rate) is . The gyro/accelerometer outputs in a sculling environment defined by (13) are

As previously mentioned, N-interval sculling velocity algorithm can be formulated as (19). Substituting (27) into (19) we obtain

Applying (28) with Taylor series expansion for the coefficient terms “ΩH”, we obtain

Applying (15) with Taylor series expansion for the coefficient terms “ΩH” gives

From we can obtainwhere

The solution to (31) is G = A−1D. Details regarding the optimal coefficients are shown in Table 1.

Comparing the developed sculling algorithm given by (22) with the conventional sculling algorithms represented in (5) or (7), we can see the advantages of the developed algorithm are that it is able to calculate out the sculling correction and then the velocity at directly without any requirements to perform the dimension conversion of inertial sensor outputs.

4. Sculling Algorithm Using Angular Rate/Specific Force Increments Input

4.1. Generalized Sculling Algorithm

If inertial sensors output angular rate/specific force increments, for a 2-interval sculling velocity algorithm there are three sample gyro outputs ω (i=1, 2, 3) at times , , and and two sample accelerometer outputs Vj (j=1, 2) at times , over an update period (, ). Assume that the angular rate ω and the specific force increments Vj can be approximated by the second-order polynomial:where a, b, A, B, and are the polynomials coefficients. We then obtain the following:

Comparing (9) and (10) with (33) and (34) we can see that there is a duality between the sculling algorithm using incremental angle/specific force inputs and the sculling algorithm using angular rate/specific force increments inputs. Eqs. (9) and (10) have the identical mathematical forms to (33) and (34), and they equal each other when the terms θ, f, aH, bH2, A, BH, and CH2 in (9) and (10) are replaced by V, ω, AH, BH2, a, bH, and cH2 respectively. The 2-interval generalized sculling algorithm using angular rate/specific force increments inputs can therefore be given as

4.2. Formalized Optimal Sculling Algorithm

For N-interval sculling velocity algorithm using angular rate/specific force increments inputs, the sample number of the accelerometer outputs (specific force increments) is N-1, and the sample number of the gyro outputs (angular rate) is . The gyro/accelerometer outputs in a sculling environment defined by (13) are

Similar to the derivations of (15)-(17), the generalized form for sculling correction algorithm using angular rate/specific force increments inputs is

It can be derived from (36) that

Obviously, the sculling correction in (37) is only controlled by j-i. Therefore (37) can be simplified as

Eqs. (19) and (39) have the identical mathematical forms when the terms of θ, f in (19) are replaced by V, ω. Hence the optimal values for coefficients , … in (39) are as same as those in (9). That is, the optimal values for coefficients shown in Table 1 are also appropriate for the sculling algorithm using angular rate/specific force increments inputs. For example, the optimal coefficient for a 2-interval sculling algorithm using angular rate/specific force increments inputs is k=1/3, and the corresponding sculling algorithm is

The algorithm error per unit time is

5. Simulations

The sculling motion is defined by (13). For this 600s duration test, the amplitude of the angular vibration b=1°, the amplitude of the specific force vibration c=10g, the frequency associated with the angular and specific force oscillations Ω=2π rad/s (oscillation frequency is 1 Hz). The inertial sensors outputs are given by (16). The velocity update period H=0.01s. The initial attitude is (0, 0, 0)°. The initial velocity is (0, 0, 0)m/s. The initial position is (118.813773°, 32.035512°, 10 m). The navigation coordinate frame is set to east-north-up. The error comparisons between the developed 2-interval sculling algorithm given by (22) and the conventional 2-interval sculling algorithm given by (5) are shown in Figures 1 and 2. The solid line represents the developed sculling algorithm errors; the dotted line represents the conventional sculling algorithm errors.

As can be seen in Figure 1, the eastward velocity errors of both algorithms are larger about one order than those northern velocity errors. This is because in a sculling environment defined by (13), the sculling error mainly exists in the x-axis of the carrier. The corresponding velocity component is in the east-north-up coordinate frame.

Particularly, for the traditional algorithm the sculling correction term Vsculm given in (15) has not been compensated effectively due to the computational error caused by the conversion of specific force into specific force increments by digital integration. There is a constant error term in the eastward velocity of the traditional algorithm, so the eastward velocity error curve of the traditional algorithm increases rapidly and linearly due to the error propagation.

However, the accuracy of both and as estimated by the proposed algorithm is improved by one order of magnitude when compared with those measured by the traditional sculling algorithm. This is because using the proposed sculling algorithm can calculate out the velocity directly without dimension conversion of inertial sensor outputs. Therefore, the sculling correction has been compensated effectively and the velocity determination precision is improved dramatically.

From Figure 2 we can see that the longitude errors of both algorithms are larger than the latitude errors of both algorithms. This is because the eastward velocity error is the main reason for the longitude error. As mentioned in the third paragraph before, the eastward velocity errors of both algorithms are larger about one order than those northern velocity errors.

The increase of the longitude error curve of the traditional algorithm is particularly rapid, because when the inertial sensors output integrated angular rate/specific force and the carrier is in a sculling motion environment, the traditional algorithm cannot compensate the sculling correction well. It will induce a rapid error propagation in eastward velocity and then a rapid increasing longitude error finally.

However, the position errors of the proposed algorithm are reduced by more than one order of magnitude compared with those of the traditional sculling algorithm. This is because the improved precision in velocity determination will also result in improved precision in position determination.

6. Trial Study

As is shown in Figure 3, a dynamic car test was performed to validate the performance of our proposed sculling algorithm. For this 20-minute test, the constant gyro drift is 0.01°/h; the accelerometer bias is 5 × 10−5g. The update period for the velocity algorithm is 0.01s. A GPS/INS integrated navigation system (SPAN-CPT, NovAtel in Sweden) is also used as the benchmark for attitude, velocity, and position. NovAtel has claimed that the performance of this integrated navigation system is better than 0.06° for heading and 0.02° for pitch and roll, 0.015 m/s for horizontal velocity, and 1.2m for horizontal position accuracy.

Trial results for the comparative study between the novel and traditional algorithm are shown in Figures 4 and 5. Obviously, the accuracy of horizontal (eastward/northward) velocity and horizontal position (longitude/latitude) is improved when using the novel algorithm. These trial results are consistent with both theoretical analysis (Section 3.3) and simulation results before (Figures 1 and 2).

7. Conclusions

To solve the issue that in certain situations the output parameters of inertial sensor do not match the input parameters required by the conventional sculling algorithms, an optimal sculling algorithm using incremental angle/specific force input or angular rate/specific force increments inputs is developed in this paper. The developed sculling algorithms can calculate out the carrier velocity directly without the dimension conversion of inertial sensor outputs. Accordingly, the developed algorithms provide higher precision than conventional sculling algorithms in the SINS in which the employed inertial sensors have the integrated angular rate/specific force or angular rate/specific force increments outputs. Our novel sculling velocity algorithm thus has great useful value in such cases.

Nomenclature

:Specific force measured by accelerometers
:Direction cosine matrix
:Update period
:Incremental angle vector over the ith subminor interval
:Angular velocity vector.

Data Availability

The readers can access the data underlying the findings of the study by visiting https://fairsharing.org/bsg-p000118.

Conflicts of Interest

The authors declare that they have no conflicts of interest.

Acknowledgments

The authors would like to acknowledge postgraduate student Di Sang for his work in the dynamic car test. We also appreciate the assistance of the Information Navigation and Measurement and Control Technology Institute of Southeast University, Nanjing, in the use of their equipment. The authors gratefully acknowledge the helpful comments and suggestions of English editors and reviewers. This work was supported in part by the National Natural Science Foundation of China under Grant Nos. 61601228 and 51305207, the Natural Science Foundation of Jiangsu Provincial College under Grant No. 13KJB460010, the Natural Science Foundation of Jiangsu under Grant No. BK20161021, and the Top-Notch Academic Programs Project of Jiangsu Higher Education Institutions (TAPP: PPZY2015A062). This work was also supported by the National Key Research and Development Program of China (Grant No. 2017YFB1103200).