Hostname: page-component-745bb68f8f-mzp66 Total loading time: 0 Render date: 2025-02-06T09:26:01.313Z Has data issue: false hasContentIssue false

Development and Performance Validation of a Navigation System for an Underwater Vehicle

Published online by Cambridge University Press:  26 January 2016

R. Ramesh*
Affiliation:
(National Institute of Ocean Technology, Ministry of Earth Sciences, Chennai, India)
V. Bala Naga Jyothi
Affiliation:
(National Institute of Ocean Technology, Ministry of Earth Sciences, Chennai, India)
N. Vedachalam
Affiliation:
(National Institute of Ocean Technology, Ministry of Earth Sciences, Chennai, India)
G.A. Ramadass
Affiliation:
(National Institute of Ocean Technology, Ministry of Earth Sciences, Chennai, India)
M.A. Atmanand
Affiliation:
(National Institute of Ocean Technology, Ministry of Earth Sciences, Chennai, India)
*
Rights & Permissions [Opens in a new window]

Abstract

Underwater position data is a key requirement for the navigation and control of unmanned underwater vehicles. The proposed navigation scheme can be used in any vessel or boat for any shallow water vehicle. This paper presents the position estimation algorithm developed for shallow water Remotely Operated Vehicles (ROVs) using attitude data and Doppler Velocity Log data with the initial position from the Global Positioning System (GPS). The navigational sensors are identified using the in-house developed simulation tool in MATLAB, based on the requirement of a position accuracy of less than 5%. The navigation system is built using the identified sensors, Kalman filter and navigation algorithm, developed in LabVIEW software. The developed system is tested and validated for position estimation, with an emulator consisting of a GPS-aided fibre optic gyro-based inertial navigation system as a reference, and it is found that the developed navigation system has a position error of less than 5%.

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

1. INTRODUCTION

Underwater vehicles require precision navigational sensors for the purpose of effective navigation and to determine the position of the vehicle in real time. The precision requirement depends on the mission objectives, sensor accuracies and duration (Ramadass et al., Reference Ramadass, Vedachalam, Balanagajyothi, Ramesh and Atmanand2013; Geng et al., Reference Geng, Martins and Sousa2010; Li and Wang, Reference Li and Wang2013). Manned and unmanned underwater vehicles designed for complex subsea operations and long mission durations are often equipped with very high precision Fibre Optic Gyro (FOG)-based Inertial Navigation Systems (INS), aided by a Doppler Velocity Log (DVL) and acoustic base line positioning systems (Vedachalam et al., Reference Vedachalam, Ramadass and Atmanand2014a; Narayanaswamy et al., Reference Narayanaswamy, Raju, Durairaj, Ananthapadmanabhan, Annamalai, Ramadass and Atmanand2013; Vedachalam et al., Reference Vedachalam, Ramadass and Atmanand2014b). Shallow water vehicles, which are designed for shorter mission periods, are often fitted with a navigational system comprising MEMS (Micro-Electro-Mechanical Systems)/magnetic sensor technology-based attitude sensors (Fossen, Reference Fossen2012), DVL and a processor for real time computation of the position. The navigation system is initialised with a position input from an external terrestrial Global Positioning System (GPS) and works in a dead reckoning mode (Marco and Healey, Reference Marco and Healey2001) during the underwater mission. In the dead reckoning mode, based on the last known or computed position, the navigational algorithm estimates the current position based on the inputs from the sensor suite. The sensor suite comprises attitude sensors measuring the vehicle's orientation in three Degrees Of Freedom (DOF) and the acoustic-based DVL measures the vehicle's body frame linear velocities in all three axes.

The precision of the sensor hardware suite and the effectiveness of the position estimation algorithm are vital in effective position determination. The selection of the sensor suite is a trade-off between the position estimation needs of the mission, sensor footprint and costs (Grewal et al., Reference Grewal, Weill and Andrews2001; Ellingsen, Reference Ellingsen2008). The National Institute of Ocean Technology (NIOT) designed and developed a Remotely Operated Vehicle (ROV) with a depth rating of 500 m for shallow water and polar exploration. This paper presents the development of an INS for the shallow water ROV which can be deployed from any ship. The selection of the navigation sensor suite is done with the aid of the in-house developed simulator tool, which is a MATLAB mathematical model that takes the sensor error model parameters and user-defined mission profile as inputs, and simulates the vehicle trajectory in geo-coordinates. The tool also displays the vehicle trajectory under ideal sensor conditions for the same mission profile. Based on the simulation results obtained for various combinations of sensors and the mission target position accuracy requirement of less than 5%, the attitude sensor and DVL hardware are realised. A real time controller and LabVIEW software are used for data acquisition and algorithm development for computing the position with the Kalman filter. Prior to installing the systems on board the ROV, the calibration of the inertial and attitude sensor has been carried out as per the recommended calibration procedures given by the manufacturer. Calibration of the Photonic Inertial Navigation System (PHINS) was performed with the aid of GPS, as per the instruction given in the user manual (PHINS, 2013). A staircase shaped trajectory was performed during the fine alignment mode until the heading covariance was less than 0·1°. With this, the developed navigational system is validated for the desired performance, using an in-house developed emulator (which is based on the GPS-aided high precision FOG-based INS and error models of the sensors), which provides the attitude and velocity sensor inputs, with accuracies resembling the selected sensor suite and validated on board a terrestrial vehicle, with a mission profile closely resembling the actual underwater vehicle. The developed system is installed and qualified for the desired performance on board the NIOT developed 500 m depth rated ROV.

2. POSITION ESTIMATION METHODOLOGY IN UNDERWATER VEHICLES

Land-based and ocean surface vessel navigational systems utilise GPS signals for computing their position (Hegrenaes et al., Reference Hegrenaes, Berglund and Hallingstad2008). GPS signals cannot be used by underwater vehicles as electromagnetic waves suffer significant attenuation in water (Fallon et al., Reference Fallon, Papadopoulos, Leonard and Patrikalakis2010). Prior to deployment, the underwater vehicle navigational system is initialised with the position input from the external GPS. It then works in the dead reckoning mode during the underwater mission. In the dead reckoning mode, based on the last known or computed position, the navigational algorithm, with inputs from the vehicle on board attitude sensors and DVL, estimates the current position. The DVL, which is mounted on the body frame of the vehicle, measures the vehicle velocity in body frame coordinates (Jalving et al., Reference Jalving, Gade, Hagen and Vestgard2003). In order to compute the change in position of the navigating vehicle with respect to the Earth frame, the measured body frame velocity needs to be converted into an Earth frame. Figure 1 represents the vehicle with reference to the Earth frame, where the velocities are to be resolved in the North and East directions and Figure 2 represents the six DOF parameters for a typical ROV in the body frame.

Figure 1. Vehicle orientation in the Earth frame.

Figure 2. Representation of a typical vehicle orientation in the body frame.

The conversion of the DVL measured body frame velocity to an Earth frame velocity is achieved using the Direct Cosine Matrix (DCM) transformation with the vehicle attitude parameters (Fossen, Reference Fossen1994; Hofmann-Wellenhof et al., Reference Hofmann-Wellenhof, Legat and Wieser2011; Hegrenaes et al., Reference Hegrenaes, Berglund and Hallingstad2008) represented in Equation (1).

(1) $${V_e} = C_b^e \; {V_b}$$

where, $\; {\rm C}_{\rm b}^{\rm e} $ is a transformation matrix, which is computed with the attitude data measured by the attitude sensor (Lammas et al., Reference Lammas, Sammut and He2007).

(2) $$C_b^e = \left[ {\matrix{ {c\psi c\theta} & { - s\psi c\theta + c\psi s\theta s\phi} & {s\psi s\phi + c\psi c\phi s\theta \;} \cr {s\psi c\theta} & {c\psi c\phi + s\phi s\theta s\psi} & { - c\psi s\phi + s\theta s\psi c\phi} \cr { - s\theta} & {c\theta s\phi} & {c\theta c\phi} \cr}} \right]$$

where, s. = sin (.), c. = cos (.) and t. = tan (.), roll (ϕ), pitch (θ) and Yaw (ψ) or attitude/Euler angles of the underwater vehicle and Vb is the body frame velocity matrix [Vx, Vy, Vz] and Ve is the Earth frame velocity [Vn, Ve, Vd] matrix.

The vehicle velocity computed in the Earth frame coordinates is integrated over a time ∆t to get the updated position every one second in geo-coordinates represented in latitude and longitude computed using Equations (3) and (4), which takes into account for the Earth parameters (Liansheng and Tao, Reference Liansheng and Tao2011; Titterton and Weston, Reference Titterton and Weston2004; Christensen et al., Reference Christensen, Fogh, la Cour-Harbo and Bisgaard2008; Hofmann-Wellenhof et al., Reference Hofmann-Wellenhof, Legat and Wieser2011) shown in Equations (5) and (6).

(3) $$Latitude\; L = L + \left( {\displaystyle{{{v_N}\;{\ast}\;\Delta t} \over {{R_N}}}} \right)$$
(4) $$Longitude\; \lambda = \lambda + \left( {\displaystyle{{{v_E}\;{\ast}\;\Delta t\;{\ast}\;secL} \over {{R_E}}}} \right)$$

where, VN is the Northing velocity of the vehicle in m/s; VE is the Easting velocity of the vehicle in m/s; RN is the meridian radius curvature of the Earth, RE is the transverse radius curvature of the Earth computed as per the following Equations (5), (6), (7), (10) and ∆t is the integration time of one second.

(5) $$\; {R_N} = \left( {\displaystyle{{{R_E}\left( {1 - {e^2}} \right)} \over {{{\left( {1 - {e^2}si{n^2}L} \right)}^{\textstyle{3 \over 2}}}}}} \right)$$
(6) $${R_E} = \left( {\displaystyle{{{R_E}} \over {{{\left( {1 - {e^2}si{n^2}L} \right)}^{\textstyle{1 \over 2}}}}}} \right)$$

The Earth parameters can be defined as per the international standard World Geodetic System (WGS).WGS84 (Grewal et al., Reference Grewal, Weill and Andrews2001) is a reference Earth model as an ellipsoid.The Radius of the Earth, RE = 6378137m, eccentricity, e = 0.00335281066475

3. SELECTION OF THE SENSOR SUITE USING A SIMULATOR

The selection of suitable navigational sensors is a key challenge in the design of underwater position estimation systems, as the accuracy of the position estimation depends mainly on the sensor characteristics (Fossen, Reference Fossen2012; Foss and Meland, Reference Foss and Meland2007). Hence, based on the accuracy requirements of the mission, the navigational sensors are selected. A modelling and simulation tool was developed in MATLAB software, which accepts the initial position, sensor characteristics and mission profile as inputs, and provides the estimated position in the time domain as the output is used (Ramadass et al., Reference Ramadass, Vedachalam, Balanagajyothi, Ramesh and Atmanand2013). The tool, which is coded with the error models of the DVL and attitude sensor, is explained below.

3.1. Attitude sensor error model

The vehicle's angular orientation in three axes is measured, using the attitude sensor housing compass and tilt sensors. The compass measures the vehicle heading with respect to true North and the tilt sensors provide the roll and pitch values. The error model of the attitude sensor is based on the following Equation (7) representing the bias error and random noise (Cruz et al., Reference Cruz, Matos, de Sousa, Pereira, Silva, Silva and Dias2003; Healey et al., Reference Healey, An and Marco1998; Foss and Meland, Reference Foss and Meland2007; PNI sensors Corporation, 2014) parameters.

(7) $$Heading\; {\Psi _o} = ({\Psi _i}\,{\ast}\,{\rm sec}L) + ({\Psi _{acc}}\,{\ast}\,b(t))$$
(8) $$Roll\; {\Phi _o} = {\Phi _i}\left( {1 + {S_f}} \right) + b\left( t \right)$$
(9) $$Pitch\; {\theta _o} = {\theta _i}(1 + {S_f}) + b(t)$$

where, Ψi is the input heading measurement from the compass; Ψacc is the heading accuracy; Ψo is the heading output as shown in Equation (7). Φi is the input roll measurement from the tilt sensor; Sf is the scale factor; Φo is the roll output as shown in Equation (8). θi is the input pitch measurement from the tilt sensor; Sf is the scale factor and θo is the pitch output as shown in Equation (9). b(t) is the white Gaussian noise modelled with zero mean and the sensor standard deviation.

3.2. Doppler Velocity Log error model

The body frame velocity of the underwater vehicle is measured using the Doppler Principle, and the error model of the DVL is shown and explained in Equation (10):

(10) $${{\rm V}_{\rm o}} = \left( {1 + {{\rm S}_{\rm f}}} \right){{\rm V}_{\rm i}} + {\rm b}\left( {\rm t} \right)$$

Where V i is the simulated velocity input data from the DVL sensor, V o is the velocity output from the model, Sf is the scale factor, and b(t) is the white Gaussian noise with zero mean and the sensor standard deviation (Jalving et al., Reference Jalving, Gade, Svartveit, Willumsen and Sorhagen2004; Mandt et al., Reference Mandt, Gade and Jalving2001; Braga et al., Reference Braga, Healey and Sousa2012; Teledyne RD Instruments, 2013; LinkQuest Incl, 2013, Hegrenaes et al., Reference Hegrenaes, Berglund and Hallingstad2008) derived using the Allan Variance method as shown in Figure 3. The noise characteristics of the DVL have been carried out by placing the DVL in a static mode in the NIOT in-house tank facility continuously for two hours and logging the data in a computer every second. Using the velocity data from the DVL, the Allan Variance graph (Allan, Reference Allan1966; Hou, Reference Hou2004; El-Sheimy et al., Reference El-Sheimy, Hou and Niu2008) is plotted in Figure 3. It can be seen from Figure 3 that when the time is less than 10 seconds, the slope is −1/2 representing the white noise variance of 0·002 at one second.

Figure 3. Analysis of the white noise characteristics for the DVL sensor using Allan Variance.

3.3. Simulation methodology

Figure 4 explains the principle of the simulator software developed in MATLAB. In the simulation it is considered that the entire sensor data update rate is at one second. Based on the described sensor error models, three-axes body frame velocity and three-axes attitude, the sensor data is generated and stored as data files as per the designed circular vehicle trajectory (Ramadass et al., Reference Ramadass, Vedachalam, Balanagajyothi, Ramesh and Atmanand2013). The initial position of the vehicle in latitude and longitude will be obtained from the GPS receiver, which is a standalone system with a fixed antenna, providing the position output in geo-coordinates using the GPS satellite constellation (Acquaris, 2012) in the National Marine Electronics Association (NMEA 0183) $GPGGA format.

Figure 4. Simulation methodology.

The Earth parameters are initialised as per the WGS84 standard. The body frame velocities of the DVL are transformed into the Earth frame using a direct cosine matrix as explained in Equation (1) with Euler angles. The position estimation is done based on the navigation Equations (3)–(6) in the dead reckoning mode. The simulation algorithm computes and plots the position of the vehicle in geo-coordinates over the mission period for the given vehicle trajectory.

3.4. Selection of the sensor suite

The navigational system developed for the 500 m depth rated ROV demands a position estimation accuracy of better than 10 m in both the latitude and longitude coordinates, when the vehicle is operated with an average velocity of one knot, for a period of 30 minutes. In order to meet the defined mission requirements, a combination of the sensor suite with a range of commercially available DVL (Braga et al., Reference Braga, Healey and Sousa2012; Panish and Taylor, Reference Panish and Taylor2011; de Morais et al., Reference de Morais2013; Mandt et al., Reference Mandt, Gade and Jalving2001) and attitude sensors (PHINS, 2013; PNI sensors Corporation, 2014; Honeywell magnetic sensors, 2014) was selected as three different types. Types 1, 2 and 3 represent the sensor suite with a highly accurate velocity log and different attitude sensors and types 4, 5 and 6 represent a less accurate velocity log and different attitude sensors. The performance of the sensor suite was simulated for the position estimation performance for the defined mission.

The simulation results for sensor suite types 1, 2 and 5 plotted in the geographical coordinates are shown in Figure 5. Details of the sensors considered in each suite and their simulated position estimation performances are shown in Table 1.

Figure 5. Simulation results for the sensor suites.

Table 1. Performance of the various combinations of sensor suites.

From the simulation results shown in Table 1, it can be seen that sensor suites 2 and 5 were found to match the target position estimation performance for the mission. By considering the overall project requirements, the type 5 sensor suite is identified for developing the vehicle's navigational system as it is low cost, small size and low weight and thus suitable for a shallow water ROV.

4. SYSTEM DEVELOPMENT AND EMULATOR-BASED VALIDATION

Based on the simulation results, the navigational system is developed. The architecture of the hardware is shown in Figure 6 and the details of the interface are shown in Table 2.

Figure 6. Architecture of the navigation system.

Table 2. Description of the hardware used for the navigational system.

The developed navigational system is qualified for its position estimation performance, using an in-house developed emulator. The emulator comprises a GPS-aided high precision FOG-based INS (PHINS, 2013) providing attitude and velocity sensor inputs, which are fed to the software coded to introduce inaccuracies resembling the selected sensor suite. The GPS-aided FOG-based INS has a proven high precision performance with a heading stability accuracy of 0·002°/ hour and velocity accuracy of 0·01 m/s.

The output of the emulator module thus matches the output performance of the selected sensor suite. The emulator output is provided as input to the developed navigational system. Figure 7 shows the methodology involved in providing the emulation inputs and validating the position estimation performance of the navigational system. The developed navigational system is qualified for performance using the emulator-fed system by moving in a terrestrial vehicle in a known location (Latitude - 12·94621, Longitude - 80·21350) which can be seen in Figure 8. The terrestrial vehicle is manoeuvred in a profile almost resembling the expected underwater mission profile conditions (X and Y linear DOF and all three angular DOF).

Figure 7. Performance validation algorithm using emulator.

Figure 8. Test setup for performance test using the emulation.

Figure 9 shows the navigation plot of the GPS-aided FOG based-INS and the output of the emulator fed developed navigational system. Table 3 details the temporal performance of the emulator-fed navigational system with reference to the GPS-aided FOG-based INS.

Figure 9. System's navigation performance using the emulator.

Table 3. Performance of the system compared with near ideal reference.

5. IMPLEMENTATION AND PERFORMANCE IN SHALLOW WATER ROV

The developed navigational system comprising attitude sensors, DVL and controller is mounted on board the 500 m depth rated ROV (Vedachalam at al., Reference Vedachalam, Ramesh, Subramanian, Sathianarayanan, Ramesh, Harikrishnan and Atmanand2015). The vehicle velocity measurement using the DVL is based on the Doppler acoustic principle, which provides three-axes linear velocity data at an update rate of one second to the position estimation algorithm. Due to the vehicle dynamics, there are possibilities that could result in data outages from the DVL that could lead to erroneous position computation. To overcome the system's degraded performance during such data outages, a linear Kalman Filter (KF) is developed and incorporated in the DVL velocity measurements (Leader, Reference Leader1994; Anonsen and Hallingstad, Reference Anonsen and Hallingstad2007; Welch and Bishop, Reference Welch and Bishop1995; Simon, Reference Simon2006; Mandt et al., Reference Mandt, Gade and Jalving2001). The prediction methodology of the KF is shown below.

The KF matrices for the estimation of velocities are given below.

A, is the state transition matrix linking the states at time k-1 and k-

$$A = {[{\bi I}]_{3{\ast}3}}$$

B, is the control input vector matrix

$$B = {[{\bi O}]_{3{\ast}3}}$$

uk−1, is the input vector

$${u_{k - 1}} = {[{\bi O}]_{1{\ast}3}}$$

$\hat{\rm X}_{{\rm k} - 1}$ , is the a priori state vector at time k

$$ \hat {X}_{k - 1} = [{\bi O}]_{3{\ast}3}$$

Hk, is the measurement matrix

$$H = {[{\bi I}]_{3{\ast}3}}$$

Q is the process noise covariance

$$Q = 0.01^ 2{\ast}{[{\bi I}]_{3{\ast}3}}$$

R is the measurement noise covariance

$$R = 0.52^ 2\,{\ast}\,{[{\bi I}]_{3{\ast}3}}$$

${\rm P}_{\rm k}^ - $ , is the covariance matrix of the prediction error initialised as

$${P_{k -}} = 0.01\,{\ast}\,{[{\bi I}]_{3{\ast}3}}$$

Zk, is the measurement vector at time k

$${Z_k} = H\,{\ast}\,{V_k}$$

where V k is the linear vehicle velocity Input data in 3-axes from the DVL,

$${V_k} = [\matrix{ {{v_x}} & {{v_y}} & {{v_z}} \cr} ]$$

Time Update

(11) $$\hat{X}_{k -} = A\hat{X}_{k - 1} + B{u_{k - 1}}$$
(12) $${P_{k -}} = A{P_{k - 1}}{A^T} + Q$$

Measurement Update

(13) $${K_k} = P_k^ - {H^T}{(HP_k^ - {H^T} + R)^{ - 1}}$$
(14) $$\hat{X}_k = \hat{X}_{k -} + K(Z_k - H\hat{X}_{k -})$$
(15) $${P_k} = (I - {K_k}{H_k})\; P_k^ - $$

Where ${\hat {\rm X}_{{\rm k} -}} $ is the posteriori state vector at time k, Kk is the Kalman gain and Pk is the covariance of the posterior error.

Based on the Equations (11)–(15), the velocities measured from the DVL are taken as the input matrix, Hk and the process and measurement covariance parameters are tuned to filter the noisy velocity data. Based on standard KF tuning methods (Li et al., Reference Li, Wu, Wang and Lu2013; Healey et al., Reference Healey, An and Marco1998), the filter is tuned to have a process noise covariance (Q) of 0·0001 and measurement noise covariance (R) of 0·2704, and the filtered velocities are obtained for the navigation algorithm computation. The implemented logic is shown in Figure 10.

Figure 10. Implemented algorithm incorporating KF.

As a part of the ROV qualification trials, Figure 11 shows the ROV being launched from the anchored barge in Idukki Lake in the Kerala State of South India, where the water depth at the test location was 40 m. The figure at right shows the vehicle operation, and the data is logged in the pilot console located on board the anchored barge (Vedachalam et al., Reference Vedachalam, Ramesh, Subramanian, Sathianarayanan, Ramesh, Harikrishnan and Atmanand2015).

Figure 11. Navigational system tested for performance.

Figure 12 shows the vehicle velocity input for the position computation algorithm, without and with the KF in place.

Figure 12. KPA performance for velocity during DVL outages.

The ROV was navigated for a period of 30 minutes at an average depth of 25 m and the recorded depth plot in the pilot console is shown in Figure 13.

Figure 13. Depth plot for underwater navigation.

Figure 14 shows the position plot of the underwater vehicle in geo-coordinates during the test period. It can be seen that the vehicle has navigated a distance of 120 m and at a maximum speed in x-axis to 0·5 m/s and y-axis to 0·115 m/s to perform a circular trajectory. After the 30 minute period, when the vehicle surfaced and was recovered to the stationary anchored barge, it could be seen that there were position offsets of 2·89 m in Latitude and −4·38 m in the longitude coordinates with resultant offset of 5·2 m and the calculated position error was 4·3%.The result is found to comply with the emulated performance with a position error of less than 5% which meets the mission requirements.

Figure 14. Geo-referenced plot of underwater navigation.

6. CONCLUSION

This paper has presented the navigational system developed for the position estimation of a shallow water Remotely Operated Vehicle using attitude and the Doppler Velocity Log with an initial position aid from GPS. Based on the defined vehicle position accuracy requirement of less than 10 m in the Latitude and Longitude coordinates for 30 minutes at one knot vehicle speed, suitable velocity and attitude sensors are identified using the in-house developed simulator tool. The position estimation performance of the developed system was validated using a precision emulator providing attitude and velocity sensor inputs with accuracies resembling the selected sensor suite, and was found to comply with the simulation results. The developed system was found to perform with the envisaged accuracy of less than 5%, when tested in the in-house developed shallow water Remotely Operated Vehicle. In the near future, it is planned to test the ROV in deeper waters and for longer mission durations, to test the position accuracy and improve the navigation algorithm.

ACKNOWLEDGEMENT

The authors gratefully acknowledge the support extended by the Ministry of Earth Sciences, Government of India, in funding this research. The authors also wish to thank the other staff involved in the project for their contribution and support.

References

REFERENCES

Acquaris. (2012). Acquaris Model, Astech Thales GPS receiver. http://ashgps.com/mirror/20130710/Marine%20Survey/Aquarius-Sagitta-3011/Manuals/Sagitta%20Seismic.pdf. Accessed 15 December 2012.Google Scholar
Allan, D. W. (1966). Statistics of atomic frequency standards. Proceedings of the IEEE, 54(2), 221230.CrossRefGoogle Scholar
Anonsen, K. B., and Hallingstad, O. (2007). Sigma point Kalman filter for underwater terrain-based navigation. Proceedings of the IFAC Conference on Control Applications in Marine Systems, Bol, Croatia. (pp. 106110).CrossRefGoogle Scholar
Braga, J., Healey, A. J., and Sousa, J. (2012). Navigation scheme for the LSTS SEACON vehicles: Theory and application. In Navigation. Guidance and Control of Underwater Vehicles, 3(1), 6975).Google Scholar
Christensen, R., Fogh, N., la Cour-Harbo, A., and Bisgaard, M. (2008). Inertial navigation system. Department of Control Engineering in Aalborg University.Google Scholar
Cruz, N., Matos, A., de Sousa, J. B., Pereira, F. L., Silva, J., Silva, E., and Dias, E. B. (2003). Operations with multiple autonomous underwater vehicles: the PISCIS project. In Second Annual Symposium on Autonomous Intelligent Networks and Systems AINS.Google Scholar
de Morais, F. B. (2013). An Advanced Navigation System for Remotely Operated Vehicles. Department of Engineering Cybernatics, Norwegian University of Science and Technology (NTNU).Google Scholar
El-Sheimy, N., Hou, H. and Niu, X. (2008). Analysis and modeling of inertial sensors using Allan variance. Instrumentation and Measurement, IEEE Transactions on, 57(1), 140149.CrossRefGoogle Scholar
Ellingsen, H. (2008). Development of a Low-Cost Integrated Navigation System for USVs. Department of Engineering Cybernetics, Norwegian University of Science and Technology, Trondheim, Norway.Google Scholar
Fallon, M. F., Papadopoulos, G., Leonard, J. J. and Patrikalakis, N. M. (2010). Cooperative AUV navigation using a single maneuvering surface craft. The International Journal of Robotics Research, 29(12), 14611474.CrossRefGoogle Scholar
Foss, H. T. and Meland, E. T. (2007). Sensor Integration for Nonlinear Navigation System in Underwater Vehicles. Department of Engineering and Cybernetics, Norwegian University of Science and Technology (NTNU).Google Scholar
Fossen, T.I. (1994). Guidance and Control of Ocean Vehicles, John Wiley.Google Scholar
Fossen, T.I. (2012). Low-cost integrated navigation systems for autonomos underwater vehicles. Plenary paper presented at the XXXIII Jornadas de Automatica, Vigo, Spain.Google Scholar
Geng, Y., Martins, R., and Sousa, J. (2010). Accuracy analysis of DVL/IMU/magnetometer integrated navigation system using different IMUs in AUV. In Control and Automation (ICCA), 2010 8th IEEE International Conference on (pp. 516521). IEEE.Google Scholar
Grewal, M. S., Weill, L. R. and Andrews, A. P. (2001). Global positioning systems, inertial navigation, and integration. John Wiley & Sons.Google Scholar
Healey, A. J., An, E. P. and Marco, D. B. (1998). Online compensation of heading sensor bias for low cost AUVs. In Autonomous Underwater Vehicles, 1998. AUV'98. Proceedings Of The 1998 Workshop on Underwater Navigation (pp. 3542). IEEE.Google Scholar
Hegrenaes, O., Berglund, E. and Hallingstad, O. (2008). Model-aided inertial navigation for underwater vehicles. Robotics and Automation, ICRA 2008. IEEE International Conference on (pp. 10691076), Pasadena, CA, USA.CrossRefGoogle Scholar
Hofmann-Wellenhof, B., Legat, K. and Wieser, M. (2011). Navigation: principles of positioning and guidance. Springer Science & Business Media.Google Scholar
Hou, H. (2004). Modelling inertial sensors errors using Allan variance. University of Calgary, Department of Geomatics Engineering, University of Calgary, Alberta.Google Scholar
Jalving, B., Gade, K., Hagen, O. K. and Vestgard, K. (2003). A toolbox of aiding techniques for the HUGIN AUV integrated inertial navigation system. In OCEANS 2003. Proceedings (Vol. 2, pp. 11461153). IEEE.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. Modelling Identification and Control, 25(4), 223236. Nice, France.CrossRefGoogle Scholar
Lammas, A. K., Sammut, K. and He, F. (2007). A 6 DoF navigation algorithm for autonomous underwater vehicles. In OCEANS 2007-Europe (pp. 16). IEEE.Google Scholar
Leader, D.E. (1994). Kalman Filter Estimation of Underwater Vehicle Position and Attitude Using a Doppler Velocity Aided Inertial Motion Unit, Engineer Degree Thesis, Massachusetts Institute of Technology and Woods Hole Oceanographic Institution, Massachusetts, September 1994.CrossRefGoogle Scholar
Li, W. and Wang, J. (2013). Effective adaptive Kalman filter for MEMS-IMU/magnetometers integrated attitude and heading reference systems. Journal of Navigation, 66(1), 99113.CrossRefGoogle Scholar
Li, W., Wu, W., Wang, J. and Lu, L. (2013). A fast SINS initial alignment scheme for underwater vehicle applications. Journal of Navigation, 66(2), 181198.CrossRefGoogle Scholar
Liansheng, L. and Tao, J. (2011). Research on Strap-down Inertial Navigation System Simulation. Intelligent Computation Technology and Automation (ICICTA), 2011 International Conference on (Vol. 2, pp. 1168–1171). IEEE.CrossRefGoogle Scholar
LinkQuest Incl. (2013). http://www.link-quest.com/html/NavQuest600M.pdf. Accessed on 5th January 2013.Google Scholar
Mandt, M., Gade, K. and Jalving, B. (2001). Integrating DGPS-USBL position measurements with inertial navigation in the HUGIN 3000 AUV. Proceedings of the 8th Saint Petersburg International Conference on Integrated Navigation Systems, Saint Petersburg, Russia.Google Scholar
Marco, D. B. and Healey, A. J. (2001). Command, control, and navigation experimental results with the NPS ARIES AUV. IEEE Journal of Oceanic Engineering, 26(4), 466476.CrossRefGoogle Scholar
Narayanaswamy, V., Raju, R., Durairaj, M., Ananthapadmanabhan, A., Annamalai, S., Ramadass, G. A. and Atmanand, M. A. (2013). Reliability-Centered Development of Deep Water ROV ROSUB 6000. Marine Technology Society Journal, 47(3), 5571.CrossRefGoogle Scholar
Panish, R. and Taylor, M. (2011). Achieving high navigation accuracy using inertial navigation systems in autonomous underwater vehicles. OCEANS, 2011 IEEE-Spain (pp. 17).Google Scholar
PHINS. (2013). Photonic Inertial Sensors, IXBLUE, France. https://www.ixblue.com/products/phins. Accessed 30 March 2013.Google Scholar
PNI sensors corporation. (2014) PNI sensors corporation. CA, USA. http://www.precisionnav.com/products/tcm. Accessed 25 January 2014 Google Scholar
Ramadass, G. A., Vedachalam, N., Balanagajyothi, V., Ramesh, R. and Atmanand, M. A. (2013). A modeling tool for sensor selection for inertial navigation systems used in underwater vehicles. Ocean Electronics (SYMPOL), 2013 (pp. 175188). IEEE. Kochi, India.CrossRefGoogle Scholar
Simon, D. (2006). Optimal state estimation: Kalman, H infinity, and nonlinear approaches. John Wiley & Sons.CrossRefGoogle Scholar
Teledyne RD Instruments. (2013). http://www.rdinstruments.com/pdfs/wh_navigator_ds_lr.pdf. Accessed 20 January 2013 Google Scholar
Titterton, D.H. and Weston, J.L. (2004). Strapdown inertial navigation technology. The Institution of Electrical Engineers (pp. 344345).Google Scholar
Vedachalam, N., Ramadass, G. A. and Atmanand, M. A. (2014a). Reliability centered modeling for development of deep water Human Occupied Vehicles. Applied Ocean Research, 46, 131143.CrossRefGoogle Scholar
Vedachalam, N., Ramadass, G. A. and Atmanand, M. A. (2014b). Review of Technological Advancements and HSE-Based Safety Model for Deep-Water Human Occupied Vehicles. Marine Technology Society Journal, 48(3), 2542.CrossRefGoogle Scholar
Vedachalam, N., Ramesh, S., Subramanian, A. N., Sathianarayanan, D., Ramesh, R., Harikrishnan, G. and Atmanand, M. A. (2015). Design and development of Remotely Operated Vehicle for shallow waters and polar research. In Underwater Technology (UT), IEEE (pp. 15). Chennai, India.Google Scholar
Welch, G. and Bishop, G. (1995). An introduction to the Kalman filter. Department of Computer Science, University of North Carolina at Chapel Hill, Chapel Hill, NC.Google Scholar
Figure 0

Figure 1. Vehicle orientation in the Earth frame.

Figure 1

Figure 2. Representation of a typical vehicle orientation in the body frame.

Figure 2

Figure 3. Analysis of the white noise characteristics for the DVL sensor using Allan Variance.

Figure 3

Figure 4. Simulation methodology.

Figure 4

Figure 5. Simulation results for the sensor suites.

Figure 5

Table 1. Performance of the various combinations of sensor suites.

Figure 6

Figure 6. Architecture of the navigation system.

Figure 7

Table 2. Description of the hardware used for the navigational system.

Figure 8

Figure 7. Performance validation algorithm using emulator.

Figure 9

Figure 8. Test setup for performance test using the emulation.

Figure 10

Figure 9. System's navigation performance using the emulator.

Figure 11

Table 3. Performance of the system compared with near ideal reference.

Figure 12

Figure 10. Implemented algorithm incorporating KF.

Figure 13

Figure 11. Navigational system tested for performance.

Figure 14

Figure 12. KPA performance for velocity during DVL outages.

Figure 15

Figure 13. Depth plot for underwater navigation.

Figure 16

Figure 14. Geo-referenced plot of underwater navigation.