Hostname: page-component-745bb68f8f-lrblm Total loading time: 0 Render date: 2025-02-11T05:41:56.278Z Has data issue: false hasContentIssue false

A Passive Acoustic Positioning Algorithm Based on Virtual Long Baseline Matrix Window

Published online by Cambridge University Press:  02 August 2018

Tao Zhang*
Affiliation:
(Southeast University, Nanjing, School of Instrument Science and Engineering, Key Laboratory of Micro-Inertial Instrument and Advanced Navigation Technology of Ministry of Education, Nanjing 210096, China)
Ziqiang Wang
Affiliation:
(Southeast University, Nanjing, School of Instrument Science and Engineering, Key Laboratory of Micro-Inertial Instrument and Advanced Navigation Technology of Ministry of Education, Nanjing 210096, China)
Yao Li
Affiliation:
(Southeast University, Nanjing, School of Instrument Science and Engineering, Key Laboratory of Micro-Inertial Instrument and Advanced Navigation Technology of Ministry of Education, Nanjing 210096, China)
Jinwu Tong
Affiliation:
(Southeast University, Nanjing, School of Instrument Science and Engineering, Key Laboratory of Micro-Inertial Instrument and Advanced Navigation Technology of Ministry of Education, Nanjing 210096, China)
Rights & Permissions [Opens in a new window]

Abstract

A new acoustic positioning method for Autonomous Underwater Vehicles (AUV) that uses a single underwater hydrophone is proposed in this paper to solve problems of Long Baseline (LBL) array laying and communication synchronisation problems among all hydrophones in the traditional method. The proposed system comprises a Strapdown Inertial Navigation System (SINS), a single hydrophone installed at the bottom of the AUV and a single underwater sound source that emits signals periodically. A matrix of several virtual hydrophones is formed with the movement of the AUV. In every virtual LBL window, the time difference from the transmitted sound source to each virtual hydrophone is obtained by means of a Smooth Coherent Transformation (SCOT) weighting cross-correlation in the frequency domain. Then, the recent location of the AUV can be calculated. Simulation results indicate that the proposed method can effectively compensate for the position error of SINS. Thus, the positioning accuracy can be confined to 2 m, and the method achieves good applicability. Compared with traditional underwater acoustic positioning systems, the proposed method can provide great convenience in engineering implementation and can reduce costs.

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

1. INTRODUCTION

Autonomous Underwater Vehicles (AUVs) play important roles in ocean pollution monitoring and seabed, marine mineral and oil resources investigation due to their advantages, which include unmanned operation, the capability to enter narrow underwater environments and relatively low cost (Choi et al., Reference Choi, Lee, Hong, Suh and Kim2015; Ji et al., Reference Ji, Zhang, Wang and Zheng2014; Yu and Wu, Reference Yu and Wu2015; Zhong et al., Reference Zhong, Xia and He2015).

Highly accurate underwater navigation and positioning technologies are required for AUVs to accomplish these missions (Zhang et al., Reference Zhang, Xu, Li and Gong2013). In terms of current navigation technologies, integrated navigation systems of underwater acoustic and Inertial Navigation Systems (INSs) are widely used for AUVs (Zhang et al., Reference Zhang, Shi, Chen, Li and Tong2016b). Although INSs have autonomous characteristics and are useful when concealment is required, their errors increase with time and limit their continuity (Morgado et al., Reference Morgado, Batista, Oliveira and Silvestre2010). To achieve a high positioning precision over longer periods, INSs are required to use other external information to periodically correct the position errors during navigation (Paull et al., Reference Paull, Seto and Li2014; Deng et al., Reference Deng, Bao and Zhao2009; Mahdinejad and Seghaleh, Reference Mahdinejad and Seghaleh2013). Global Navigation Satellite Systems (GNSS) and other radio signals cannot be used underwater due to their rapid attenuation that requires AUVs to float toward the water surface to receive satellite signals for positioning (Jiao et al., Reference Jiao, Li and Men2013; An et al., Reference An, Chen and Fang2013; Barisic et al., Reference Barisic, Miskovic and Vasilijevic2012). These conditions seriously reduce system efficiency, expose the current position of AUVs and influence the real-time characteristics of information interaction. Therefore, accurate navigation technologies are key factors in AUV development (Ferreira et al., Reference Ferreira, Matos and Cruz2010).

Compared with electromagnetic waves, the attenuation rate of sound waves in the ocean is low so that they can spread over long distances (Ngatini et al., Reference Ngatini, Apriliani and Nurhadi2016). Long baseline positioning methods are used worldwide. Paull et al. (Reference Paull, Seto and Li2014) summarised the recent advances of underwater vehicle navigation and positioning and introduced several traditional methods (Ji et al., Reference Ji, Song, Zhao and Liu2016). Donovan (Reference Donovan2012) adopted integrated tests and a real-time terrain particle filter framework to complete the positioning and navigation of AUVs. Lee et al. (Reference Lee, Huan, Choi and Hong2005) optimised the number of transponders that simplified the matrix model. Maki et al. (Reference Maki, Matsuda, Sakamaki, Ura and Kojima2013) proposed a method that estimates the position and direction of underwater vehicles by using a single bottom station without expensive INSs or time-consuming calibration. Miller et al. (Reference Miller, Farrell, Zhao and Djapic2010) established a type of positioning system using a tight LBL/Doppler Velocity Log (DVL)/INS integration method, which is suitable for AUV positioning in a complicated deep sea environment. These studies proposed several valuable solutions that were based on long baseline systems and promoted the application of underwater acoustic positioning worldwide.

However, several limitations of Long Baselines (LBL) were reported in the literature. Zhang (Reference Zhang, Han, Zheng and Sun2016a) indicated a series of engineering implementation problems, such as the number of transponders being so large that they complicated the matrix system and made the laying, calibrating and recalling processes tedious. Casalino et al. (Reference Casalino, Simetti, Sperindè and Torelli2014) used buoys rather than traditional seabed transponders. However, several instability errors were introduced in this method because the positions of the buoys were unfixed and the buoys thus floated in the sea; in addition, their positions were frequently calibrated, leading to increased workload. In Zhang et al. (Reference Zhang, Chen and Li2015), acoustic signals were received from different transponders at different periods, and a synchronising technology was required before processing all the signals from different transponders. In addition, the method mentioned in Zhang et al. (Reference Zhang, Chen and Li2015) allowed AUVs to be easily monitored by others and reduced their concealment.

To solve these problems, we have designed a passive acoustic positioning method based on a virtual LBL matrix window algorithm that uses a single sound source. This method does not require AUVs to float toward the surface to update their location and offers high concealment and safety. This method also reduces the difficulty in releasing transponders because only one sound source is placed at the bottom of the sea and one hydrophone is installed at the bottom of the AUV. In addition, all received signals can be directly processed by the computer embedded in the AUV without time synchronisation and then returned to the AUV for processing. Thus, the complexity and cost are significantly reduced. Moreover, the virtual LBL matrix window method can be used to estimate AUV position through a few time windows. This method does not require a large number of data points and guarantees a good real-time performance. The accuracy increases with the number of iterations of the matrix window. Therefore, this method provides a new concept for AUV positioning.

2. SYSTEM PRINCIPLE AND STRUCTURE

2.1. Formation of virtual LBL matrix window

The proposed method in this study is based on a virtual LBL matrix window. In this system, a single sound source is placed at the bottom of the sea and sends periodic signals and a single hydrophone is installed on the AUV. In the AUV navigation trajectory, four selected recent positions of the AUV are regarded as four virtual hydrophones of the LBL matrix, which constitute a virtual LBL matrix window, as shown in Figure 1.

Figure 1. Formation of virtual LBL matrix.

2.2. Positioning algorithm based on a moving virtual LBL matrix window

In this method, the single sound source is fixed on the seabed in which its absolute position is measured as (x, y, z) in advance in Earth-centred Earth-fixed coordinates. This sound source sends periodic pulse signals at regular intervals, with the time period defined as Ts. A virtual LBL matrix window is created when the AUV enters the area where the source signal can be received. The current position of the AUV is set as the initial position P 0, where the period of receiving acoustic signals is denoted as x0. Then, the AUV continues to move forward, and its position is denoted as P 1 at the beginning of the eleventh period. A period of receiving acoustic signals is denoted as x1. In this way, the AUV position is denoted as P i(i = 2, 3,···), and the receiving acoustic signal is denoted as xi(i = 2, 3,···) for every ten periods. Each of the four consecutive positions of the AUV forms a virtual LBL matrix window. For example, the first virtual LBL matrix window is composed of the initial four positions (P 0, P 1, P 2, P 3), which are marked by the blue rectangle in Figure 2. The second virtual LBL window is formed by removing position P 0 and adding position P 4 when the AUV arrives at position P 4; this window is shown as the red rectangle in Figure 2. In this way, the moving virtual LBL windows are established by removing the previous position and adding the more recent position to iteratively calculate the current position of the AUV.

Figure 2. Time window model based on periodic movement.

3. ALGORITHM IMPLEMENTATION

3.1. Iterative updating of position based on moving virtual LBL windows

Considering that the same algorithm is used to calculate the position of the AUV based on each window, we describe the calculation method for the AUV by taking the first window as an example.

The initial position of the AUV is denoted as P 0(x 0, y 0, z 0) in the inertial coordinate system. From the above description, each new position of the AUV is obtained every 10Ts, for example, P 1(x 1, y 1, z 1), P 2(x 2, y 2, z 2) and P 3(x 3, y 3, z 3). The four positions form the first virtual LBL matrix window. The distances between position P i(i = 0, 1, 2) and P 3 in the three-axis direction (x, y, z) are defined as Δ x 3i, Δ y 3i and Δz 3i respectively; their values can be measured by dead reckoning using INS. P i can be described by recent position P 3 as follows; its position is considered unknown and should be calculated:

(1)$$\left\{\matrix{\lpar x_{0}{,y}_{0}{,z}_{0} \rpar = \lpar \lpar x_{3}{-\Delta x}_{30} \rpar ,\lpar y_{3}{-\Delta y}_{30} \rpar ,\lpar z_{3}{-\Delta z}_{30} \rpar \rpar \hfill \cr \lpar x_{1}{,y}_{1}{,z}_{1} \rpar =\lpar \lpar x_{3}{-\Delta x}_{31} \rpar , \lpar y_{3}{-\Delta y}_{31} \rpar , \lpar z_{3}{-\Delta z}_{31} \rpar \rpar \hfill \cr \lpar x_{2}{,y}_{2}{,z}_{2} \rpar = \lpar \lpar x_{3}{-\Delta x}_{32} \rpar , \lpar y_{3}{-\Delta y}_{32} \rpar , \lpar z_{3}{-\Delta z}_{32} \rpar \rpar \hfill}\right.$$

Time difference τ3i of the received signal at positions P3 and P i can be obtained through a cross-correlation operation. Two factors lead to the time difference. The first factor is the difference in geographic location (Δ t 3i), and the second factor is the time interval of the sent signal, as indicated in Equation (2):

(2)$${\Delta t}_{3i} = \tau_{3i} - \lpar 30-10i \rpar t, \quad \lpar {\hbox{i} = 0,1,2} \rpar $$

The sound propagation velocity underwater is assumed to be a constant value denoted as c, and three equations are established as follows:

(3)$$\left\{\matrix{{\Delta t}_{30}c = \sqrt {{(x_{3}-x)}^{2}+{(y_{3}-y)}^{2}+{(z_{3}-z)}^{2}}\hfill \cr -\,\sqrt {{(x_{0}-x)}^{2}+{(y_{0}-y)}^{2}+{(z_{0}-z)}^{2}} \hfill \cr {\Delta t}_{31}c = \sqrt {{(x_{3}-x)}^{2}+{(y_{3}-y)}^{2}+{(z_{3}-z)}^{2}} \hfill \cr -\,\sqrt {{(x_{1}-x)}^{2}+{(y_{1}-y)}^{2}+{(z_{1}-z)}^{2}} \hfill \cr {\Delta t}_{32}c=\sqrt {{(x_{3}-x)}^{2}+{(y_{3}-y)}^{2}+{(z_{3}-z)}^{2}} \hfill \cr -\,\sqrt {{(x_{2}-x)}^{2}+{(y_{2}-y)}^{2}+{(z_{2}-z)}^{2}}\hfill}\right.$$

(x 0, y 0, z 0),(x 1, y 1, z 1) and (x 2, y 2, z 2) can be expressed as expressions that contain (x 3, y 3, z 3) through Equation (1), and recent position P3(x 3, y 3, z 3) can be calculated by Equation (3). Subsequently, the recent geodetic coordinates can be obtained through the coordinate transformation of latitude and longitude.

The AUV coordinates in the geodetic coordinate and Earth rectangular coordinate systems are set as (λ, L, H) and (x, y, z), respectively. The formula for converting the geodetic coordinates into the Earth frame's rectangular coordinates is expressed as follows:

$$\left\{\matrix{x = \lpar N + H \rpar cosLcos\lambda \hfill \cr y = (N + H) cosLsin \lambda \hfill \cr z = [N\lpar \hbox{1-}e^{2} \rpar +H] sinL} \right.$$

where e is the first eccentricity and N is the radius of the unitary circle at latitude L.

$$N = a / \sqrt{\lpar \hbox{1-}e^{{\rm 2}}{sin}^{{\rm 2}}L \rpar }$$

where a is the long semi-axis of the Earth.

Therefore, the formula for converting the Earth's rectangular coordinates to geodetic coordinates is:

$$\left\{\matrix{\lambda = arctan (y / x) \hfill \cr L = \hbox{arctan} \left(\displaystyle{z+be_{{2}}^{{2}}{sin}^{{\rm 3}}U \over \sqrt{x^{{\rm 2}}+y^{{\rm 2}}} -ae^{{2}}{cos}^{{\rm 3}}U}\right)\hfill \cr H = \sqrt {x^{{\rm 2}}+y^{{\rm 2}}} / {cosL-N} \hfill} \right.$$

Among the coordinates, b is the short semi-axis of the Earth and e 2 is the second eccentricity, where $U=arctan\left(z / {\sqrt{x^{{\rm 2}}+y^{{\rm 2}}} \sqrt {\hbox{1-}e^{{\rm 2}}}} \right)$.

The first and second virtual LBL windows are used as examples to explain the iterative updating of the AUV position. The AUV continues to move and obtains the current position P 4(x 4, y 4, z 4) after 10Ts when the recent position P3(x3, y 3, z 3) is obtained. P 0(x 0, y 0, z 0) is removed from the window and P4 is added in the new window with positions P1, P2 and P3. The AUV updates the current position by using this method, which corrects the errors of the SINS.

3.2. Calculation of Time Difference of Arrival (TDOA)

A TDOA positioning method provides the sound source position by measuring the TDOA at different targets from the sound source. Given the difficulty of synchronising underwater signals, the time difference is easy to obtain through the cross-correlation processing of the received signals.

Assuming that the received signals at positions Pi and Pj are:

(4)$$\matrix{\hbox{x}_{i}=\hbox{a}_{i}x\lpar t-{\rm \tau }_{i} \rpar +\hbox{n}_{i}{\rm (}t{\rm )} \cr \hbox{x}_{j}=\hbox{a}_{j}x\lpar t-{\rm \tau }_{j} \rpar +\hbox{n}_{j}{\rm (}t{\rm )}\hfill}$$

where ai and aj are the attenuation coefficients of the acoustic signals that propagate underwater, ni(t) and nj(t) are the uncorrelated noise signals and τi, τj are the propagation times.

The cross-correlation function of x i(t) and xj(t) is:

(5)$$\hbox{R}_{{\rm x}_{i}{\rm x}_{j}} ({\rm \tau}) {\rm =E} [\hbox{x}_{i} (\hbox{t}) \hbox{x}_{j}^{\ast} (\hbox{t}-\tau)] = \displaystyle{1 \over \hbox{T}-\tau} \int_{\rm \tau}^{\rm T} \hbox{x}_{i} (\hbox{t}) \hbox{x}_{j} (\hbox{t}-\tau) \hbox{dt}$$

where τ = τ j − τ i indicates the TDOA signals and T denotes the observation time. In theory, the peak of $\hbox{R}_{{\rm x}_{i}{\rm x}_{j}}$ corresponds to the time difference of x i(t) and xj(t), which is τ.

3.3. Smooth Coherent Transformation (SCOT)-weighted generalised cross-correlation

As a result of complicated underwater environments, refractions and reflections are common, and they are called multipath effects. Figure 3 shows a simplified multipath channel model of underwater acoustic propagation, in which only the direct propagation path (P iD,(i=1, 2, … )), reflection propagation path of the sea surface (P iS,(i=1, 2, …)) and reflection propagation path of the seabed (P iB,(i=1, 2, …)) are considered. In addition, noise exists in the underwater environment, and includes the radiated noise of the AUV, oceanic reverberation and other factors that interfere with acoustic signals. This condition results in a number of similar peaks that correspond to different time differences. However, the positioning error is amplified after the time differences are multiplied by the speed of the acoustic propagation (Deng et al., Reference Deng, Bao and Zhao2009).

Figure 3. Simplified channel mode for underwater acoustic multipath propagation.

Mahdinejad and Seghaleh (Reference Mahdinejad and Seghaleh2013) used a different weighted generalised cross-correlation method to calculate time delays and compared the experimental results in a reverberation room under an acoustic environment. They determined that the SCOT-weighted generalised cross-correlation algorithm obtains good results in acoustic signal processing and time delay estimation, and this method has better accuracy and precision than other methods. In this study, the SCOT-weighted generalised cross-correlation is used to make the relevant peaks prominent to effectively enhance the spectral component of the source signal in the received signal. Therefore, the signal-to-noise ratio is improved, and the cross-correlation function is enhanced. These improvements increase the accuracy of the estimation of the time difference.

The received signals of the hydrophone at positions Pi and Pj are transformed from the time domain into the frequency domain by using Fourier transformation:

(6)$$\matrix{F_{x_{i}}\lpar \omega \rpar =\int_{-\infty }^{+\infty } {x_{i}\lpar t \rpar } e^{-j\omega t}dt\cr F_{x_{j}}\lpar \omega \rpar =\int_{-\infty }^{+\infty } {x_{j}\lpar t \rpar } e^{-j\omega t}dt}$$

The function of cross-power spectral density is obtained by the following equation:

(7)$$G_{x_{i}x_{j}}\lpar \omega \rpar = F_{x_{i}}\lpar \omega \rpar F_{x_{j}}^{\ast }\lpar \omega \rpar $$

where $F_{x_{j}}^{\ast} \lpar \omega \rpar $ is the conjugate of $F_{x_{j}}\lpar \omega \rpar $.

According to the theorem of Wiener-Khinchin (Cohen, Reference Cohen1998), the relationship between the function of cross-power spectral density and cross correlation is:

(8)$$R_{x_{i}x_{{\rm j}}}\lpar \tau \rpar =\int_0^\pi {G_{x_{i}x_{j}}\lpar \omega \rpar } e^{-j\omega \tau }d\omega$$

To reduce the multipath interference and noise in the selection of correct correlation peaks, the received signals are processed by the above mentioned SCOT-weighted method. Signals xi and xj are passed through a pre-filter, and the SCOT-weighted general cross-correlation operation is performed on the pre-filtered signals. The cross-correlation function based on weighted function $\varphi_{x_{i}x_{j}}\lpar \omega \rpar $ in the frequency domain is:

(9)$$R_{x_{i}x_{{\rm j}}} \lpar \tau \rpar = \int_{\rm 0}^{\pi} \varphi_{x_{i} x_{j}} \lpar \omega \rpar G_{x_{i} x_{j}} \lpar \omega \rpar e^{-j\omega \tau} d \omega$$

The flow chart of the SCOT-weighted generalised cross correlation is shown in Figure 4.

Figure 4. Flow chart of the SCOT frequency domain-weighted generalised cross-correlation algorithm.

The SCOT-weighted generalised cross-correlation function improves the proportion of effective spectra in the received signal, which suppresses the noise interference and improves the accuracy of the estimated time difference. The abscissa value that corresponds to the maximum peak in the SCOT-weighted generalised cross-correlation function is the time difference τ.

4. SYSTEM SIMULATION AND SEMI-PHYSICAL EXPERIMENT

4.1. Simulation to verifying the validity of the SCOT weighted function

The Bellhop model (Michael, Reference Michael2011) is widely used in underwater acoustic channel simulation. This model is equally effective in channel analysis and modelling. It simulates underwater environment noise, multipath effects, and Doppler frequency shifts by introducing sound field data. It thus forms a real channel model and obtains various practical data, such as eigen line, impulse response, propagation loss and arrival time sequence of sound.

To verify the validity of the SCOT-weighted cross-correlation function in the frequency domain, we performed simulations and compare the method with traditional cross-correlation methods by establishing a propagation model of underwater acoustic signals using the Bellhop software. The sound source signal was selected as a type of amplitude modulation signal with a bandwidth of 40 kHz and a centre frequency of 22 kHz. The sound source was placed at a depth of 50 m, and two hydrophones were placed at a depth of 25 m underwater at different locations. The results of the two methods of cross-correlation functions are shown in Figures 5 and 6. The simulations were conducted three times, and the results are subsequently compared (Table 1).

Figure 5. Basic cross-correlation function in simulation.

Figure 6. SCOT-weighted cross-correlation function in simulation.

Table 1. Comparisons of time difference errors in simulations.

Figures 5 and 6 and Table 1 show that the SCOT-weighted cross-correlation function in the frequency domain reduces the amplitude of pseudo-peaks near the ideal peak that corresponds to the time difference by eliminating the inference of multiple correlation peaks caused by the multipath propagation effect. The result reveals that the time difference estimated by this method is more accurate than that obtained by the traditional method.

4.2. Semi-physical experiment to verify the validity of the SCOT-weighted function

To evaluate the performance of the above method, we conducted a semi-physical experiment involving an ultrasonic sound source and five receivers in an open space with low noise. The four receivers formed a square shape with a side length of 5 m, and the remaining receiver was placed in the centre of the square. The equipment layout is shown in Figure 7, and the experimental environment is shown in Figure 8.

Figure 7. Equipment layout.

Figure 8. Experimental environment.

The sound source signal is a type of pulse signal with a frequency of 40 kHz and a pulse width of 20 ms. The traditional cross-correlation and SCOT-weighted cross-correlation methods in the frequency domain were applied for the signals received by two receivers. The results are shown in Figures 9 and 10 and Table 2.

Figure 9. Semi-physical basic cross-correlation function graph.

Figure 10. Semi-physical SCOT-weighted cross-correlation function graph.

Table 2. Comparison of time difference errors in the semi-physical experiment.

Table 3. Rocking parameters of the AUV.

The result of the traditional cross-correlation method reveals several pseudo-peaks with similar peaks. By contrast, the SCOT-weighted cross-correlation method in the frequency domain effectively reduces all the amplitudes of the pseudo-peaks and attains the maximum peak. The results of the semi-physical experiment show that the SCOT-weighted cross-correlation method significantly enhances the real correlation peak and effectively estimates the time difference.

4.3. Simulation of dynamic positioning

A simulation was conducted to verify the dynamic positioning effect of the time window model based on periodic movement. A single sound source was placed at a longitude of 120 · 01°, latitude of 40° and depth of 50 m. The sound source transmitted the pulse signal with a frequency of 0·025 Hz and a pulse width of 100 ms. The AUV moved along the northeast direction from its initial position of 119·995° longitude and 32·995° latitude at the speed of 1 m/s and depth of 25 m. The AUV swung in accordance with the three-axis sine model. The random and constant drifts of the gyroscopes were 0·05° h, and the random and constant biases of the accelerometers were 50 μg. The initial misalignment angles at the three axes were 1·5° and the period of the time window was set as 400 s. The simulation time was 3,600 s. In the simulation, the AUV position was estimated only on the basis of the SINS for the first 1,200 s. The algorithm based on a virtual LBL matrix window was introduced to calculate the position for the remaining 2,400 s.

Three algorithms, namely the algorithms based on SINS with no LBL aiding, virtual LBL matrix window using traditional cross-correlation function and SCOT-weighted cross-correlation function in the frequency domain, are compared in Figure 11. Table 4 shows the positioning errors of the three algorithms. As shown in Figure 11 and Table 4, the position obtained by SINS significantly deviates from the real trajectory. This result indicates that the accumulated errors of inertial sensors have a considerable influence on the positioning accuracy of the AUV. In the initial stage of the algorithm based on the virtual LBL matrix window, the accuracy of the position is rapidly obtained to within 3 m. The positioning accuracy was improved as the number of iterations increased for the virtual LBL matrix window algorithm. The positioning result became accurate and reliable when the number of iterations reached four and five. Then, the positioning error gradually increases because the distance from the AUV to the sound source becomes large. Compared with the traditional cross-correlation function, the SCOT-weighted cross-correlation function in the frequency domain performs better and meets the high accuracy requirements of underwater vehicle navigation positioning.

Figure 11. Comparison of two tracks with the ideal track.

Table 4. Comparison of pure inertia and acoustic cycle time window distance error.

5. CONCLUSION

Underwater acoustic positioning technologies have been investigated, and a virtual LBL matrix window method based on a SCOT-weighted cross-correlation function in the frequency domain proposed. A single hydrophone was installed at the bottom of the AUV, and a sound source was placed on the seabed. This set-up avoids the placement of a long and complex baseline array and reduces the cost. The proposed method also solves the problem of data communication and signal synchronisation underwater and enhances the concealment of AUVs. The experimental results show that the SCOT-weighted cross-correlation function calculates the time difference more accurately than the traditional cross-correlation function. Therefore, the algorithm based on a virtual LBL matrix window can provide precise underwater position at an accuracy of approximately 2 m.

ACKNOWLEDGEMENTS

The author would like to thank the support in part by the National Natural Science Foundation of China (Grant no. 51375088), Inertial Technology Key Lab Fund, the Fundamental Research Funds for the Central Universities (2242015R30031, 2242018K40065, 2242018K40066), the Foundation of Shanghai Key Laboratory of Navigation and Location Based Services.

References

REFERENCES

An, L., Chen, L. J. and Fang, S. L. (2013). Investigation on Correlation Peaks Ambiguity and Ambiguity Elimination Algorithm in Underwater Acoustic Passive Localization. Journal of Electronics & Information Technology, 35(12), 29482953.Google Scholar
Barisic, M., Miskovic, N. and Vasilijevic, A. (2012). Fusing Hydroacoustic Absolute Position Fixes With AUV On-Board Dead Reckoning. IFAC Proceedings Volumes, 45(22), 211217.Google Scholar
Casalino, A. T. G., Simetti, E., Sperindè, A. and Torelli, S. (2014). Impact of LBL Calibration on the Accuracy of Underwater Localization. IFAC Proceedings Volumes, 47(3), 33763381.Google Scholar
Choi, Y. H., Lee, J. W., Hong, S. H., Suh, J. H. and Kim, J. G. (2015). The development of the modular autonomous underwater navigation system based on OPRoS. International Conference on Ubiquitous Robots and Ambient Intelligence. IEEE, 625628.Google Scholar
Cohen, L. (1998). The generalization of the Wiener-Khinchin theorem. IEEE Signal Processing Letters, 5(11), 292294.Google Scholar
Deng, A. D., Bao, Y. Q. and Zhao, L. (2009). Research on Time Delay Estimation Algorithm Based on Generalized Cross Correlation in Acoustic Emission Source Location. Proceedings of the CSEE, 29(14), 8692.Google Scholar
Donovan, G. T. (2012). Position Error Correction for an Autonomous Underwater Vehicle Inertial Navigation System (INS) Using a Particle Filter. IEEE Journal of Oceanic Engineering, 37(3), 431445.Google Scholar
Ferreira, B., Matos, A. and Cruz, N. (2010). Estimation approach for AUV navigation using a single acoustic beacon. Sea Technology, 51(12), 5459.Google Scholar
Ji, C. L., Zhang, N., Wang, H. H. and Zheng, C. E. (2014). Application of Kalman Filter in AUV Acoustic Navigation. Applied Mechanics & Materials, 525, 695701.Google Scholar
Ji, D. X., Song, W., Zhao, H. Y. and Liu, J. (2016). Deep Sea AUV Navigation Using Multiple Acoustic Beacons. China Ocean Engineering (English Edition), 30(2), 309318.Google Scholar
Jiao, X. T., Li, J. C. and Men, L. J. (2013). Accuracy Analysis of Two TDOA Algorithms in Passive Underwater Acoustic Positioning. Audio Engineering, 37(1), 7375.Google Scholar
Lee, P. M., Huan, J. B., Choi, H. T. and Hong, S. W. (2005). An integrated navigation systems for underwater vehicles based on inertial sensors and pseudo LBL acoustic transponders. Oceans. Washington, DC, USA, IEEE, 1, 555562.Google Scholar
Mahdinejad, K. and Seghaleh, M. Z. (2013). Implementation of time delay estimation using different weighted generalized cross correlation in room acoustic environments. Life Science Journal, 10(6S), 846851.Google Scholar
Maki, T., Matsuda, T., Sakamaki, T., Ura, T. and Kojima, J. (2013). Navigation Method for Underwater Vehicles Based on Mutual Acoustical Positioning With a Single Seafloor Station. IEEE Journal of Oceanic Engineering, 38(1), 167177.Google Scholar
Michael, B. P. (2011). The BELLHOP Manual and User's Guide: PRELIMINARY DRAFT. Heat, Light, and Sound Research, Inc.Google Scholar
Miller, P. A., Farrell, J. A., Zhao, Y. Y. and Djapic, V. (2010). Autonomous underwater vehicle navigation. IEEE Journal of Oceanic Engineering, 35(3), 663678.Google Scholar
Morgado, M., Batista, P., Oliveira, P. and Silvestre, V. (2010). Position USBL/DVL sensor-based navigation filter in the presence of unknown ocean currents. Automatica, 47(12), 26042614.Google Scholar
Ngatini, , Apriliani, E. and Nurhadi, H. (2016). Ensemble and Fuzzy Kalman Filter for Position Estimation of an Autonomous Underwater Vehicle Based on Dynamical System of AUV Motion. Expert Systems with Applications, 68, 2935.Google Scholar
Paull, L., Saeedim S., Seto, M. and Li, H. (2014). AUV Navigation and Localization: A Review. IEEE Journal of Oceanic Engineering, 39(1), 131149.Google Scholar
Yu, P. and Wu, B. (2015). The optimal design of long baseline acoustic positioning array. Ship Electronic Engineering, 35(5), 125129.Google Scholar
Zhang, J. C., Han, Y. F., Zheng, C. and Sun, D. (2016a). Underwater target localization using long baseline positioning system. Applied Acoustics, 111, 129134.Google Scholar
Zhang, T., Chen, L. P. and Li, Y. (2015). AUV Underwater Positioning Algorithm Based on Interactive Assistance of SINS and LBL. Sensors, 16(1), 4264.Google Scholar
Zhang, T., Shi, H. F., Chen, L. P., Li, Y. and Tong, J. W. (2016b). AUV Positioning Method Based on Tightly Coupled SINS/LBL for Underwater Acoustic Multipath Propagation. Sensors, 16(3), 357373.Google Scholar
Zhang, T., Xu, X., Li, Y. and Gong, S. P. (2013). AUV fault tolerant navigation technology based on ins and underwater acoustic assistance system. Chinese Journal of Inertial Technology, 21(4), 512516.Google Scholar
Zhong, S., Xia, W. and He, Z. S. (2015). Multipath Time Delay Estimation Based on Gibbs Sampling under Incoherent Reception Environment. IEICE Transactions on Fundamentals of Electronics Communications & Computer Sciences, E98.A(6), 13001304.Google Scholar
Figure 0

Figure 1. Formation of virtual LBL matrix.

Figure 1

Figure 2. Time window model based on periodic movement.

Figure 2

Figure 3. Simplified channel mode for underwater acoustic multipath propagation.

Figure 3

Figure 4. Flow chart of the SCOT frequency domain-weighted generalised cross-correlation algorithm.

Figure 4

Figure 5. Basic cross-correlation function in simulation.

Figure 5

Figure 6. SCOT-weighted cross-correlation function in simulation.

Figure 6

Table 1. Comparisons of time difference errors in simulations.

Figure 7

Figure 7. Equipment layout.

Figure 8

Figure 8. Experimental environment.

Figure 9

Figure 9. Semi-physical basic cross-correlation function graph.

Figure 10

Figure 10. Semi-physical SCOT-weighted cross-correlation function graph.

Figure 11

Table 2. Comparison of time difference errors in the semi-physical experiment.

Figure 12

Table 3. Rocking parameters of the AUV.

Figure 13

Figure 11. Comparison of two tracks with the ideal track.

Figure 14

Table 4. Comparison of pure inertia and acoustic cycle time window distance error.