Hostname: page-component-cd9895bd7-dk4vv Total loading time: 0 Render date: 2024-12-27T23:38:48.223Z Has data issue: false hasContentIssue false

Underwater Doppler Navigation with Self-calibration

Published online by Cambridge University Press:  23 September 2015

Xianfei Pan
Affiliation:
(National University of Defense Technology - College of Mechatronics and Automation, China, 410073)
Yuanxin Wu*
Affiliation:
(Central South University - School of Aeronautics and Astronautics, China, 410083)
Rights & Permissions [Opens in a new window]

Abstract

Precise autonomous navigation remains a substantial challenge to all underwater platforms. Inertial Measurement Units (IMU) and Doppler Velocity Logs (DVL) have complementary characteristics and are promising sensors that could enable fully autonomous underwater navigation in unexplored areas without relying on additional external Global Positioning System (GPS) or acoustic beacons. This paper addresses the combined IMU/DVL navigation system from the viewpoint of observability. We show by analysis that under moderate conditions the combined system is observable. Specifically, the DVL parameters, including the scale factor and misalignment angles, can be calibrated in-situ without using external GPS or acoustic beacon sensors. Simulation results using a practical estimator validate the analytic conclusions.

Type
Research Article
Copyright
Copyright © The Royal Institute of Navigation 2015 

1. INTRODUCTION

Current underwater navigation technology enables new emerging applications that have been previously considered impossible or impractical, including autonomous naval operations, oceanographic studies and under ice surveys. Despite significant advances, precise navigation remains a substantial challenge to all underwater platforms (Kinsey et al., Reference Kinsey, Eustice and Whitcomb2006, Hegrenæs and Berglund, Reference Hegren, S. and Berglund2009). The Global Positioning System (GPS) provides superior three-dimensional navigation capabilities for vehicles above the water surface, but not underwater due to water blockage of GPS radio-frequency signals. This limits GPS usage to surveying of acoustic transponders or aiding of sensor calibration for underwater applications (Kinsey and Whitcomb, Reference Kinsey and Whitcomb2006). Acoustic navigation is widely used for limited-area scientific and industrial underwater vehicles, which requires prior careful placement of beacons fixed or moored on the sea floor or on the hull of a surface ship.

The development of commercial Doppler sensors and Inertial Measurement Units (IMU, consisting of a triad of gyroscopes and a triad of accelerometers) has enabled significant improvement to underwater navigation (Kinsey et al., Reference Kinsey, Eustice and Whitcomb2006). The multi-beam Doppler Velocity Log (DVL) can provide the bottom-track or water-track velocity measurement with a precision of 0·3% or less, while the IMU measures the arbitrary three-dimensional (3D) angular velocity and translational acceleration which can be integrated to yield navigation information. Combining a DVL with IMU makes possible large-scale underwater navigation in unexplored areas. They are complementary in characteristics to each other. The DVL velocity aids the IMU in mitigating the accumulated navigation errors and in calibrating inertial sensor errors. On the other hand, the IMU's short-time stability helps the DVL to adaptively update parameters that may vary significantly due to ambient factors like water temperature and density (Kinsey et al., Reference Kinsey, Eustice and Whitcomb2006). Their combined navigation accuracy depends on the accuracy of IMU-DVL alignment calibration (Whitcomb et al., Reference Whitcomb, Yoerger and Singh1999; Jalving et al., Reference Jalving, Gade, Svartveit, Willumsen and Sorhagen2004). The alignment calibration problem is not easy as IMU and DVL are usually separate units and placed at different locations on the vehicle. This mounting arrangement excludes the alignment calibration during manufacture and instead requires an in-situ calibration during normal naval operations. Several approaches have been reported to attack this alignment calibration using additional external sensors such as GPS or Long Baseline (LBL) acoustic navigation beacons (Joyce, Reference Joyce1989; Tang et al., Reference Tang, Wang, Li and Wu2013; Kinsey and Whitcomb, Reference Kinsey and Whitcomb2006; Reference Kinsey and Whitcomb2007). These methods require the vehicle to run on the surface so that a GPS signal is available (Joyce, Reference Joyce1989; Tang et al., Reference Tang, Wang, Li and Wu2013), or additional navigation beacons to be placed at surveyed sites (Kinsey and Whitcomb, Reference Kinsey and Whitcomb2006; Reference Kinsey and Whitcomb2007). Troni et al. (Reference Troni, Kinsey, Yoerger and Whitcomb2012) and Troni and Whitcomb (Reference Troni and Whitcomb2010) proposed an in-situ calibration method using only on board DVL, gyrocompass and depth sensors, but the gyrocompass is unrealistically assumed to provide exact absolute attitude. In fact, precise attitude estimation for gyrocompass is not a solved problem and also needs extensive study (Silson, Reference Silson2011; Li et al., Reference Li, Tang, Lu and Wu2013). In view of the inherent characteristics of both IMU and DVL, their respective parameter estimation and alignment calibration should be accounted for together, so as to achieve autonomous underwater navigation in large unexplored areas. Otherwise, the combined navigation capacity of IMU and DVL would be compromised in one aspect or another.

The content of the paper is organised as follows. Section 2 presents the mathematical formulation of the combined IMU/DVL navigation system, and then discusses the state estimability from the viewpoint of observability. An ideal observer is derived from the observability analysis procedure. Section 3 designs numerical simulations mimicking typical underwater vehicle motions and uses both the ideal observer and a practical estimator to validate the analytic conclusions. Conclusions are drawn in Section 4.

2. SYSTEM FORMULATION AND STATE OBSERVABILITY

2.1. System Formulation

The DVL uses the principle that by reflecting three or more non-coplanar radio/sound beams off a surface and measuring the Doppler shifts, the velocity of the body with respect to that surface can be obtained (Groves, Reference Groves2008). Most systems use the Janus configuration with four beams. The surface-referenced velocity can be obtained as

(1)$${\bf v}^d = {\bf K\Delta f}$$

The superscript d denotes the DVL's coordinate frame D naturally defined by the beam spatial configuration. The vector Δf is formed by Doppler shifts along each beam and the matrix K depends on the transmitted sound wave frequency, the spatial configuration of beams and the sound speed in water. The first two factors of K are fixed for a DVL unit, but the sound speed may vary with temperature, depth and salinity by a few percent (Groves, Reference Groves2008). We rewrite the above relationship as

(2)$${\bf v}^d = {\bf K\Delta f} = \displaystyle{1 \over k}{\bf K}_s {\bf \Delta f} = \displaystyle{1 \over k}{\bf y}_{DVL} \Leftrightarrow {\bf y}_{DVL} = k{\bf v}^d $$

where yDVLKsΔf denotes the DVL output, k is a scalar factor that accounts for the change of sound velocity, and Ks is a scaled version of K that is nearly invariant to water conditions.

In contrast to the DVL directly providing the velocity relative to the seabed (bottom-lock), the IMU measures the angular velocity and non-gravitational acceleration with respect to the inertial space. Numerical integrations must be carried out to derive attitude, velocity or position information, which is known as the inertial navigation computation procedure (Groves, Reference Groves2008; Wu and Pan, Reference Wu and Pan2013b). As gyroscopes and accelerometers are subject to errors like bias and noise, the computed inertial navigation result is prone to error drift accumulating with time.

Denote by N the local level reference frame, by B the IMU body frame, by I the inertial non-rotating frame, and by E the Earth frame. The navigation (attitude, velocity and position) rate equations in the reference n-frame are well known as (Titterton and Weston, Reference Titterton and Weston2004; Groves, Reference Groves2008; Savage, Reference Savage2007)

(3)$$\dot{\bf C}_b^n = {\bf C}_b^n \left( {{\bf \omega} _{nb}^b \times} \right){\comma}\quad {\bf \omega} _{nb}^b = {\bf \omega} _{ib}^b - {\bf b}_g - {\bf C}_n^b \left( {{\bf \omega} _{ie}^n + {\bf \omega} _{en}^n} \right)\comma$$
(4)$$\dot{\bf v}^n = {\bf C}_b^n \left( {{\bf f}^b - {\bf b}_a} \right) - \left( {2{\bf \omega} _{ie}^n + {\bf \omega} _{en}^n} \right) \times {\bf v}^n + {\bf g}^n $$
(5)$$\dot{\bf p} = {\bf R}_c {\bf v}^n $$

where ${\bf C}_b^n $ denotes the attitude matrix from the body frame to the reference frame, vn the velocity relative to the Earth, ${\bf \omega} _{ib}^b $ the error-contaminated body angular rate measured by gyroscopes in the body frame, fb the error-contaminated specific force measured by accelerometers in the body frame, ${\bf \omega} _{ie}^n $ the Earth rotation rate with respect to the inertial frame, ${\bf \omega} _{en}^n $ the angular rate of the reference frame with respect to the Earth frame, ${\bf \omega} _{nb}^b $ the body angular rate with respect to the reference frame, and gn the gravity vector. The skew symmetric matrix (·×) is defined so that the cross product satisfies a × b = (a×)b for two arbitrary vectors. The gyroscope bias bg and the accelerometer bias ba are taken into consideration as approximately random constants, i.e., ${\dot{\bf b}_g} = {\dot{\bf b}_a} = {\bf 0}$. The position ${\bf p} \mathop{=}\limits^\Delta \left[ {\matrix{\lambda & L & h \cr}} \right]^T $ is described by the angular orientation of the reference frame relative to the Earth frame, commonly expressed as longitude λ, latitude L and height h above the Earth's surface. In the context of a specific local level frame choice, e.g., North-Up-East, ${\bf v}^n \mathop{=}\limits^\Delta \left[ {\matrix{{v_N} & {v_U} & {v_E}\cr}} \right]^T $ and the local curvature matrix is explicitly expressed as

(6)$${\bf R}_c = \left[ {\matrix{ 0 & 0 & {\displaystyle{1 \over {(R_E + h)\cos L}}} \cr {\displaystyle{1 \over {R_N + h}}} & 0 & 0 \cr 0 & 1 & 0 \cr}} \right]$$

where R E and R N are respectively the transverse radius of curvature and the meridian radius of curvature of the reference ellipsoid.

Using Equation (2), the derived velocity from IMU is related to the DVL output by

(7)$${\bf y}_{DVL} = k{\bf C}_b^d {\bf C}_n^b {\bf v}^n $$

where ${\bf C}_b^d $ is the misalignment attitude matrix of the d-frame with respect to the b-frame. This misalignment matrix and the scale factor are both regarded as random constants. As with previous studies (Hegrenæs and Berglund, Reference Hegren, S. and Berglund2009; Joyce, Reference Joyce1989; Kinsey and Whitcomb, Reference Kinsey and Whitcomb2006; Reference Kinsey and Whitcomb2007; Tang et al., Reference Tang, Wang, Li and Wu2013; Troni et al., Reference Troni, Kinsey, Yoerger and Whitcomb2012; Troni and Whitcomb, Reference Troni and Whitcomb2010), the translational misalignment between DVL and IMU will not be considered hereafter.

We see from Equations (3), (4) and (7) that in addition to attitude/velocity/position that are of immediate interest to us, the combined IMU/DVL navigation also necessitates the finding of such parameters as inertial sensor biases (bg and ba), DVL scale factor k and misalignment matrix ${\bf C}_b^d $. Insufficient knowledge of these parameters could result in degrading the combined navigation accuracy.

2.2. State Observability Analysis

Without any other external sensors, is it possible to determine the above parameters? From a viewpoint of a control system, this question relates to the (global) observability of the system state (Chen, Reference Chen1999; Wu et al., Reference Wu, Zhang, Wu, Hu and Hu2012). In such a case, the system model is given by Equations (3)–(5) and the observation model is given by Equation (7), with the IMU measurement as the system input and the DVL measurement as the system output.

Hereafter we use y to replace yDVL for notational brevity. From Equation (7), we have ${\bf v}^n = {\bf C}_b^n {\bf C}_d^b {\bf y}/k$. Substituting into Equation (4) and using Equation (3) yield

(8)$${{\left( {{\bf C}_b^n \left( {{\bf \omega}_{nb}^b \times} \right){\bf C}_d^b {\bf y} + {\bf C}_b^n {\bf C}_d^b \dot{\bf y}} \right)} / k} = {\bf C}_b^n \left( {{\bf f}^b - {\bf b}_a} \right) - \left( {2{\bf \omega}_{ie}^n + {\bf \omega}_{en}^n} \right) \times {{\left( {{\bf C}_b^n {\bf C}_d^b {\bf y}} \right)} / k} + {\bf g}^n $$

or equivalently,

(9)$$k\left( {{\bf C}_n^b {\bf g}^n + {\bf f}^b - {\bf b}_a} \right) = \left( {\left( {{\bf \omega} _{ie}^b + {\bf \omega}_{ib}^b - {\bf b}_g} \right) \times} \right){\bf C}_d^b {\bf y} + {\bf C}_d^b \dot{\bf y}$$

Troni et al. (Reference Troni, Kinsey, Yoerger and Whitcomb2012) and Troni and Whitcomb (Reference Troni and Whitcomb2010) used a quite coarse simplification of this equation for DVL calibration, for instance, neglecting the term ${\bf C}_n^b {\bf g}^n $.

On any trajectory segment with constant ${\bf C}_n^b $, the quantities ${\bf \omega} _{ie}^b $ and ${\bf \omega} _{ib}^b - {\bf b}_g $ keep almost unchanged with the moderate speed of an underwater vehicle. As the vector magnitude $\Vert {{\bf \omega} _{ib}^b - {\bf b}_g} \Vert \approx \Vert {{\bf \omega} _{ie}^b} \Vert \approx 7\hskip-2pt \cdot \hskip-2pt 3 \times 10^{ - 5} \,{\rm rad}/{\rm s}$ is very small, Equation (9) is reasonably approximated by

(10)$$k\left( {{\bf C}_n^b {\bf g}^n + {\bf f}^b - {\bf b}_a} \right) = {\bf C}_d^b \dot{\bf y}$$

Time derivative of the above equality is

(11)$$k\dot{\bf f}^b = {\bf C}_d^b \ddot{\bf y}$$

from which we obtain $k = \pm {{\Vert {\ddot{\bf y}} \Vert} / {\Vert {{{\dot{\bf f}}^b}} \Vert}}$ whenever $\Vert {{{\dot{\bf f}}^b}} \Vert$ is non-vanishing, as an attitude matrix does not change the magnitude of a vector. It is trivial to solve the sign ambiguity. For example, if the b-frame is roughly aligned with the d-frame, which is often the case in practice, the positive sign will obviously be the right option. So the DVL scale factor is now a known quantity. Note that Equation (11) is valid for any segment of this type, so if there exist two such segments that ${\dot{\bf f}^b}$ (or equivalently $$\ddot{\bf y}$$) have different directions, the misalignment matrix ${\bf C}_d^b $ can be determined according to Lemma 1 in the Appendix.

On any trajectory segment with fast-changing ${\bf C}_n^b $, the quantity ${\bf \omega} _{ib}^b $ is much larger in magnitude than ${\bf \omega} _{ie}^b $ or bg (as far as a quality IMU is concerned). Equation (9) can be approximated as

(12)$${\bf C}_n^b {\bf g}^n = {{\left( {\left( {{\bf \omega}_{ib}^b \times} \right){\bf C}_d^b {\bf y} + {\bf C}_d^b \dot{\bf y}} \right)} / {k - {\bf f}^b + {\bf b}_a}} $$

Taking the norm on both sides gives

(13)$$g = \Vert {{\bf g}^n} \Vert = \Vert {{\bf \alpha} + {\bf b}_a} \Vert $$

which is a quadratic equation on the accelerometer bias ba with ${\bf \alpha} \mathop{=}\limits^\Delta {{\left( {\left( {{\bf \omega} _{ib}^b \times} \right){\bf C}_d^b {\bf y}\; + {\bf C}_d^b \dot{\bf y}} \right)} \big/ {k - {\bf f}^b}} $. According to Lemma 2 in the Appendix, we know that ba will be determined if the vectors α, at all times on segments of this type, are non-coplanar, or ∑ααT is non-singular (Wu et al., Reference Wu, Zhang, Wu, Hu and Hu2012). This requirement is naturally met for practical turning in water, as shown in the simulation section.

Then by the chain rule of the attitude matrix, ${\bf C}_n^b $ at any time on this segment satisfies

(14)$${\bf C}_n^b = {\bf C}_{b(t_0 )}^{b(t)} {\bf C}_{n(t_0 )}^{b(t_0 )} {\bf C}_{n(t)}^{n(t_0 )} \mathop{=}\limits^\Delta {\bf C}_{b(t_0 )}^{b(t)} {\bf C}_n^b (t_0 ){\bf C}_{n(t)}^{n(t_0 )} $$

where ${\bf C}_n^b (t_0 )$ denotes the initial attitude matrix at the beginning of this segment, and ${\bf C}_{b(t_0 )}^{b(t)} $ and ${\bf C}_{n(t_0 )}^{n(t)} $, respectively, encode the attitude changes of the body frame and the reference frame. Substituting Equation (14) into Equation (12),

(15)$${\bf C}_n^b (t_0 ){\bf C}_{n(t)}^{n(t_0 )} {\bf g}^n = {\bf C}_{b(t)}^{b(t_0 )} ({\bf \alpha} + {\bf b}_a )$$

${\bf C}_n^b (t_0 )$ is solvable as there always exist two time instants that ${\bf C}_{n(t)}^{n(t_0 )} {\bf g}^n $ have different directions due to the Earth rotation (Wu et al., Reference Wu, Zhang, Wu, Hu and Hu2012). Also solvable is the attitude matrix ${\bf C}_n^b $ using Equation (14). Then the velocity vn can be determined by Equation (7), and the gyroscope bias bg can be determined by Equation (3).

The above analysis is summarised in the theorem below.

Theorem 1 (State Observability): If the vehicle trajectory contains segments of constant attitude with linearly independent ${\dot{\bf f}^b}$ (Type-I), as well as turning segments on which the vectors α as defined in Equation (13) are non-coplanar (Type-II), then the system of Equations (3)–(5) and (7) is observable in attitude, velocity, inertial sensor biases, and DVL scale factor and misalignment matrix.

Here are some explanations on the condition of linearly independent ${\dot{\bf f}^b}$, the rate of the specific force (sum of external forces except gravitation).

Remark 1: For a multiple-thruster-propelled underwater vehicle as in Kinsey and Whitcomb (Reference Kinsey and Whitcomb2006; Reference Kinsey and Whitcomb2007), it is not difficult to fulfil this condition, for example by thruster switching. This will normally create driving forces in different directions in the IMU body frame, resulting in linearly independent ${\dot{\bf f}^b}$.

Remark 2: For an underwater vehicle with a single thruster, it is tricky to fulfil this condition while keeping constant attitude. No matter the thruster force or the water resistance, its direction is fixed relative to IMU or DVL. If the vehicle moves at the same depth, linearly independent ${\dot{\bf f}^b}$ might only occur instantaneously at both start and end times of Type-I segments (a situation much like that in Tang et al. (Reference Tang, Wu, Wu, Wu, Hu and Shen2009)). This excitation is in practice not sufficient to produce a good estimate. Consider an example where $\dot{\bf f}^b = \left[ {\matrix{{\dot f_x^b} & 0 & 0 \cr}} \right]^T $ for all Type-I segments, which means the thrusters' force aligns with x-axis of the IMU body frame. Suppose the rotation sequence from d-frame to b-frame is first around y-axis (yaw angle, ψ), followed by z-axis (pitch angle, θ) and then by x-axis (roll angle, φ), ${\bf C}_d^b $ can be re-parameterised in Euler angles as

(16)$${\bf C}_d^b = \left[ {\matrix{ {\cos \theta \cos \psi} & {\sin \theta} & { - \cos \theta \sin \psi} \cr {\sin \phi \sin \psi - \cos \phi \cos \psi \sin \theta} & {\cos \phi \cos \theta} & {\cos \psi \sin \phi + \cos \phi \sin \theta \sin \psi} \cr {\cos \phi \sin \psi + \cos \psi \sin \phi \sin \theta} & { - \cos \theta \sin \phi} & {\cos \phi \cos \psi - \sin \phi \sin \theta \sin \psi} \cr}} \right].$$

Substituting into Equation (11)

(17)$$k\,{\dot f_x^b} \left[ {\matrix{ {\cos \theta \cos \psi} & {\sin \theta} & { - \cos \theta \sin \psi} \cr}} \right]^T = \ddot{\bf y}$$

which is irrelevant to the roll angle φ around x-axis. The other two angles can be computed by element comparison, while the angle φ is not estimable. This case is right what we encountered in land vehicle navigation subject to the non-holonomic constraint (Wu et al., Reference Wu, Wu, Hu and Hu2009). It is the angle around the thruster force that is inestimable, so if the thruster force was in a general direction, it can be imagined that all three Euler angles would be affected.

Remark 3: Even if ${\dot{\bf f}^b}$ (or equivalently $\ddot{\bf y}$) on the segments of constant attitude are linearly dependent, all states in Theorem 1 are still observable except the angle around the direction of ${\dot{\bf f}^b}$. This interesting conclusion can be obtained from the proof of Theorem 1. We only need to show that the products ${\bf C}_d^b {\bf y}$ and ${\bf C}_d^b \dot{\bf y}$ are known quantities in this scenario, in spite of the undetermined ${\bf C}_d^b $. Denote by η the unit direction of linearly dependent $\ddot{\bf y}$. For a single-thruster underwater vehicle, both the DVL velocity y and the velocity rate $\dot{\bf y}$ almost certainly align with the direction of η. From Equation (11), for some time t 1 on this segment $k\dot{\bf f}^b (t_1 ) = {\bf C}_d^b \ddot{\bf y}(t_1 ) = \Vert {\ddot{\bf y}(t_1 )} \Vert{\bf C}_d^b {\bf \eta} $ where $\ddot{\bf y}({t_1})$ is non-zero. Therefore, ${\bf C}_d^b {\bf y} = {{\Vert {\bf y} \Vert{\bf C}_d^b {\bf \eta} = k\Vert {\bf y} \Vert\dot{\bf f}^b (t_1 )} / {\Vert {\ddot{\bf y}(t_1 )} \Vert}}$ and ${\bf C}_d^b \dot{\bf y} = {{\Vert {\dot{\bf y}} \Vert{\bf C}_d^b {\bf \eta} = k\Vert {\dot{\bf y}} \Vert\dot{\bf f}^b (t_1 )} / {\Vert {\ddot{\bf y}(t_1 )} \Vert}}$ are both functions of known quantities.

Remark 4: Ascending or descending motion makes it possible for a single-thruster underwater vehicle to have linearly independent ${\dot{\bf f}^b}$. The water resistance due to ascending/descending velocity change will incur non-zero ${\dot{\bf f}^b}$ that deviates in direction from the thruster force. The ascending/descending motions are realised by unloading/loading the ballast tank.

2.3. Derived Ideal Observers

The above observability analysis not only gives a ‘yes or no’ answer to state estimability, but provides us valuable insights on designing observers. This is an additional advantage of global observability analysis (Wu et al., Reference Wu, Zhang, Wu, Hu and Hu2012). Specifically, Equation (11) allows us to construct an ideal observer to estimate DVL parameters, using IMU and DVL measurements on Type-I segments. No additional external sensors like GPS or LBL beacons are required. Suppose the time interval $\left[ {\matrix{{t_s^j} & {t_e^j} \cr}} \right]$ corresponds to the j-th Type-I segment (j = 1,2,…). For any $t \in \left[ {\matrix{{t_s^j} & {t_e^j}\cr}} \right]$, integrating Equation (11) twice over the subinterval $\left[ {\matrix{{t_s^j} & t \cr}} \right]$

(18)$$k{\bf \beta} (t) = {\bf C}_d^b {\bf \gamma} (t)$$

where ${\bf \beta} (t) \mathop{=}\limits^\Delta \int_{t_s^j} ^t {{\bf f}^b} d\tau - {\bf f}^b \left( {t_s^j} \right)\left( {t - t_s^j} \right)$ and ${\bf \gamma} (t) \mathop{=}\limits^\Delta {\bf y}\left( t \right) - {\bf y}\left( {t_s^j} \right) - \dot{\bf y}\left( {t_s^j} \right)\left( {t - t_s^j} \right)$. Compared with Equation (11), this integral form spares the differentiation of the measurements that would be subject to noise amplification (Wu and Pan, Reference Wu and Pan2013a; Wu et al., Reference Wu, Wang and Hu2014). The above equation obviously applies to all Type-I segments. Denote $\Omega = \bigcup\limits_j {\left[ {\matrix{{t_s^{\;j}} & {t_e^{\hskip2pt j}} \cr}} \right]} $, we have the following observer to calibrate the DVL parameters.

Ideal Observer – DVL Calibration (IO-DVLC):

  1. 1) Compute $k = {{\Vert {{\bf \gamma }(t)} \Vert} / {\Vert {{\bf \beta }(t)} \Vert}}$ for each t ∈ Ω;

  2. 2) Obtain ${\bf C}_d^b $ by solving the constrained optimization problem $\mathop {\min}\limits_{{\bf C} \in SO(3)} \int_\Omega {{{\Vert {k{\bf \beta }(t) - {\bf C\gamma }(t)} \Vert}^2}dt} $ as done in (Wu and Pan, Reference Wu and Pan2013a).

The “ideal observer” will be used to verify the analytic conclusions above.

3. NUMERICAL STUDY

In this section, we carry out numerical simulations to study the validity of the analysis. We will see that the above analysis can explain quite well what we will encounter in practical state observers or estimators. The simulations are designed to mimic the typical motions of a single-thruster propelled underwater vehicle. The 3D trajectory of the vehicle is illustrated in Figure 1 and the motion sequences with time are listed in Table 1. The thruster force is arranged along the vehicle's longitudinal direction (x-axis of the vehicle frame, v-frame, defined as forward-upward-rightward). Onboard the vehicle is an IMU equipped with a triad of gyroscopes (bias 0·01°/h, noise $${0 \cdot 1^{\circ}\!}/h/\sqrt {{\rm Hz}} $$) and accelerometers (bias 50 $\mu$g, noise $10\mu g/\sqrt {{\rm Hz}} $), and a DVL with measurement noise 2 cm/s (1σ). The vehicle v-frame is assumed to align perfectly with the IMU (b-frame), from which the DVL (d-frame) misaligns in attitude by −0·1° (roll), −0·5° (yaw) and −0·2° (pitch). The DVL scale factor is set to 0·9998. The initial attitude of the IMU is set to 3° (roll), 10° (yaw) and zero (pitch).

Figure 1. Moving trajectory of the underwater vehicle (3D run: in blue, 2D run: in red).

Table 1. Motion Sequences with Time.

The DVL output profile and IMU output profile generated by 3D motion sequences in Table 1 are respectively plotted in Figures 2 and 3. As the vehicle moves forward over 600–660 s and downward over 660–720 s, and the vectors of specific force rate (Figure 3) or DVL acceleration on these two segments are linearly independent (Figure 2), the condition of Theorem 1 for Type-I segments is satisfied. The derived IO-DVLC observer in Section 2.3 is used to estimate the DVL scale factor (Figure 4) and misalignment angles (Figure 5). We see that the scale factor is computable at either of two segments, while the misalignment angles, especially the roll angle, cannot converge until the downward segment is carried out at 660 s. These observations have been well predicted already by Remarks 2 and 4, although the IO-DVLC observer is not accurate enough in the misalignment angles.

Figure 2. Profile of DVL outputs with specific time tag.

Figure 3. Profile of IMU gyroscope/accelerometer outputs with specific time tag.

Figure 4. DVL scale factor estimate by ideal observer IO-DVLC.

Figure 5. DVL misalignment angle estimate by ideal observer IO-DVLC (unit: degree).

Next we implement an Extended Kalman Filter (EKF) to estimate the states of the combined IMU/DVL system, of which the system dynamics are given by Equations (3)–(5) and the measurement is given by Equation (7). The EKF is a nonlinear state estimator widely used in numerous applications. In addition to those states in Theorem 1, the EKF also estimates the position. The position is unobservable, but it is correlated with other states through the system dynamics and the determination of other states will help mitigate the position error drift. The first 600 s static segment is used for IMU initial alignment. Additional angle errors of 0·1° (1σ, for yaw) and 0·01° (1σ, for roll and pitch) are added to the final alignment result so as to mimic the influence of non-benign alignment conditions underwater. Figures 6 and 7 respectively present the DVL scale factor estimate and misalignment angle estimate, as well as their standard variances. The scale factor in Figure 6 converges swiftly from the initial value 0·8 to the truth once the vehicle starts to move at 600 s, as are the two misalignment angles, yaw and pitch, in Figure 7. The roll angle approaches its true value when the descending motion starts at 660 s. Apparently, EKF is more accurate than the IO-DVLC observer in estimating the DVL parameters. The inertial sensor bias estimates and their standard variances are presented in Figures 8 and 9. We see that turning on the square trajectory after 750 s drives the accelerometer bias estimate to convergence (Figure 9). The gyroscope bias in Figure 8 is relatively slower in convergence, especially that in vertical direction (y-axis), due to weaker observability. Figures 10 and 11 give the attitude error and positioning error, as well as their standard variances. The normalised standard variances for attitude, gyroscope/accelerometer biases, DVL scale factor and misalignment angles are plotted in Figure 12. It is the DVL scale factor and misalignment angles (yaw and pitch) that have the strongest observability in this simulation scenario. The interaction among states are quite obvious from Figure 12; for example, yaw angle and the DVL roll angle (at 660 s), and roll/pitch angles and the x-axis accelerometer bias(at 750 s). All of the EKF's behaviours accord with Theorem 1.

Figure 6. DVL scale factor estimate and standard variance by EKF.

Figure 7. DVL misalignment angle estimate and standard variance by EKF (unit: °).

Figure 8. Gyroscope bias estimate and standard variance by EKF (unit: °/h)

Figure 9. Accelerometer bias estimate and standard variance by EKF (unit: micro g).

Figure 10. Attitude error and standard variance by EKF (unit: °).

Figure 11. Horizontal position error and standard variance of position estimate by EKF (unit: metre).

Figure 12. Normalised standard variances for attitude, inertial sensor bias, DVL scale factor and misalignment angles.

A 2D trajectory is also examined to verify the analysis of Remark 3. This planar run is similar with the above 3D run, but excludes the descending/ascending segments (as seen in Figure 1 and Table 1). The DVL scale factor and misalignment angle estimates, attitude error and position error by EKF are respectively plotted in Figures 13–16. As predicted by Remarks 2 and 3, all states but the DVL roll angle are estimable. Although the DVL roll angle does not converge (Figure 14) in this case, other states are estimated quite well.

Figure 13. DVL scale factor estimate by EKF in 2D run.

Figure 14. DVL misalignment angle estimate by EKF in 2D run (unit: °).

Figure 15. Attitude error and standard variance by EKF in 2D run (unit: °).

Figure 16. Horizontal position error and standard variance of position estimate by EKF in 2D run (unit: metre).

4. CONCLUSIONS

The development of commercial gyroscope/accelerometer and Doppler sensors has enabled significant improvements to underwater navigation, especially in unexplored areas without artificial beacons. This paper addresses combined IMU/DVL underwater navigation from the viewpoint of the control system. We show by analysis that the combined system is observable under moderate motion conditions. The DVL parameters, such as the scale factor and misalignment angles, especially can be in-situ calibrated without relying on additional external GPS or acoustic beacons. The IMU bias errors can also be effectively estimated, aided by the DVL measurement. These benefits are promising to enable a fully autonomous underwater navigation. We carried out numerical simulations and used a practical EKF to integrate IMU and DVL information. The simulation results accord very well with our analytic conclusions. The essential result also applies to IMU/Doppler laser airborne applications. The analytic result is important and a necessary step to ultimately solve the challenging problem of in-situ IMU/DVL self-calibration. It also provides useful guidance for field test planning and implementation. High quality field test data will be collected in the future and used to verify the proposed IMU/DVL integration scheme in this paper.

FINANCIAL SUPPORT

This work was supported in part by the Fok Ying Tung Foundation (grant number 131061) and National Natural Science Foundation of China (grant number 61174002, 61422311).

APPENDIX

Lemma 1 (Black, Reference Black1964; Shuster and Oh, Reference Shuster and Oh1981): For any two linearly independent vectors, if their coordinates in two arbitrary frames are given, then the attitude matrix between the two frames can be determined.

Lemma 2 (Wu et al., Reference Wu, Zhang, Wu, Hu and Hu2012): Given m known points ai, i = 1,2,…,m, in three-dimensional space satisfying ||ai − x|| = r, where x is an unknown point, r is a positive scalar. If points ai do not lie in any common plane, x has a unique solution.

References

REFERENCES

Black, H. D. (1964). A passive system for determining the attitude of a satellite. AIAA Journal, 2, 13501351.CrossRefGoogle Scholar
Chen, C.-T. (1999). Linear System Theory and Design, Rinehart and Winston, Inc.Google Scholar
Groves, P. D. (2008). Principles of GNSS, Inertial, and Multisensor Integrated Navigation Systems, Artech House, Boston and London.Google Scholar
Hegren, S., Ø. and Berglund, E. (2009). Doppler Water-Track Aided Inertial Navigation for Autonomous Underwater Vehicle. OCEANS 2009 - EUROPE.Google Scholar
Jalving, B., Gade, K., Svartveit, K., Willumsen, A. and Sorhagen, R. (2004). DVL Velocity Aiding in the HUGIN 1000 Integrated Inertial Navigation System. Modeling, Identification and Control, 25, 223236.CrossRefGoogle Scholar
Joyce, T. M. (1989). On in situ calibration of shipboard ADCPs. Journal of Atmospheric and Oceanic Technology, 6, 169172.2.0.CO;2>CrossRefGoogle Scholar
Kinsey, J. C., Eustice, R. M. and Whitcomb, L. L. (2006). A Survey of Underwater Vehicle Navigation: Recent Advances and New Challenges. IFAC Conference of Manoeuvering and Control of Marine Craft.Google Scholar
Kinsey, J. C. and Whitcomb, L. L. (2006). Adaptive Identification on the Group of Rigid-Body Rotations and its Application to Underwater Vehicle Navigation. IEEE Transactions on Robotics, 23, 124136.CrossRefGoogle Scholar
Kinsey, J. C. and Whitcomb, L. L. (2007). In Situ Alignment Calibration of Attitude and Doppler Sensors for Precision Underwater Vehicle Navigation: Theory and Experiment. IEEE Journal of Oceanic Engineering, 32, 286299.CrossRefGoogle Scholar
Li, W., Tang, K., Lu, L. and Wu, Y. (2013). Optimization-based INS in-motion alignment approach for underwater vehicles. Optik - International Journal for Light Electron Optics, in press.CrossRefGoogle Scholar
Savage, P. G. (2007). Strapdown Analytics, Strapdown Analysis.Google Scholar
Shuster, M. D. and Oh, S. D. (1981). Three-axis attitude determination from vector observations. Journal of Guidance, Control, and Dynamics, 4, 7077.CrossRefGoogle Scholar
Silson, P. M. G. (2011). Coarse Alignment of a Ship's Strapdown Inertial Attitude Reference System Using Velocity Loci. IEEE Trans. on Instrumentation and Measurement, 60, 19301941.CrossRefGoogle Scholar
Tang, K., Wang, J., Li, W. and Wu, W. (2013). A Novel INS and Doppler Sensors Calibration Method for Long Range Underwater Vehicle Navigation. Sensors, 13, 1458314600.CrossRefGoogle ScholarPubMed
Tang, Y., Wu, Y., Wu, M., Wu, W., Hu, X. and Shen, L. (2009). INS/GPS integration: global observability analysis. IEEE Trans. on Vehicular Technology, 58, 11291142.CrossRefGoogle Scholar
Titterton, D. H. and Weston, J. L. (2004). Strapdown Inertial Navigation Technology, the Institute of Electrical Engineers, London, United Kingdom, 2nd Ed.CrossRefGoogle Scholar
Troni, G., Kinsey, J. C., Yoerger, D. R. and Whitcomb, L. L. (2012). Field Performance Evaluation of New Methods for In-Situ Calibration of Attitude and Doppler Sensors for Underwater Vehicle Navigation. IEEE International Conference on Robotics and Automation.CrossRefGoogle Scholar
Troni, G. and Whitcomb, L. L. (2010). New Methods for In-Situ Calibration of Attitude and Doppler Sensors for Underwater Vehicle Navigation: Preliminary Results. OCEANS 2010. Seattle, WA.CrossRefGoogle Scholar
Whitcomb, L., Yoerger, D. and Singh, H. (1999). Advances in Doppler-based navigation of underwater robotic vehicles. IEEE International Conference on Robotics and Automation.CrossRefGoogle Scholar
Wu, Y. and Pan, X. (2013a). Velocity/Position Integration Formula (I): Application to In-flight Coarse Alignment. IEEE Transactions on Aerospace and Electronic Systems, 49, 10061023.CrossRefGoogle Scholar
Wu, Y. and Pan, X. (2013b). Velocity/Position Integration Formula (II): Application to Strapdown Inertial Navigation Computation. IEEE Transactions on Aerospace and Electronic Systems, 49, 10241034.CrossRefGoogle Scholar
Wu, Y., Wang, J. and Hu, D. (2014). A New Technique for INS/GNSS Attitude and Parameter Estimation Using Online Optimization. IEEE Transactions on Signal Processing, 62, 26422655.CrossRefGoogle Scholar
Wu, Y., Wu, M., Hu, X. and Hu, D. (2009). Self-calibration for Land Navigation Using Inertial Sensors and Odometer: Observability Analysis. AIAA Guidance, Navigation and Control Conference. Chicago, Illinois, USA.CrossRefGoogle Scholar
Wu, Y., Zhang, H., Wu, M., Hu, X. and Hu, D. (2012). Observability of SINS Alignment: A Global Perspective. IEEE Transactions on Aerospace and Electronic Systems, 48, 78102.Google Scholar
Figure 0

Figure 1. Moving trajectory of the underwater vehicle (3D run: in blue, 2D run: in red).

Figure 1

Table 1. Motion Sequences with Time.

Figure 2

Figure 2. Profile of DVL outputs with specific time tag.

Figure 3

Figure 3. Profile of IMU gyroscope/accelerometer outputs with specific time tag.

Figure 4

Figure 4. DVL scale factor estimate by ideal observer IO-DVLC.

Figure 5

Figure 5. DVL misalignment angle estimate by ideal observer IO-DVLC (unit: degree).

Figure 6

Figure 6. DVL scale factor estimate and standard variance by EKF.

Figure 7

Figure 7. DVL misalignment angle estimate and standard variance by EKF (unit: °).

Figure 8

Figure 8. Gyroscope bias estimate and standard variance by EKF (unit: °/h)

Figure 9

Figure 9. Accelerometer bias estimate and standard variance by EKF (unit: micro g).

Figure 10

Figure 10. Attitude error and standard variance by EKF (unit: °).

Figure 11

Figure 11. Horizontal position error and standard variance of position estimate by EKF (unit: metre).

Figure 12

Figure 12. Normalised standard variances for attitude, inertial sensor bias, DVL scale factor and misalignment angles.

Figure 13

Figure 13. DVL scale factor estimate by EKF in 2D run.

Figure 14

Figure 14. DVL misalignment angle estimate by EKF in 2D run (unit: °).

Figure 15

Figure 15. Attitude error and standard variance by EKF in 2D run (unit: °).

Figure 16

Figure 16. Horizontal position error and standard variance of position estimate by EKF in 2D run (unit: metre).