Next Article in Journal
Tidal and Ocean Current Energy
Next Article in Special Issue
An Efficient Underwater Navigation Method Using MPC with Unknown Kinematics and Non-Linear Disturbances
Previous Article in Journal
Towards Lower Carbon Emissions: A Distributed Energy Management Strategy-Based Multi-Objective Optimization for the Seaport Integrated Energy System
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Underwater Positioning System Based on Drifting Buoys and Acoustic Modems

by
Pablo Otero
,
Álvaro Hernández-Romero
,
Miguel-Ángel Luque-Nieto
* and
Alfonso Ariza
Institute of Oceanic Engineering Research, University of Málaga, 29010 Málaga, Spain
*
Author to whom correspondence should be addressed.
J. Mar. Sci. Eng. 2023, 11(4), 682; https://doi.org/10.3390/jmse11040682
Submission received: 14 December 2022 / Revised: 7 March 2023 / Accepted: 18 March 2023 / Published: 23 March 2023
(This article belongs to the Special Issue Navigation and Localization for Autonomous Marine Vehicles)

Abstract

:
GNSS (Global Navigation Satellite System) positioning is not available underwater due to the very short range of electromagnetic waves in the sea water medium. In this article a LBL (Long Base Line) acoustic repeater system of the GNSS positioning is presented. The system is hyperbolic, i.e., based on time differences and it does not need very accurate atomic clocks to synchronize repeaters. The system architecture and system calculations that demonstrate the feasibility of the solution are presented. The system uses four buoys that sequentially transmit their position and the time of the instant of transmission, for which they are equipped with GNSS receivers and acoustic modems. The buoys can be fixed or even drifting, but they are inexpensive devices, which pose no hazard to navigation and can be easily and quickly deployed for a specific underwater mission. The multilateration algorithm used in the receiver is presented. To simplify the algorithm, the depth of the receiver, measured by a depth sensor, is used. Results are presented for the position error of an underwater vehicle due to its displacement during the transmission frame of the four buoys.

1. Introduction

Oceans and seas are threatened due to ever-growing human activity. Pollution is the most dangerous threat to sea life. Less polluting human activities and more efficient sea monitoring are the targets of many oceanic engineering researchers. On the other hand, ocean exploitation is needed for human food, mineral extraction, and transportation. AUVs (autonomous underwater vehicles) play a paramount role in the sustainable exploitation of the seas; that is, exploitation which will protect water quality and sea life while fairly using the resources extracted.
The terms localization and positioning are often used interchangeably. However, there are two distinct actions; one is for an observer outside the water to know where a submerged AUV is, and the other is for the AUV to know or calculate its own position. This article deals with the latter, for which the term positioning will be used, keeping the word localization for the former. Navigation of AUVs will only be possible if an underwater positioning system is available. GNSS (Global Navigation Satellite System) cannot provide that service due to the high absorption of electromagnetic waves in the salted water media. Although positioning is a key issue for AUVs to navigate, little literature can be found on this topic, compared to other research subjects. A good starting point is the work of Paull et al. [1], which presented a review of the 2014 state of the art underwater positioning and localization and advanced future research on the subject. The survey deals with the overall problem of navigation and explores the existing localization and positioning technologies and other related topics as, for instance, sensors data fusion or mapping. Regarding positioning, existing systems are commonly classified according to the distance between stations (or sensors or transmitters, depending on the configuration of the system): USBL (Ultra Short Base Line), SBL (Short Base Line) and LBL (Long Base Line).
This article is about a new LBL system. In 2015, Han et al. [2] proposed a LBL system that used anchored beacons so that an AUV may calculate its position using a triangulation or trilateration method. The method is sensitive to the accuracy of the positions of the beacons; therefore, they proposed a calibration method to improve the precision of their system against the errors of the positions of the beacons. In 2015 Zhang et al. [3] presented a data fusion algorithm that combined the data from the inertial navigation system, the Doppler velocity log, the magnetic compass and the LBL to improve the accuracy of the positioning. The same group presented in 2016 [4] an extension of the previous work where the effective positional calibration area of the system is wider and shows a better positioning performance. In 2018 they included the equivalent—or effective—sound velocity (ESV) in their algorithm, to consider the variable underwater sound velocity and ray refraction [5]. In 2001 Vincent [6] proposed a method and a system for determining underwater ESV. The correction for the effects of varying sound velocity is also discussed in ref. [7], where the authors carry out experiments to characterize this error and show that it is possible to obtain consistent time-of-arrival (ToA) values, so that a fixed beacon LBL system could even improve the accuracy of commercial GNSS systems. Sun et al. presented in 2019 a method based on an effective sound velocity table and a genetic algorithm to improve the accuracy of the ToA [8].
Other research efforts were presented in 2016 in refs. [9,10]. In ref. [9], a localization system is presented that allows a surface vessel to determine the position of an AUV. Surface buoys equipped with GNSS receivers and acoustic transducers are used. Theoretical errors in the order of one meter were reported. In ref. [10], the authors solve a similar problem using a range-only single-beacon approach.
Dikarev et al., in 2019 [11], presented a geometrical model based on ToA and the experimental results of localizing an AUV using acoustic transponders. They reported an accuracy comparable to GNSS systems. Finally, Yang et al. [12] reported a system that uses a LiDAR camera combined with an Inertial Measurement Unit (IMU) to obtain the accurate localization data of an unmanned underwater vehicle (UUV).
As said, this article proposes a LBL system that is based on classical hyperbolic systems that uses GNSS service available on the sea surface to broadcast signals to the sea bottom that will allow an underwater receiver to calculate its position. There are important differences with previous works: (i) It is a positioning system, not a localization system, according to the meaning used at the beginning of this Section. (ii) The system does not require accurate atomic clocks. (iii) There is no limitation on the number of underwater receivers that can be serviced.
Of course, the presented system is not error free. The main error sources are: (i) the intrinsic GNSS error (which is also present in the regular GNSS service); (ii) the acoustic wave refraction due to the variable vertical profile of the sound propagation velocity in seawater, as well as the variable velocity itself, but we have seen that several research works have been conducted to minimize this error [5,6,7,8] in underwater localization systems; (iii) error due to movement of the receiver, which may have changed position between transmissions from different buoys. This error is due to the limited capacity of the underwater acoustic channel and the small propagation velocity of the acoustic wave in the water. It is addressed in Section 4 of this paper.
Other errors are of an order of magnitude less than those due to refraction. This article deals with the system concept and equations. Refraction error and its compensation have received much attention in the scientific literature and are not the subject of this paper.
In this article, Section 2 contains the description of the proposed system, Section 3 presents the equations that allow an underwater receiver to compute its position, and Section 4 contains the results of a test to verify the proper system operation, as well as a discussion on the system limitations. A brief study of the error due to the movement of the receiver is also covered in Section 4, where the errors calculated for different receiver speeds are presented. Finally, the article contents will be summarized in Section 5.

2. System Description

The proposed system consists of at least four surface buoys that transmit messages containing their GNSS-position and the GNSS-time at which the buoy position was computed. Figure 1 shows a schematic view of the system. The buoys positions define a quadrilateral on the sea surface. For a greater coverage, the preferred quadrilateral is a square, but the system is still possible if the buoys are vertices of an irregular polygon.
Surface buoys can be fixed or drifting buoys, as will be soon be explained in Section 3. The reason is that the data transmitted by each buoy are its GNSS position and the GNSS time at the instant of transmission, which are all that is needed by the receiver to calculate the position using the proposed algorithm. The buoys are not observation buoys, but a kind of “GNSS repeaters”. The buoys must be deployed following a favorable geometry. The best geometry is when they are at the vertices of a square. However, as long as they are not collinear, the underwater receivers will be able to calculate their positions. Basically, the hardware of a buoy consists of a microcontroller, a GNSS receiver, an underwater acoustic modem, including a hydrophone, and a power supply. They also incorporate a LoRa transceiver which is intended to facilitate the recovery of drifting buoys and may, in the future, facilitate the use of more than four buoys to increase the coverage region of the system. These buoys are inexpensive devices which pose no hazard to navigation and can be easily and quickly deployed for a specific underwater mission. The receiver onboard the underwater vehicle consists of an underwater acoustic modem and a microcontroller.
Each buoy transmits sequentially, through an underwater acoustic transmitter, a message containing its GNSS position and the time of the instant at which that position was calculated. All buoys use the GNSS time, so that we can consider that they are synchronized. All receivers that are in the acoustic communication range of four buoys can calculate their position. It is possible to demonstrate the feasibility of the buoy transmission schedule. The length of the message is estimated to be around 80 bytes. This number comes from the length of the complete frame of the standard NMEA [13] and could be shortened if needed. Assuming a maximum limit of one second for the transmission time of a message, the minimum bit rate for the transmitter would be 640 bps, which is achievable with commercial underwater acoustic modems.
Concerning propagation time, one second roughly means 1.5 km range (the propagation speed depends on the salinity and temperature of the water and on depth), which is a long range in the world of underwater communications. A guard time of one second can be considered so far, which means a duty cycle of less than 10 s for the four buoys and a delay of around 8 s between the transmission of buoy #1 and the transmission of buoy #4. Figure 2 shows the frame structure.
If the coverage region is a cube of which one of the faces is the one with the four buoys as vertices, for the maximum distance between any of the buoys and any point inside that cube to be 1.5 km, the maximum side of the buoys square should be 1500/√3 m, that is, approximately 866 m. All of the above buoy spacing, guard time and range figures are indicative; their sole purpose is to confirm the feasibility of the system and they should be recalculated under the premise of a concrete system specification.
In Figure 2, mBi stands for the message transmitted by buoy i, and gBi is the guard time before buoy i + 1 starts transmitting; tm is the duration of the buoy message and Tf is the length of a single frame, which is the period of the transmission of the four buoys. On the other hand, an AUV is unlikely to move faster than 10 knots, which is around 5 m/s. In 2 s, it would have moved 10 m. This figure can be roughly considered the upper bound of the intrinsic limitation of the system in terms of position accuracy. Nevertheless, in case a lower upper limit is required, the use of a higher data rate in the modem or the reduction of the guard time results in a shorter frame and, consequently, higher position accuracy.

3. Analytic Solution of the Multilateration Equations

The Time Difference of Arrival (TDoA) technique has been used extensively in many different engineering applications and is very well known. When the stations (or sensors or transmitters, depending on the configuration of the system) are far apart in terms of wavelength, the system is said to be hyperbolic, since the locus of the points that are a constant distance from two given points is a hyperboloid, the foci of which are the latter two points. If there are four stations, the intersection of the hyperboloids obtained by taking the foci two by two is the 3D position of the point sought. This technique is called multilateration and has received much attention from scientists and engineers since the beginning of hyperbolic systems such as LORAN (which was 2D and normally used three stations) followed by other systems up to the current GNSS systems. Among the many solutions to the multilateration problem, the ones we have preferred in this work are those of Kleusberg [14] and Potluri [15].
The analytical solution of the so-called multilateration problem is summarized below. So far, a constant sound propagation velocity c is assumed. The effective sound velocity can be used for c. As mentioned, the four buoys use the GNSS clock. Let t i be the instant of transmission of buoy i = 1, …, 4, and t i the instant of the reception of the corresponding message by the underwater receiver. The message transmitted by buoy i contains t i and the GNSS-position of the buoy, Ri.
Attention must be paid to the fact that the clock of t i is the GNSS-time at buoy i and the clock of t i is the underwater receiver clock, which does not need to be synchronized with the GNSS time. That means that t i and t i are measured by different clocks. Let Δt be the offset between the two clocks. The so-called pseudorange between buoy i and the receiver is calculated as
P i = c t i t i + Δ t .
The difference of pseudoranges between buoys i and j and the receiver is
d j i = P j P i = c t j t j t i t i ,
because the offset in the pseudoranges cancels out. That is, the receiver knows Ri and d i j   , which are the data that are needed to solve the multilateration problem.
As said, in this work, we followed three approaches to obtain the receiver position. First, we used the analytical solution of Kleusberg [14] to verify the validity of the proposed solution of using four buoys transmitting their own position and time of transmission. We particularly liked the analytical solution of Kleusberg because of its elegance. The Kleusberg method can be used in the laboratory to test other algorithms, which is what has been done in this work. But this method only works if the solution exists. This means that there are combinations of pseudoranges that are theoretically impossible. Conceptually, the solution of the multilateration problem consists in finding the intersection of at least three hyperboloids. The intersection of two hyperboloids, if it exists, is a line in space. The lines resulting from intersecting the hyperboloids two by two in a real case do not have to intersect and then the Kleusberg method, which has the elegance of solving the problem analytically, does not provide the point where the receiver is located.
This means that the two lines resulting from the intersection of four hyperboloids taken two by two may not cut each other in space but cross each other. Therefore, we also used a second approach inspired by the work by Potluri [15] and particularized it to the underwater scenario. Finally, we proposed a third approach that simplifies the solution, based on using the position of one of the buoys as a reference for the positions of the other three buoys.
Our approach, which proves to be a valuable technique, is to use the depth data from the depth sensor fitted to the underwater vehicle. In that case, only two equations are needed to compute the coordinates x and y of the receiver. This technique is valuable for the following reason. If the four buoys are coplanar, as is the case, a bidimensional (2D) reference world is used to compute a 3D position. This makes the computed value of the receiver z-coordinate very sensitive to small errors due to numerical mismatches.
For this reason, we have designed a third strategy for the solution of the multilateration problem. We have referenced the coordinates of three of the buoys to the position of one of them, to which we have given the index 0. The difference of distances between the receiver and buoy i (i = 1, 2, 3) and buoy 0 is
d i 0 = x i x 2 + y i y 2 + z i z 2 x 0 x 2 + y 0 y 2 + z 0 z 2     ,
where now i = 1, 2, 3. If Equation (3) is squared, the terms in x2, y2 and z2 cancel out and can be written as
x 0 x 2 + y 0 y 2 + z 0 z 2 = A i x + B i y + C i z + D i   ,
where
A i = x 0 x i d i o   ;   B i = y 0 y i d i o   ;   C i = z 0 z i d i o   ;
D i = x i 2 + y i 2 + z i 2 x 0 2 y 0 2 z 0 2 d i o 2 2 d i o   .
If the right-hand members of the three equations in (4) are equated two by two, a linear system of three equations is obtained
A i A j x + B i B j y + C i C j z = D j D i   .
Only two of the three equations in (7) are linearly independent and to obtain the receiver position, RR, we must also use (4). The point here is that if again z0 = z1 = z2 = z3i,j, then Ci = Cj and the two independent equations in (7) give the sought coordinates x and y. This brings us back to the discussion on the calculation of a 3D position from a 2D reference. The problem is overcome by using the value of z = zd that can be obtained from the depth sensor of the underwater vehicle.

4. Results

The analytical solution has been tested using the reverse calculation. The test consists in placing four buoys on the sea surface and a receiver in determined underwater positions. That is, the GNSS positions of the four buoys are known. Pseudoranges are calculated and, eventually, the eight values of t i and t i . A stationary receiver has been considered. The four messages are formed and given to the receiver, that computes its position using the analytical solution presented in Section 3 and it is found to be exact.
As mentioned in Section 1, one of the limitations of the presented positioning system is the movement of the receiver, because buoys do not transmit simultaneously, and because the propagation delay of the acoustic wave cannot be neglected. Figure 3 and Figure 4 show the error vs. the receiver speed, when moving along a parallel or a meridian, respectively. The error is calculated by placing the submerged receiver in the various different positions it would be in when transmitting each buoy (because of its movement). Obviously, the ToA differences are not those that would be present if the receiver were at a fixed point. These time differences were used to calculate the position with the presented algorithm and compared with the position of the receiver after receiving the signal from the fourth buoy. The shown error is the distance in meters between these two positions and it has been computed for different receiver velocities. Geographical coordinates of the receiver position for the test were approximately (N36°, W4°). The distance shown on the horizontal axis is the distance the receiver travels between two successive transmissions from the transmitters on the buoys. That is, if the time between two successive transmissions is Δ T = T f / 4 (see Figure 2), then the receiver speed is the abscissa shown divided by ΔT. For example, if the distance is 3.4 m and the transmission interval is 2 s, the receiver speed is 1.7 m/s. Obviously, the lower ΔT the smaller the error. The error depends not only on the receiver velocity and ΔT, but also on the relative position of the receiver with respect to the polygon whose four vertices are the positions of the buoys, and on the direction of motion. The reference to the cardinal points is also relative; for the error, the direction of movement is relative to the rotation of the buoy transmission (clockwise or counterclockwise). Figure 3 and Figure 4 show values that have been obtained in different examples. The error in Figure 3 is the largest error obtained in different calculations.
There is an interesting debate on how to reduce this error. As already mentioned, the lower ΔT the smaller the error, but ΔT has a lower value which depends, among other things, on the propagation velocity of the acoustic wave in water, which is a physical constraint. The operational solution of stopping the underwater vehicle for a short period of time while the receiver calculates the position is always possible, but the sea current will always be present. The technological option is to use sensor data fusion, which has proven to be an effective way to reduce the error in underwater positioning [16,17]. In addition, the data fusion system can help compensate for sea current drift to maintain a stable position while calculating.

5. Conclusions

In this article a GNSS repeater system has been presented to provide underwater positioning using four acoustic transmitters mounted on surface buoys. The main contribution of the chart is that the underwater receiver clock does not need to be synchronized with the buoy clocks or be a very accurate atomic clock. The proof of concept has been carried out using the Kleusberg analytical method to solve the multilateration problem, and the feasibility of the time schedule has also been demonstrated. Finally, a multilateration algorithm derived from Potluri’s algorithm has been used to compute the receiver position.
As mentioned in Section 2, the drifting of the buoys is not a limitation because the buoys sequentially transmit their position at a particular instant and the time of the instant of transmission, which are all the receiver algorithm needs to calculate the difference of pseudoranges.
Regarding the system limitations, the following can be mentioned. The service range is limited by the communication range of the underwater acoustic communication system. The position accuracy is limited by the transmission bit rate of the above-mentioned system, as explained in Section 2, and the receiver movement, as shown in Section 4. There is no limitation on the number of receivers that the system can serve, as long as they are in the range of four buoys.

Author Contributions

P.O. suggested the idea for the article and drafted the manuscript. Á.H.-R. carried out the mathematical developments and programming. M.-Á.L.-N. checked the developments and contributed to the editing. A.A. contributed to the implementation of the corresponding microcontroller-based system and revised the final text. All authors have read and agreed to the published version of the manuscript.

Funding

This research has been funded by a grant from the Spanish Ministry of Science and Innovation through the project “NAUTILUS: Swarms of underwater autonomous vehicles guided by artificial intelligence: its time has come” (PID2020-112502RB/AEI/10.13039/501100011033).

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Not applicable.

Acknowledgments

The authors would like to thank María-Ángeles Gómez-Molleda, University of Málaga, who helped them with the multilateration equations.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Paull, L.; Saeedi, S.; Seto, M.; Li, H. AUV Navigation and Localization: A Review. IEEE J. Ocean. Eng. 2014, 39, 131–149. [Google Scholar] [CrossRef]
  2. Han, Y.; Zheng, C.; Sun, D. Accurate Underwater Localization Using LBL Positioning System; OCEANS—MTS: Washington, DC, USA; IEEE: Washington, DC, USA, 2015; pp. 1–4. [Google Scholar] [CrossRef]
  3. Zhang, T.; Chen, L.; Li, Y. AUV Underwater Positioning Algorithm Based on Interactive Assistance of SINS and LBL. Sensors 2015, 16, 42. [Google Scholar] [CrossRef] [PubMed] [Green Version]
  4. Zhang, T.; Shi, H.; Chen, L.; Li, Y.; Tong, J. AUV Positioning Method Based on Tightly Coupled SINS/LBL for Underwater Acoustic Multipath Propagation. Sensors 2016, 16, 357. [Google Scholar] [CrossRef] [PubMed] [Green Version]
  5. Zhang, T.; Chen, L.; Yan, Y. Underwater Positioning Algorithm Based on SINS/LBL Integrated System. IEEE Access 2018, 6, 7157–7163. [Google Scholar] [CrossRef]
  6. Vincent, H.R., II. Models, Algorithms, and Measurements for Underwater Acoustic Positioning. Ph.D. Dissertation, University of Rhode Island, Kingston, RI, USA, 2001. Available online: https://www.proquest.com/docview/276304511?pq-origsite=gscholar&fromopenview=true (accessed on 7 March 2023).
  7. Almeida, R.; Melo, J.; Cruz, N. Characterization of Measurement Errors in a LBL Positioning System; OCEANS: Shanghai, China, 2016; pp. 1–6. [Google Scholar] [CrossRef] [Green Version]
  8. Sun, D.; Li, H.; Zheng, C.; Li, X. Sound velocity correction based on effective sound velocity for underwater acoustic positioning systems. Appl. Acoust. 2019, 151, 55–62. [Google Scholar] [CrossRef]
  9. Aparicio, J.; Jimenez, A.; Alvarez, F.J.; Ruiz, D.; De Marziani, C.; Urena, J. Characterization of an Underwater Positioning System Based on GPS Surface Nodes and Encoded Acoustic Signals. IEEE Trans. Instrum. Meas. 2016, 65, 1773–1784. [Google Scholar] [CrossRef]
  10. Masmitja, I.; Gomariz, S.; Del Río, J.; Kieft, B.; O’Reilly, T. Range-Only Underwater Target Localization: Path Characterization; OCEANS—MTS: Monterey, CA, USA; IEEE: Monterey, CA, USA, 2016; pp. 1–7. [Google Scholar] [CrossRef] [Green Version]
  11. Dikarev, A.; Dmitriev, S.; Kubkin, V.; Vasilenko, A. Position Estimation of Autonomous Underwater Sensors Using the Virtual Long Baseline Method. Int. J. Wirel. Mob. Netw. 2019, 11, 13–25. [Google Scholar] [CrossRef]
  12. Yang, H.; Xu, Z.; Jia, B. An Underwater Positioning System for UUVs Based on LiDAR Camera and Inertial Measurement Unit. Sensors 2022, 22, 5418. [Google Scholar] [CrossRef] [PubMed]
  13. National Marine Electronics Association (NMEA); International Marine Electronics Association. NMEA: Standard for Interfacing Marine Electronic Devices; National Marine Electronics Association and International Marine Electronics Association: Severna Park, MD, USA, 2012. [Google Scholar]
  14. Kleusberg, A. Analytical GPS Navigation Solution. In Geodesy—The Challenge of the 3rd Millennium; Grafarend, E.W., Krumm, F.W., Schwarze, V.S., Eds.; Springer: Berlin/Heidelberg, Germany, 2003. [Google Scholar] [CrossRef]
  15. Potluri, S. Hyperbolic Position Location Estimator with TDoAs from Four Stations. Master’s Thesis, New Jersey Institute of Technology, Newark, NJ, USA, 2002. Available online: https://digitalcommons.njit.edu/theses/704 (accessed on 7 March 2023).
  16. Shaukat, N.; Ali, A.; Iqbal, M.J.; Moinuddin, M.; Otero, P. Multi-sensor fusion for underwater vehicle localization by augmentation of RBF neural network and error-state Kalman filter. Sensors 2021, 21, 1149. [Google Scholar] [CrossRef] [PubMed]
  17. Shaukat, N.; Moinuddin, M.; Otero, P. Underwater vehicle positioning by correntropy-based fuzzy multi-sensor fusion. Sensors 2021, 21, 6165. [Google Scholar] [CrossRef] [PubMed]
Figure 1. System sketch.
Figure 1. System sketch.
Jmse 11 00682 g001
Figure 2. Frame structure.
Figure 2. Frame structure.
Jmse 11 00682 g002
Figure 3. Error when the receiver is moving along a parallel.
Figure 3. Error when the receiver is moving along a parallel.
Jmse 11 00682 g003
Figure 4. Error when the receiver is moving along a meridian.
Figure 4. Error when the receiver is moving along a meridian.
Jmse 11 00682 g004
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Otero, P.; Hernández-Romero, Á.; Luque-Nieto, M.-Á.; Ariza, A. Underwater Positioning System Based on Drifting Buoys and Acoustic Modems. J. Mar. Sci. Eng. 2023, 11, 682. https://doi.org/10.3390/jmse11040682

AMA Style

Otero P, Hernández-Romero Á, Luque-Nieto M-Á, Ariza A. Underwater Positioning System Based on Drifting Buoys and Acoustic Modems. Journal of Marine Science and Engineering. 2023; 11(4):682. https://doi.org/10.3390/jmse11040682

Chicago/Turabian Style

Otero, Pablo, Álvaro Hernández-Romero, Miguel-Ángel Luque-Nieto, and Alfonso Ariza. 2023. "Underwater Positioning System Based on Drifting Buoys and Acoustic Modems" Journal of Marine Science and Engineering 11, no. 4: 682. https://doi.org/10.3390/jmse11040682

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop