Abstract
Purpose of Review
The goal of this paper is to review current developments in the area of underwater robotics regarding the use of AI, especially in model learning, robot control, perception and navigation as well as manipulation.
Recent Findings
AI technologies and advanced control techniques are finding their way into robotics systems to deal with complex and challenging conditions and to equip them with higher levels of autonomy.
Summary
Although AI techniques and concepts are already a focus area in research on autonomous underwater systems, broad adoption to commercial systems is still in its infancy. Nonetheless, major advances have been done in recent years, especially on integrating different capabilities (perception, navigation, advanced control) in a single system and with first approaches on interaction and autonomous manipulation.
Introduction
Various socio-political transformations in recent years, such as climate change or the steadily growing world population, require and promote new technologies and the creation of the corresponding infrastructure. This “Green New Deal” has a major impact also on the maritime economy [1]. For example, existing offshore installations, especially in the oil and gas industry, will have to be checked much more frequently and thoroughly than before for their environmental compatibility and a vast number of new offshore parks with corresponding foundation structures are being created in the area of offshore wind energy. Aquaculture plantations take up space in sensitive local ecosystems and require maintenance and monitoring above water and especially underwater and on the seabed. The attempt to better understand the large- and small-scale interrelationships and processes in the oceans and to further investigate the effects of interventions in these ecosystems is also leading to an increase in marine research infrastructures, such as semi-autonomous measuring stations in the sea.
All these infrastructures, some of which are quite complex, must somehow be built, monitored, maintained and, if necessary, dismantled in the future. It is foreseeable that the capacities of conventional diving operations will not be sufficient [2, 3]. Diving operations are also dangerous, highly dependent on weather, wind and waves and only possible down to shallow depths. The deeper they are, the more expensive and dangerous to human health they become.
So what can be done? Ignoring the dangers and simply not looking and not carrying out repairs at all or only when a damaging event occurs is clearly not an option. Making the design and construction of subsea facilities so robust and self-sustaining will not be realistically a viable path either; nature and time will lead to failures sooner or later. As in other industrial sectors, we will have to automate large parts of these necessary processes, but not in the traditional sense, such as in conventional factories with high plant density and very frequent recurring identical processes. Rather, we will have to gradually increase the degree of autonomy of intelligent systems, in which the use of artificial intelligence is playing a crucial role.
In the early stage of robotics and AI, one prominent goal was to build embodied intelligent systems [4]. Some see AI as a field of research that emerged from cybernetics or even as a subdomain of robotics, and others see all of robotics nowadays as a sub-field of AI (a good overview on this is given in [5] and [6••]), so basically all advances in the field of maritime robotics would somehow qualify as “AI”. In the following, however, we will take a closer look and discuss where artificial intelligence is applicable in the different layers of AUVs (autonomous underwater vehicles) and how this can lead to intelligent behaviour and robust systems that can solve challenges in harsh maritime application scenarios. We will furthermore elaborate on selected topics in the area of model learning for vehicle control and manipulation as well as navigation and environment perception.
AI in Underwater Robotics
Machine learning plays a dominant role in the current perception of AI, and it is also indispensable in many domains of maritime robotics. However, AI has significantly more manifestations that are being used in various areas of unmanned underwater vehicles [7••], be it in classical remotely operated vehicles (ROVs), gliders, crawlers up to fully autonomous intervention AUVs like the Cuttlefish depicted in Fig. 1 and all of their (hybrid) variations.
Not taking into account the use of AI-related techniques already in the concept and construction phase of unmanned underwater vehicles (UUVs), major areas that benefit from or imply AI in maritime robotics are as follows (top-down): (1) mission planning, spatio-temporal scheduling, multi-robot deployment coordination and logistics (see [8, 9•], [10]); (2) mission decomposition, task execution [11] and action monitoring [12], behaviour composition using behaviour trees [13]; (3) constraint-based path planning with consideration of adaptive capabilities, sensor coverage planning etc. [14•]; (4) guidance and navigation including SLAM and similar probabilistic sensor-fusion approaches [15], machine learning of system disturbances (for example ML-based magnetic field distortion compensation) [16], underwater obstacle avoidance [17, 18], docking and homing [19]; (5) environment perception and -representation [20], object detection and classification [21•]; (6) introspection and failure detection [22, 23]; (7) model-based control (see the “Modeling” and “Control” sections); (8) object grasping and manipulation, interaction with subsea structures (see the “Control” section).
There have been significant advances in all of these topics of robotics in recent years, which will find their way into maritime robotics or were even driven by UUV research, like the aspects discussed in the following.
Modeling
A robot model is a fundamental tool to predict the behaviour of a system and thereby facilitate trajectory planning, control and localization. In the marine and underwater domain, models are typically computed as the combination of Newtonian rigid-body dynamics, hydrostatic effects due to buoyant forces and hydrodynamics due to the interaction between the robot and its surrounding fluid. Given a geometric representation of the robot and the physical parameters of the surrounding fluid, its motion within the fluid can be computed using the Navier-Stokes equations. This approach however is impractical for any robotic application since, first, full knowledge of the environmental parameters must be accurately estimated, and second, solving a high dimensional problem like the Navier-Stokes on board of a robot’s computer is computationally infeasible.
Literature such as [24] provides finite-dimensional approaches to approximate the hydrodynamics of underwater rigid-bodies, and thereby provides computationally feasible solutions that could be used to design model-based control and observer algorithms. This has become a widely accepted set of equations for motion for unmanned underwater vehicles, expressed as
where \(\varvec{\nu }\) is a vector representing the 6-DOF velocities in a body-fixed frame, and \(\mathbf {R}_b^i \in SO3\) is a rotation matrix from the body-fixed frame \(\{b\}\) to an inertial frame \(\{i\}\). The rest of the parameters can be describer as follows: \(\varvec{M}\) represents the combination of rigid-body and added inertia, \(\varvec{C}(\varvec{\nu })\) the Coriolis and centripetal forces, \(\varvec{d}_{\varvec{\nu }}(\varvec{\nu })\) the hydrodynamic damping effect, \(\varvec{b}\) restoring effects due to buoyant and gravitational forces, and \(\varvec{\tau }\) represents external forces and moments applied on the body.
While the inertia, Coriolis and restoring terms are generally standardized in the literature, the damping term is yet one of the most uncertain and hard to model terms. As described by [24], hydrodynamic damping is mainly due to dissipative forces caused by forced oscillations, viscous skin friction, lifting forces and vortex shedding. Several manifestations of damping models based on various approximations are reported in the literature. The author of [25] identified eight different damping models which are labeled as Fossen [24], uncoupled, Prestero [26], Coe [27], Linear, Gertler-Hagen [28], pitch-yaw and McFarland-Whitcomb [29]. Each of these reported models assumes different properties of vehicle geometry and fluid parameter and thus differs in parameter complexity and coupling effects.
The main challenge when modeling a certain robot is to select the most optimal model that fits the application and populates it with the true coefficients that represent the motion of such robot most accurately. Two paradigms stand out in the literature when approaching this problem: (1) system identification (SI) and (2) model learning. SI is one of the most popular approaches used to estimate the model parameters where observations of the vehicle motion states are gathered in an experimental setup. An optimization process is run to adjust the model parameters while minimizing the error between the observations and predictions. Model learning on the other hand is a pure data-driven approach where no assumptions about a fixed mathematical form of the model are considered. A hypothesis model that relates the robot’s states and actions is built directly from the data using machine learning techniques. We review next SI and model learning approaches applied to underwater vehicles.
System Identification
One of the most common techniques for parameter identification is the least squares (LS) methods which is an optimization algorithm that minimizes the quadratic loss between the observed and predicted data points. Several studies such as [30,31,32,33,34,35,36,37] addressed the identification of low-order decoupled hydrodynamic models using LS techniques. These studies reduced the dynamics of the system to a set of linearly independent differential equations, each representing the motion of the system in one degree of freedom (DOF). To identify the model of the vehicle at hand, various state observers were utilized to gather the necessary measurements.
A sensor fusion approach to observe the states of torpedo-shaped AUV was presented in [38, 39], where a model decoupled into three simplified slightly interacting subsystems (speed, steering and diving) was considered. In these studies, the authors compared the performance the 3-DOF coupled model and an uncoupled model showing that the coupled model outperformed its uncoupled counterpart when evaluated on the same dataset.
An alternative optimization method to LS based on the minimization of a Lyapunov candidate function was presented in [40]. The method presented could be run iteratively and without the need of explicit acceleration measurements. The authors evaluated this method on a ROV to identify a decoupled model, showing that the model parameters remain bounded during identification. This work was extended later by [29, 41] to a identify the parameters of a 6-DOF fully coupled model.
A novel identification method based on a null-space least-squares optimization was presented in [42] to identify a 3-DOF fully coupled second-order modulus model. Only given that the net buoyant force is known beforehand, the authors report being able to simultaneously identify both the vehicle and actuator models, contrary to the rest of the literature which required the actuator model to be identified beforehand.
An approach based on a global derivative-free black-box optimization was presented in [43]. The authors identified a 4-DOF model of the Girona 500 AUV, representing the surge, sway, heave and yaw coordinates. The presented methodology could be applied on-line due to the iterative nature of the optimization algorithm. A framework based on recursive least squares (RLS) optimization was presented in [44] to identify the model parameters of a small ROV. In addition to the parameter estimation module, the authors presented state estimation, collision avoidance and excitation modules to run the identification process in an unsupervised fashion.
An on-line identification method was presented in [45] which takes an initial crude model that was developed from theory. The model parameters are then optimized using a Nedler-Mead simplex algorithm by running a set of open-loop maneuvers with the vehicle. In this work, a decoupled model in yaw, pitch and depth coordinates was selected.
In a comparative study, the authors of [46] evaluated five different hydrodynamic models with varying complexities using an ROV for gathering the required data. The study reports that a 3-DOF coupled second-order modulus model outperformed uncoupled model variations. This work was later extended to a fully coupled 6-DOF Model in [29, 47], showing again that the coupled model outperforms uncoupled ones.
Two comparative studies [25, 48] evaluated the performance of the eight different viscous hydrodynamic models discussed above. Both works report that the Mcfarland-Whitcomb [29], Gertler-Hagen [28] and linear models achieved the lowest errors. In both works, the identification was done using a dataset collected by a small torpedo-shaped AUV.
Model Learning
From our perspective, model learning for underwater vehicles is yet understudied in comparison with system identification for analytical models.
A multi-layer perceptron (MLP) architecture was presented in [49] to identify only the damping term of the model. The authors tested the proposed methodology using a simulation of an AUV and no real sensory data was considered. Another work that used a simulated AUV to generate training data was presented in [50]. The authors compared an MLP and a recurrent neural network (RNN) architecture, showing a slight improvement of the RNN performance over the MLP.
A least squares support vector regression (LS-SVR) was used in [51] to identify the Coriolis and damping terms of a model underwater vehicle by using towing tank experimental data. This method was validated only using a simulated model. An auto-regressive neural network combined with a genetic algorithm was used in [52] to learn the dynamics of a simulated AUV with variable mass due to a payload change. Another simulation based study was presented in [53]. The authors propose a symbolic regression method to automatically construct a parametric model through genetic programming from simple mathematical components. A multi-output Gaussian process regression (GPR) was used in [54] to identify the dynamics of a simulated 6-DOF AUV. The authors showed that the multi-output GPR manages to outperform a RNN-based approach.
The authors of [55] used locally weighted projection regression to compensate the mismatch between the physics-based model and the actual navigation data an AUV. The learned model was validated on experimental data to improve the performance of an extended Kalman filter (EKF)–based observer. A comparison of different machine learning methods was evaluated in [56]. The results showed that ML-based identification outperforms the LS approach; however, the experiments were for each DOF independently. In [57], several variants of support vector regression (SVR) approaches were compared to the McFarland-Whitcomb and Gertler-Hagen approach identified with LS. The authors showed that generally SVR-based models outperformed the physics-based approaches, with a distance-weighted-kernel SVR achieving overall the best performance. This method was extended in [58, 59] to an online framework with added nodes for including and pruning data samples, keeping a consistent performance while changing the system dynamics. This methodology was further adapted in [60] using a long short-term memory (LSTM) network with a memory-efficient rehearsal method to reduce the effect of catastrophic forgetting.
Control
To ensure trajectory tracking or station keeping in the presence of disturbances and uncertainties, motion control is a crucial subsystem of AUVs. Furthermore, most ROVs feature motion control systems to relieve the operator from specific tasks like depth or heading control. Consequently, motion control has been a focus of underwater robotics research for several decades and a variety of control architectures have been proposed. An overview of common controllers is presented by [61] and [62]. Compared to other fields of robotics, the motion control for UUV faces unique challenges that must be addressed. For instance
-
Hydrodynamics are highly non-linear, time varying and subject to a high degree of uncertainty;
-
The dynamic behaviour varies with payload, requiring the motion controller to adapt;
-
The heterogeneity of actuation types on a single vehicle, e.g. thrusters, control surfaces, buoyancy engines and electric/hydraulic drives on a manipulator;
-
Thrusters are characterized by relatively slow dynamics and control rates;
-
Underwater vehicles are often under-actuated with certain degrees-of-freedom remaining uncontrollable.
An additional control problem originates when equipping the underwater system with a robotic manipulator, which still poses big challenges for its real-world deployment [63,64,65]. One challenge is due to the the uncertainty and complexity of the vehicle and hydrodynamics models, as it has been previously mentioned. Additionally, it is especially relevant due to the dynamic coupling of forces between manipulator and vehicle, that is, the motion of the manipulator (and possible contact forces with the environment) can disturb the motion of the vehicle [66]. On the other side, and as previously noted, the fact that most vehicles are underactuated (i.e. equipped with less actuators than degrees of freedom to be controlled) might make the manipulation more complicated, since it requires of higher dexterity and precision [67]. Worth mentioning is a recent a paper describing the control architecture for the “Ocean One” underwater humanoid system based on whole-body control strategies as well as initial experimental field trials [68]. Despite those and other remarkable results and recent advances, the manipulation capabilities and range of operations of underwater systems are still very limited in practical application due to the lack of sufficient dexterity and autonomy. Moreover, the current control strategies still do not consider the vehicle-manipulator system as a homogeneous system, thus not exploiting the full possibilities that such advanced control strategies would also bring for dexterous manipulation.
In recent years, modern control techniques based on tools and methods from the field of AI have been developed to tackle some of these challenges. Notably, this includes various flavours of machine learning (mostly reinforcement learning) and fuzzy-logic based control as well as optimization and decision-making (optimal control). Furthermore, AI methods have been proposed in combination with classical control schemes. The following will present recent advances in AI-based control techniques in the field of underwater robotics.
Reinforcement Learning
With the advent of reinforcement learning (RL) and the promising results this framework has been showing in various robotic applications such as manipulation and indoor navigation, the marine robotics community has been tending to further explore this field for providing solutions where model uncertainty and environmental disturbances are a main hindrance to model-based or classical control approaches. The ability to learn control policies from noisy and high-dimensional sensory inputs could be a potential benefit for marine robots to achieve adaptive behaviour in challenging and harsh environments.
Deep deterministic policy gradient (DDPG) was used by [69] to perform 5-DOF waypoint navigation in an end-to-end fashion to derive a control policy that takes as input the raw sensor information. The position and velocity of the AUV w.r.t the goal and produced thrust were taken as input signals to reach a dynamic goal that is defined by a small neighbourhood around the goal point. The approach was tested using a simulation while using a reward function comprising of euclidean distance and thruster usage. The controllers adaptability was tested by simulating thruster failure wherein one of the thrusters was intentionally switched off during testing. Another study by the same authors [70•] attempted to achieve continuous domain control of a real AUV, based on raw sensor input. The authors used a deep RL actor-critic architecture taking linear and angular velocity readings from the AUV’s Doppler velocity log (DVL) and inertial measurement unit (IMU) and output direct thruster commands. The policy was first pre-trained in simulation for 500 training episodes, and then fine-tuned on the real system. The authors demonstrate that the RL agent was able to account for non-linearities of the AUV dynamics while keeping track of the given command.
The authors of [71] evaluated the performance of deterministic policy gradient (DPG) to learn policies for solving problems such as depth control in the XZ-plane, curved depth tracking and seafloor tracking according to different target trajectories, while assuming constant surge velocity of the AUV. The authors compared their learned policy comparison model-based controllers linear quadratic integral (LQI) and non-linear model predictive controller (NMPC), showing that their method and NMPC outperformed LQI since it uses a linear approximation of the non-linear AUV dynamics. While the DPG achieved performance comparable to that of NMPC, yet due to the availability of the tuned system model, the NMPC was able to achieve faster convergence and smaller overshoot than the model-free DPG.
Another research that used DDPG was reported in [72]. The authors attempted to train a policy to perform tracking control for both straight and curved trajectories of an AUV in the xy-plane. The state-space was defined by the position and velocity of the vehicle, whereas the actions were represented as the motor torques. By training on simulation data, the authors compared the performance of their approach to a PID agent showing that the DDPG controller was both more robust and more stable than the PID controller.
The research in [73] focused on training a RL agent to perform a docking task. This study was also done in simulation where a vehicle was modeled to maneuver only in the vertical plane. This work compared different controller such as DDPG, Deep Q-Network (DQN), PID and an optimal control approach based on minimizing a cost function over a predefined time interval. This study concluded that the DDPG algorithm resulted in the shortest docking time, while PID control took the longest. However, the output of the DDPG policy showed a chattering behaviour that would be unlikely to be performed on a real system.
The authors of [74] presented a benchmarking study on DRL for a docking application of an AUV. Three state-of-the-art model-free methods were evaluated, namely proximal policy optimization (PPO), soft actor critic (SAC), and twin delay deep deterministic policy gradients (TD3). An exhaustive evaluation of reward shaping was performed, showing that TD3 achieved a consistent and efficient docking, in comparison to the other two methods.
A policy-search approach was presented in [75] to learn swimming gaits for a flipper-propelled hexapod robot. The authors proposed the use of a technique called probabilistic inference for learning control for selecting swimming gaits without the knowledge of the system’s dynamics. A simulated robot was used to optimize the policy for several behaviours by bootstrapping from random exploration over controllers. The optimized policies were then transferred onto a real system resulting in substantially different behaviour than the hand-engineered controller.
[76, 77] presented an end-to-end vision-based approach for performing obstacle avoidance in highly unstructured underwater environments such as corals and shipwrecks. Although this method does not follow the RL state-action-reward framework, a policy is learned using supervised behavioural cloning (imitation learning), by taking camera images as input and predicting the pitch and yaw deviations to drive the robot away from obstacles. This approach was extended in [78] where the learned policy was augmented by a goal condition, incentivizing the robot to reach a predefined goal while simultaneously avoiding obstacles.
Fuzzy Logic Control
Fuzzy Logic Control (FLC) has been studied extensively in the context of underwater robotics, e.g. [79,80,81] and [82]. A single input FLC is proposed by [83] and [84] to reduce the design effort and simplify the control structure compared to conventional FLC. An in-depth survey on this topic is provided by [85•]. In recent years, the research around fuzzy control for underwater vehicles has focused on hybrid solutions and extensions. [86] propose a fuzzy controller based on an adaptive neural network. Trajectory tracking using adaptive fuzzy control is reported by [87] and [88]. Adaptive fuzzy sliding mode control is presented by [89] and [90].
Optimal Control
In recent years, optimal control, e.g. linear quadratic regulation (LQR) and model predictive control (MPC), has gained popularity in humanoid or aerial robotics and was also proposed for underwater vehicles. Early examples include the work of [91, 92] and [93]. [92] presents MPC for the AUV yaw angle while [93] considers dive-plane control using adaptive LQR. More recently, [94] present an H-2 optimal controller for the kinematic control of underactuated AUV. [95] combine an optimal PD controller with a robust filter controller to control an hovering AUV despite unknown hydrodynamic parameters. For underwater gliders, LQR is proposed by [96] and [97]. Since the early work of [92], motion control of underwater vehicles using MPC has been extended to two or more coupled DOF. [98] proposes a Lyapunov-based MPC for planar trajectory tracking for an AUV [99]. proposes kinematic MPC in combination with an adaptive dynamic controller for the trajectory tracking problem for a manned underwater vehicle. Experimental results, however, are rarely reported. Notable exceptions are the following works [100]. proposes MPC for the operation of an AUV in hovering- and flight-mode. Depth/surge-velocity-control and depth/pitch-control is developed for the different operating modes and verified experimentally [101] develop a nonlinear model predictive positioning controller to reject estimated disturbances in 6-DOF. The controller was verified using a hardware-in-the-loop simulation. A combination of nonlinear MPC and SMC was proposed by [102•] in which experimental results from pool tests using the Flatfish AUV [103] are reported.
AI-Extended Classical Control
The PID controller (proportional integral derivative) and SMC (sliding mode control) are among the most widely used control methods in underwater robotics. Extending these well developed classical controllers with AI methods is a common approach to introduce the ability to adapt to uncertain or changing parameters, e.g. due to varying payloads or unmodelled hydrodynamics. In [104] the authors propose a fuzzy-based auto-tuning component to extend a classical PID controller for an AUV. The fuzzy reasoner takes as input the error and the error change and outputs updates to the PID gains. A similar approach is presented in [105]. The authors propose a PID auto-tuning algorithm using a neural network. The neural network is used to chose the PID gains online in order to minimize tracking error and achieve stability. The effectiveness of the approach is verified experimentally in pool experiments. In [106], the authors propose a neural-network-based nonlinear SMC for underwater vehicles. The neural network is introduced to approximates the umodelled hydrodynamics and estimate the vehicle velocity.
To conclude, several control strategies have been proposed for underwater vehicles. Extensive research has been performed on sliding mode and fuzzy control; however, linear PID-based methods are still frequently used. Several advanced control strategies have been proposed in research with the focus on combining or extending previous methods and tailoring them towards specific vehicles. In recent years, optimal control and reinforcement learning is playing an increasing role in underwater robotics. Simulation results indicate the benefits of modern control strategies; however, experimental results from pool tests or field trials are rarely reported.
Perception and Navigation
Perception in the underwater environment is mainly done with acoustic or visual sensors [107]. Typical acoustic sensors are acoustic measurement devices such as DVL (speed over ground, distance to ground), localization devices such as LBL and USBL (position relative to fixed stations) as well as imaging sonars such as multi-beam-echosounders (MBES), side-scan-sonars (SSS) or multibeam-sonars which all create an acoustic representation of the surrounding environment, often in the form of an image where the pixel intensity represents the degree of reflected acoustic waves. Visual sensors usually consist of a camera system together with an illumination source. These create two-dimensional images with the pixel intensity representing colour or greyscale information of the surrounding environment. A challenge of using such sensors is the the abundant sources of noise present in this natural environment: changes in water composition (salinity, temperature, depth), presence of air bubbles or disturbed sediment affect sonar sensors whereas turbidity affects visual sensors. Dealing with noisy data therefore becomes a main tasks for successful sensor data processing and interpretation. This is an area in which AI methods have proven very successful, and they have been applied to a number of tasks improving the results of textbook approaches. One example of an area where AI methods can be helpful is the complex task of docking an AUV system into a docking-station (see example in Fig. 2). While a number of approaches and physical solutions have been proposed in literature (e.g. [108, 109]), most suffer from limitations described above. In [19], a system combining the sensor data from a camera system with a multi-magnetometer sensor system to achieve docking guidance is described. The relative position between the marker target and the camera/magnetometer system was machine-learned using both an MLP network as well as a support vector regression approach in clear water, with the camera-based positioning as feedback signal. Afterward, the guidance could even be achieved if no camera image was present at all, leading to a much more stable system for a variety of environmental situations.
AUV DeepLeng docking at the under-ice docking-station in Abisko, Sweden [19]
Another area which links the topics of perception and navigation closely together is SLAM (simultaneous localization and mapping). While initially realized in structured, indoor environments and with specialized sensors (such as laser-scanners), many vision-only systems have been described over the years. For the use with underwater robotic systems, SLAM has been proven to work in natural environments if additional sensors (such as orientation/compass, speed over ground, ambient pressure) are used in conjunction with visual/sonar sensors. One such example is the work by Eustice [110], as well as work by the authors [111, 112]. One of the key challenges in these algorithms is their robustness to noise, which is addressed by fusing of a number of data sources to provide superior navigation properties to the vehicle which employ these [113, 114].
An opportunity of on-line sensor processing on a vehicle is the possibility not only to execute a pre-defined mission but to adapt this mission according to the measurements taken with various sensor systems. This is known as perception-based planning [115] and has many applications, e.g. interrupting a search-pattern of an AUV to follow a halo-/thermocline encountered [116] or adapting a vehicle’s initially defined path to ensure complete sensor coverage of an area (coverage planning) [117]. The basic idea behind perception-based planning is to move the planning step for a mission from an off-line (preparatory) step into an on-line system running on the vehicle during mission execution. This on-line planner creates the initial mission similar to its offline counterpart (with fixed mission parameters and goals), but is fed selected sensor data which enables it to react to mission-relevant information and alter or re-plan the mission. A very basic example would be the case of obstacle-avoidance [118], where a sensor (e.g. forward-looking sonar) detects an obstacle in the vehicle’s path and reports this to the on-line planning system. This system then tries to circumvent the obstacle while still reaching the mission goal, only aborting the mission if it cannot be fulfilled anymore.
Conclusions
The exploration and operation in underwater environments pose enormous challenges not only for humans but also for robotic systems. Though robotics and AI technologies advanced tremendously in the last 50 years in terrestrial and space applications, there has been a lower rate of robotics introduction in the underwater domain. However, in the last two decades, we are seeing an increasing interest in underwater robotics, both by bringing existing research from other areas to the underwater domain and by developing novel approaches to deal with the unique conditions of that environment. With respect to other more robotized areas (like the land-based industrial domain), underwater robotics is still in its infancy, however gaining rapidly momentum and recovering the gap. In contrast to other domains, and given the harsh environments, the autonomous capabilities are here of utmost importance. Currently, mainly systems developed by research institutes can show the integration of several autonomous capabilities in one system such as perception, advanced dynamic control, navigation, task planning, and even some initial manipulation and interaction capabilities, while mainstream adoption into the maritime industry is still pending.
In this paper, we highlighted some of the recent advances in AI for navigation and control of underwater robots and believe that the main challenge ahead lies in integrating these techniques in resilient and long-term capable autonomous systems in the first place, as well as in proving that such AI-enabled systems can function reliably in maritime real-world scenarios.
References
Papers of particular interest, published recently, have been highlighted as: • Of importance •• Of major importance
Dundas SJ, Levine AS, Lewison RL, Doerr AN, White C, Galloway AW, Garza C, Hazen EL, Padilla-Gamiño J, Samhouri JF, et al. Integrating oceans into climate policy: any green new deal needs a splash of blue. Conserv Lett. 2020;13(5):12716.
Fortuna N. Divers needed. UnderWater Magazine May/June; 2021
Lee J, Zhao F. Global wind report 2021. Global Wind Energy Council: Technical report; 2021.
Feigenbaum EA, Feldman J, et al. Computers and Thought. New York, NY: McGraw-Hill; 1963.
Rajan K, Saffiotti A. Towards a science of integrated AI and Robotics. Elsevier; 2017
•• Murphy RR. Introduction to AI Robotics. Cambridge, MA: MIT press; 2019. The book gives a very good overview of important AI topics for autonomous systems and could work also as an introduction to AI itself.
•• Kirchner F, Straube S, Kühn D, Hoyer N. AI technology for underwater robots. Springer, Cham, CH; 2020. https://doi.org/10.1007/978-3-030-30683-0. The book gives an overview of current challenges of underwater robotics in different aspects (system design, communication, machine learning, mapping and coordination, adaptive mission planning) and insights about next generation underwater robots.
Roehr TM, Kirchner F. Spatio-temporal planning for a reconfigurable multi-robot system. In: Finzi A, Karpas E, editors. Proceedings of the 4th workshop on planning and robotics (PlanRob). London; 2016. pp. 135–146
• Thompson F, Guihen D. Review of mission planning for autonomous marine vehicle fleets. Journal of Field Robotics. 2019;36(2):333–54. Gives an in-depth overview on major mission planning topics for autonomous marine vehicles and multirobot teams including task decomposition, task allocation and replanning.
Cashmore M, Fox M, Long D, Magazzeni D, Ridder B. Opportunistic planning in autonomous underwater missions. IEEE Trans Autom Sci Eng. 2017;15(2):519–30.
Schillinger P, Bürger M, Dimarogonas DV. Simultaneous task allocation and planning for temporal logic goals in heterogeneous multi-robot systems. Int J Robot Res. 2018;37(7):818–38.
Cashmore M, Fox M, Long D, Magazzeni D, Ridder B, Carrera A, Palomeras N, Hurtos N, Carreras M. Rosplan: Planning in the robot operating system. In: Proceedings of the international conference on automated planning and scheduling. 2015. vol 25, pp 333–341
Colledanchise M, Ögren P. Behavior trees in robotics and AI: an introduction. Boca Raton, FL: CRC Press; 2018.
• Panda M, Das B, Subudhi B, Pati BB. A comprehensive review of path planning algorithms for autonomous underwater vehicles. Int J Autom Comput. 2020;17(3):321–52. Comprehensive review on path planning algorithms for AUVs also taking into account unpredictable environments.
Thrun S. Probabilistic robotics. Commun ACM. 2002;45(3):52–7.
Christensen L, Krell M, Kirchner F. Learning magnetic field distortion compensation for robotic systems. In: 2017 IEEE/RSJ international conference on intelligent robots and systems (IROS). IEEE; 2017. pp 3516–3521
Braginsky B, Guterman H. Obstacle avoidance approaches for autonomous underwater vehicle: simulation and experimental results. IEEE Journal of Oceanic Engineering. 2016;41(4):882–92.
Yuan J, Wang H, Zhang H, Lin C, Yu D, Li C. Auv obstacle avoidance planning based on deep reinforcement learning. Journal of Marine Science and Engineering. 2021;9(11):1166.
Hildebrandt M, Christensen L, Kirchner F. Combining cameras, magnetometers and machine-learning into a close-range localization system for docking and homing. In: OCEANS 2017 - Anchorage. 2017. pp 1–6
Carrió JH, Arnold S, Böckmann A, Born A, Domínguez R, Kirchner F. Envire-environment representation for long-term autonomy. In: AI for long-term autonomy workshop of the Int Conf on robotics and automation (ICRA). 2016
• Moniruzzaman M, Islam SMS, Bennamoun M, Lavery P. Deep learning on underwater marine object detection: a survey. In: International conference on advanced concepts for intelligent vision systems. Springer; 2017. pp 150–160. Indepth introduction to Deep Learning for underwater marine object detection and a survey of recent developments in that area.
Wu H, Guan Y, Rojas J. A latent state-based multimodal execution monitor with anomaly detection and classification for robot introspection. Appl Sci. 2019;9(6):1072.
Fox M, Ghallab M, Infantes G, Long D. Robot introspection through learned hidden Markov models. Artificial Intelligence. 2006;170(2):59–113.
Fossen TI. Guidance and control of ocean vehicles. Chichester, UK: John Wiley & Sons Inc; 1994.
McCarter BR. Experimental evaluation of viscous hydrodynamic force models for autonomous underwater vehicles. PhD thesis, Virginia Tech; 2014
Prestero TTJ: Verification of a six-degree of freedom simulation model for the remus autonomous underwater vehicle. PhD thesis, Massachusetts institute of technology (2001)
Coe RG. Improved underwater vehicle control and maneuvering analysis with computational fluid dynamics simulations. PhD thesis, Virginia Tech; 2013
Gertler M, Hagen GR. Standard equations of motion for submarine simulation. David w Taylor Naval Ship Research and Development Center Bethesda MD: Technical report; 1967.
McFarland CJ, Whitcomb LL. Comparative experimental evaluation of a new adaptive identifier for underwater vehicles. In: ICRA. IEEE; 2013. pp 4614–4620
Caccia M, Indiveri G, Veruggio G. Modeling and identification of open-frame variable configuration unmanned underwater vehicles. IEEE Journal of Oceanic Engineering. 2000;25(2):227–40.
Ridao P, Battle J, Carreras M. Model identification of a low-speed uuv. IFAC Proceedings Volumes. 2001;34(7):395–400.
El-Fakdi A, Tiano A, Ridao P, Batlle J. Identification of non linear models of unmanned underwater vehicles: comparison between two identification methods. IFAC Proceedings Volumes. 2003; 36(21), 13–18. https://doi.org/10.1016/S1474-6670(17)37776-5. 6th IFAC Conference on Manoeuvring and Control of Marine Craft (MCMC 2003), Girona, Spain, 17-19 September, 1997
Smallwood DA, Whitcomb LL. Preliminary identification of a dynamical plant model for the Jason 2 underwater robotic vehicle. In: Oceans 2003. Celebrating the Past... Teaming Toward the Future (IEEE Cat. No. 03CH37492). IEEE; 2003. vol 2, pp 688–695
Conte G, Zanoli S, Scaradozzi D, Conti A. Evaluation of hydrodynamics parameters of a UUV. A preliminary study. In: First International Symposium on Control, Communications and Signal Processing, 2004. IEEE; 2004. pp 545–548.
Tiano A, Sutton R, Lozowicki A, Naeem W. Observer kalman filter identification of an autonomous underwater vehicle. Control Engineering Practice. 2007;15(6):727–39.
Avila JPJ, Adamowski JC, Maruyama N, Takase FK, Saito M. Modeling and identification of an open-frame underwater vehicle: the yaw motion dynamics. J Intell Robot Syst. 2012;66(1–2):37–56.
Natarajan S, Gaudig C, Hildebrandt M. Offline experimental parameter identification using on-board sensors for an autonomous underwater vehicle. In: Oceans, 2012. IEEE; 2012. pp 1–8.
Fauske KM, Gustafsson F, Hegrenaes O: Estimation of AUV dynamics for sensor fusion. In: 2007 10th international conference on information fusion. IEEE; 2007. pp 1–6.
Hegrenaes O, Hallingstad O, Jalving B. Comparison of mathematical models for the HUGIN 4500 AUV based on experimental data. In: 2007 symposium on underwater technology and workshop on scientific use of submarine cables and related technologies. IEEE; 2007. pp 558–567.
Smallwood DA, Whitcomb LL. Adaptive identification of dynamically positioned underwater robotic vehicles. IEEE Transactions on Control Systems Technology. 2003;11(4):505–15.
Paine TM, Whitcomb LL. Adaptive parameter identification of underactuated unmanned underwater vehicles: a preliminary simulation study. In: OCEANS 2018 MTS/IEEE Charleston. IEEE; 2018. pp 1–6.
Harris ZJ, Paine TM, Whitcomb LL. Preliminary evaluation of null-space dynamic process model identification with application to cooperative navigation of underwater vehicles. In: 2018 IEEE/RSJ international conference on intelligent robots and systems (IROS). IEEE; 2018. pp 3453–3459.
Karras GC, Bechlioulis CP, Leonetti M, Palomeras N, Kormushev P, Kyriakopoulos KJ, Caldwell DG. On-line identification of autonomous underwater vehicles through global derivative-free optimization. In: 2013 IEEE/RSJ international conference on intelligent robots and systems (IROS). IEEE; 2013. pp 3859–3864.
Karras GC, Marantos P, Bechlioulis CP, Kyriakopoulos KJ: Unsupervised online system identification for underwater robotic vehicles. IEEE Journal of Oceanic Engineering (2018)
Rentschler ME, Hover FS, Chryssostomidis C. System identification of open-loop maneuvers leads to improved AUV flight performance. IEEE Journal of Oceanic Engineering. 2006;31(1):200–8.
Martin SC, Whitcomb LL. Preliminary results in experimental identification of 3-DOF coupled dynamical plant for underwater vehicles. In: OCEANS 2008. IEEE; 2008. pp 1–9.
Martin SC, Whitcomb LL. Experimental identification of six-degree-of-freedom coupled dynamic plant models for underwater robot vehicles. IEEE Journal of Oceanic Engineering. 2013;39(4):662–71.
Gibson SB, McCarter B, Stilwell DJ, Neu WL. A comparison of hydrodynamic damping models using least-squares and adaptive identifier methods for autonomous underwater vehicles. In: OCEANS 2015-MTS/IEEE Washington. IEEE; 2015. pp 1–7.
Van De Ven PW, Johansen TA, Sørensen AJ, Flanagan C, Toal D. Neural network augmented identification of underwater vehicle models. Control Engineering Practice. 2007;15(6):715–25.
Amin R, Khayyat A, Osgouie K. Neural networks modeling of autonomous underwater vehicle. In: Proceedings of 2010 IEEE/ASME international conference on mechatronic and embedded systems and applications. IEEE; 2010. pp 14–19.
Xu F, Zou Z-J, Yin J-C, Cao J. Identification modeling of underwater vehicles’ nonlinear dynamics based on support vector machines. Ocean Eng. 2013;67:68–76.
Shafiei M, Binazadeh T. Application of neural network and genetic algorithm in identification of a model of a variable mass underwater vehicle. Ocean Eng. 2015;96:173–80.
Wu N-L, Wang X-Y, Ge T, Wu C, Yang R. Parametric identification and structure searching for underwater vehicle model using symbolic regression. J Marine Sci Technol. 2017;22(1):51–60.
Ramirez WA, Kocijan J, Leong ZQ, Nguyen HD, Jayasinghe SG. Dynamic system identification of underwater vehicles using multi-output Gaussian processes. Int J Autom Comput. 2021;18(5):681–93.
Fagogenis G, Flynn D, Lane DM. Improving underwater vehicle navigation state estimation using locally weighted projection regression. In: 2014 IEEE international conference on robotics and automation (ICRA), IEEE; 2014. pp 6549–6554.
Wehbe B, Hildebrandt M, Kirchner F. Experimental evaluation of various machine learning regression methods for model identification of autonomous underwater vehicles. In: 2017 IEEE international conference on robotics and automation (ICRA), IEEE; 2017. pp 4885–4890.
Wehbe B, Krell MM: Learning coupled dynamic models of underwater vehicles using support vector regression. In: OCEANS 2017 - Aberdeen, pp 1–7 (2017)
Wehbe B, Fabisch A, Krell MM. Online model identification for underwater vehicles through incremental support vector regression. In: 2017 IEEE/RSJ international conference on intelligent robots and systems (IROS). 2017. pp 4173–4180. https://doi.org/10.1109/IROS.2017.8206278
Wehbe B, Hildebrandt M, Kirchner F. A framework for on-line learning of underwater vehicles dynamic models. In: 2019 international conference on robotics and automation (ICRA). IEEE; 2019. pp 7969–7975.
Bande M, Wehbe B. Online model adaptation of autonomous underwater vehicles with LSTM networks. In: OCEANS 2021: San Diego–Porto. IEEE; 2021. pp 1–6.
Fossen TI. Handbook of marine craft hydrodynamics and motion control. John Wiley & Sons, Ltd, Chichester, UK; 2011. https://doi.org/10.1002/9781119994138
Antonelli G. Underwater robots. Springer Tracts in Advanced Robotics, vol 123. Springer International Publishing, Cham; 2018. https://doi.org/10.1007/978-3-319-77899-0
Ridao P, Carreras M, Ribas D, Sanz PJ, Oliver G. Intervention AUVs: the next challenge. IFAC Proceedings Volumes. 2014; 47(3), 12146–12159. 19th IFAC World Congress
Petillot YR, Antonelli G, Casalino G, Ferreira F. Underwater robots: from remotely operated vehicles to intervention-autonomous underwater vehicles. IEEE Robotics Automation Magazine. 2019;26(2):94–101.
de Gea Fernández J, Ott C, Wehbe B. Machine learning and dynamic whole body control for underwater manipulation. In: Kirchner F, Straube S, Kühn D, Hoyer N, editors. AI Technology for Underwater Robots, pp 107–115. Cham: Springer; 2020.
Barbalata C, Dunnigan MW, Petillot Y. Position/force operational space control for underwater manipulation. Robotics and Autonomous Systems. 2018;100:150–9.
Haugaløkken BOA, Jørgensen EK, Schjølberg I. Experimental validation of end-effector stabilization for underwater vehicle-manipulator systems in subsea operations. Robotics and Autonomous Systems. 2018;109:1–12.
Brantner G, Khatib O. Controlling Ocean One: human-robot collaboration for deep-sea manipulation. Journal of Field Robotics. 2021;38(1):28–51.
Carlucho I, De Paula M, Wang S, Menna BV, Petillot YR, Acosta GG. AUV position tracking control using end-to-end deep reinforcement learning. In: OCEANS 2018 MTS/IEEE Charleston. IEEE; 2018. pp 1–8.
• Carlucho I, De Paula M, Wang S, Petillot Y, Acosta GG. Adaptive low-level control of autonomous underwater vehicles using deep reinforcement learning. Robotics and Autonomous Systems. 2018;107:71–86. Not only provides a working learning algorthim for under-water vehicle control, but shows its real-life application on an actual vehicle with very promising results.
Wu H, Song S, You K, Wu C. Depth control of model-free AUVs via reinforcement learning. IEEE Transactions on Systems, Man, and Cybernetics: Systems. 2018;49(12):2499–510.
Yu R, Shi Z, Huang C, Li T, Ma Q. Deep reinforcement learning based optimal trajectory tracking control of autonomous underwater vehicle. In: 2017 36th Chinese Control Conference (CCC). IEEE; 2017. pp 4958–4965.
Anderlini E, Parker GG, Thomas G. Docking control of an autonomous underwater vehicle using reinforcement learning. Applied Sciences. 2019; 9(17). https://doi.org/10.3390/app9173456
Patil M, Wehbe B, Valdenegro-Toro M. Deep reinforcement learning for continuous docking control of autonomous underwater vehicles: a benchmarking study. In: OCEANS 2021: San Diego–Porto. IEEE; 2021. pp 1–7.
Meger D, Higuera JCG, Xu A, Giguere P, Dudek G. Learning legged swimming gaits from experience. In: 2015 IEEE international conference on robotics and automation (ICRA). IEEE; 2015. pp 2332–2338.
Manderson T, Higuera JCG, Cheng R, Dudek G. Vision-based autonomous underwater swimming in dense coral for combined collision avoidance and target selection. In: 2018 IEEE/RSJ international conference on intelligent robots and systems (IROS). IEEE; 2018. pp 1885–1891.
Karapetyan N, Johnson JV, Rekleitis I. Human diver-inspired visual navigation: towards coverage path planning of shipwrecks. Marine Technology Society Journal. 2021;55(4):24–32.
Manderson T, Higuera JCG, Wapnick S, Tremblay J-F, Shkurti F, Meger D, Dudek G. Vision-based goal-conditioned policies for underwater navigation in the presence of obstacles. arXiv preprint arXiv:2006.16235 (2020)
Teo K, An E, Beaujean P-PJ. A robust fuzzy autonomous underwater vehicle (AUV) docking approach for unknown current disturbances. IEEE Journal of Oceanic Engineering. 2012;37(2):143–55. https://doi.org/10.1109/JOE.2011.2180058.
Raeisy B, Safavi AA, Khayatian AR. Optimized fuzzy control design of an autonomous underwater vehicle. Iranian Journal of Fuzzy Systems. 2012;9(2):25–41. https://doi.org/10.22111/ijfs.2012.190.
Chang W-J, Chang W, Liu H-H. Model-based fuzzy modeling and control for autonomous underwater vehicles in the horizontal plane. Journal of Marine Science and Technology. 2003;11(3) . https://doi.org/10.51400/2709-6998.2276
Jun SW, Lee HJ, et al. Design of TS fuzzy-model-based controller for depth control of autonomous underwater vehicles with parametric uncertainties. In: 2011 11th international conference on control, automation and systems. IEEE; 2011. pp 1682–1684.
Amjad M, Ishaque K, Abdullah SS, Salam Z. An alternative approach to design a Fuzzy Logic Controller for an autonomous underwater vehicle. In: 2010 IEEE conference on cybernetics and intelligent systems. IEEE, Singapore; 2010. pp 195–200. https://doi.org/10.1109/ICCIS.2010.5518556
Ishaque K, Abdullah SS, Ayob SM, Salam Z. A simplified approach to design fuzzy logic controller for an underwater vehicle. Ocean Eng. 2011;38(1):271–84. https://doi.org/10.1016/j.oceaneng.2010.10.017.
• Xiang X, Yu C, Lapierre L, Zhang J, Zhang Q. Survey on fuzzy-logic-based guidance and control of marine surface vehicles and underwater vehicles. International Journal of Fuzzy Systems. 2018;20(2):572–86. https://doi.org/10.1007/s40815-017-0401-3. Provides an in-depth review and current trends of fuzzy-logic-based guidance and control approaches in underwater robotics.
Salman S, Anavatti SA, Asokan T. Adaptive fuzzy control of unmanned underwater vehicles. Indian Journal of Geo-Marine Science. 2011;40:168–75.
Yu C, Xiang X, Zhang Q, Xu G. Adaptive fuzzy trajectory tracking control of an under-actuated autonomous underwater vehicle subject to actuator saturation. International Journal of Fuzzy Systems. 2018;20(1):269–79. https://doi.org/10.1007/s40815-017-0396-9.
Zhang Z, Wu Y. Adaptive fuzzy tracking control of autonomous underwater vehicles with output constraints. IEEE Transactions on Fuzzy Systems. 2021;29(5):1311–9. https://doi.org/10.1109/TFUZZ.2020.2967294.
Londhe PS, Patre BM. Adaptive fuzzy sliding mode control for robust trajectory tracking control of an autonomous underwater vehicle. Intelligent Service Robotics. 2019;12(1):87–102. https://doi.org/10.1007/s11370-018-0263-z.
Chu Z, Xiang X, Zhu D, Luo C, Xie D. Adaptive fuzzy sliding mode diving control for autonomous underwater vehicle with input constraint. International Journal of Fuzzy Systems. 2018;20(5):1460–9. https://doi.org/10.1007/s40815-017-0390-2.
Spangelo I, Egeland O. Trajectory planning and collision avoidance for underwater vehicles using optimal control. IEEE Journal of Oceanic Engineering. 1994;19(4), 502–511. https://doi.org/10.1109/48.338386
Naeem W. Model predictive control of an autonomous underwater vehicle. In: Proceedings of UKACC 2002 Postgraduate Symposium. Citeseer, Sheffield, UK; 2002. pp 19–23.
Narasimhan M, Singh SN. Adaptive optimal control of an autonomous underwater vehicle in the dive plane using dorsal fins. Ocean Eng. 2006;33(3–4):404–16. https://doi.org/10.1016/j.oceaneng.2005.04.017.
Wadoo SA, Sapkota S, Chagachagere K. Optimal control of an autonomous underwater vehicle. In: 2012 IEEE Long Island systems, applications and technology conference (LISAT). IEEE, Farmingdale, NY, USA; 2012. pp 1–6. https://doi.org/10.1109/LISAT.2012.6223100
Song YS, Arshad MR. Robust optimal depth control of Hovering Autonomous Underwater Vehicle. In: 2017 IEEE 2nd international conference on automatic control and intelligent systems (I2CACIS). IEEE, Kota Kinabalu; 2017. pp 191–195. https://doi.org/10.1109/I2CACIS.2017.8239056
Tchilian RdS, Rafikova E, Gafurov SA, Rafikov M. Optimal control of an underwater glider vehicle. Procedia Eng. 2017;176:732–40. https://doi.org/10.1016/j.proeng.2017.02.322.
Ullah B, Ovinis M, Baharom MB, Ali SSA, Javaid MY. Pitch and depth control of underwater glider using LQG and LQR via Kalman filter. International journal of vehicle structures and systems. 2018;10(2). https://doi.org/10.4273/ijvss.10.2.12
Shen C, Shi Y, Buckham B. Trajectory tracking control of an autonomous underwater vehicle using lyapunov-based model predictive control. IEEE Transactions on Industrial Electronics. 2018;65(7):5796–805. https://doi.org/10.1109/TIE.2017.2779442.
Gan W, Zhu D, Hu Z, Shi X, Yang L, Chen Y. Model predictive adaptive constraint tracking control for underwater vehicles. IEEE Transactions on Industrial Electronics. 2020;67(9):7829–40. https://doi.org/10.1109/TIE.2019.2941132.
Steenson LV. Experimentally verified model predictive control of a hover-capable AUV. PhD thesis, University of Southampton; 2013
Cao Y, Li B, Li Q, Stokes AA, Ingram DM, Kiprakis A. A nonlinear model predictive controller for remotely operated underwater vehicles with disturbance rejection. IEEE Access. 2020;8:158622–34. https://doi.org/10.1109/ACCESS.2020.3020530.
• Saback RM, Conceicao AGS, Santos TLM, Albiez J, Reis M. Nonlinear model predictive control applied to an autonomous underwater vehicle. IEEE Journal of Oceanic Engineering. 2020;45(3):799–812. https://doi.org/10.1109/JOE.2019.2919860. Presents a combination of nonlinear model predictive control and sliding mode control for an autonomous underwater vehicle. Experimental results are reported and indicate the effectiveness of the proposed control chain.
Albiez J, Joyeux S, Gaudig C, Hilljegerdes J, Kroffke S, Schoo C, Arnold S, Mimoso G, Alcantara P, Saback R, Britto J, Cesar D, Neves G, Watanabe T, Merz Paranhos P, Reis M, Kirchner F. Flatfish - a compact subsea-resident inspection AUV. In: OCEANS 2015 - MTS/IEEE Washington; 2015. pp 1–8. https://doi.org/10.23919/OCEANS.2015.7404442
Khodayari MH, Balochian S. Modeling and control of autonomous underwater vehicle (AUV) in heading and depth attitude via self-adaptive fuzzy PID controller. J Marine Sci Technol. 2015;20(3):559–78. https://doi.org/10.1007/s00773-015-0312-7.
Hernández-Alvarado R, García-Valdovinos L, Salgado-Jiménez T, Gómez-Espinosa A, Fonseca-Navarro F. Neural network-based self-tuning PID control for underwater vehicles. Sensors. 2016;16(9):1429. https://doi.org/10.3390/s16091429.
Guo X, Yan W, Cui R. Neural network-based nonlinear sliding-mode control for an AUV without velocity measurements. Int J Control. 2019;92(3):677–92. https://doi.org/10.1080/00207179.2017.1366669.
Cong Y, Gu C, Zhang T, Gao Y. Underwater robot sensing technology: a survey. Fundamental Research. 2021;1(3):337–45.
Brighenti A, Zugno L, Mattiuzzo F, Sperandio A. Eurodocker-a universal docking-downloading recharging system for AUVs: conceptual design results. In: IEEE oceanic engineering society. OCEANS’98. Conference Proceedings (Cat. No. 98CH36259). IEEE; 1998. vol 3, pp 1463–1467.
Murarka A, Kuhlmann G, Gulati S, Sridharan M, Flesher C, Stone WC. Vision-based frozen surface egress: a docking algorithm for the ENDURANCE AUV. In: International Symposium on Unmanned Untethered Submersible Technology (UUST). 2009
Eustice RM, Singh H, Leonard JJ. Exactly sparse delayed-state filters for view-based slam. IEEE Trans Robot. 2006;22(6):1100–14. https://doi.org/10.1109/TRO.2006.886264.
Hildebrandt M, Kirchner F. Imu-aided stereo visual odometry for ground-tracking AUV applications. In: OCEANS’10 IEEE SYDNEY. IEEE; 2010. pp 1–8.
Hildebrandt M. Development, evaluation and validation of a stereo camera underwater slam algorithm. PhD thesis, Staats-und Universitätsbibliothek Bremen; 2014
Liu P, Wang B, Deng Z, Fu M. INS/DVL/PS tightly coupled underwater navigation method with limited DVL measurements. IEEE Sensors J. 2018;18(7):2994–3002. https://doi.org/10.1109/JSEN.2018.2800165.
Shaukat N, Ali A, Javed Iqbal M, Moinuddin M, Otero P. Multi-sensor fusion for underwater vehicle localization by augmentation of RBF neural network and error-state Kalman filter. Sensors 21(4) (2021). https://doi.org/10.3390/s21041149
Hwang J, Bose N, Fan S. AUV adaptive sampling methods: a review. Applied Sciences. 2019;9(15). https://doi.org/10.3390/app9153145
Petillo S, Balasuriya A, Schmidt H. Autonomous adaptive environmental assessment and feature tracking via autonomous underwater vehicles. In: OCEANS’10 IEEE SYDNEY. IEEE; 2010. pp 1–9.
Shi J, Zhou M. A data-driven intermittent online coverage path planning method for AUV-based bathymetric mapping. Appl Sci. 2020;10(19):6688.
Cheng C, Sha Q, He B, Li G. Path planning and obstacle avoidance for AUV: a review. Ocean Eng. 2021;235:109355.
Funding
Open Access funding enabled and organized by Projekt DEAL. The authors report grants from several German Federal Ministries (BMBF O1lS17029A, BMWi 50 NA 2002, BMWi 50 NA 1704) for part of their research, but they do not pertain to this paper.
Author information
Authors and Affiliations
Corresponding authors
Ethics declarations
Conflict of Interest
The authors declare no competing interests.
Human and Animal Rights and Informed Consent
This article does not contain any studies with human or animal subjects performed by any of the authors.
Additional information
Publisher's Note
Springer Nature remains neutral with regard to jurisdictional claims in published maps and institutional affiliations.
This article is part of the Topical Collection on Underwater Robotics
Rights and permissions
Open Access This article is licensed under a Creative Commons Attribution 4.0 International License, which permits use, sharing, adaptation, distribution and reproduction in any medium or format, as long as you give appropriate credit to the original author(s) and the source, provide a link to the Creative Commons licence, and indicate if changes were made. The images or other third party material in this article are included in the article's Creative Commons licence, unless indicated otherwise in a credit line to the material. If material is not included in the article's Creative Commons licence and your intended use is not permitted by statutory regulation or exceeds the permitted use, you will need to obtain permission directly from the copyright holder. To view a copy of this licence, visit http://creativecommons.org/licenses/by/4.0/.
About this article
Cite this article
Christensen, L., de Gea Fernández, J., Hildebrandt, M. et al. Recent Advances in AI for Navigation and Control of Underwater Robots. Curr Robot Rep 3, 165–175 (2022). https://doi.org/10.1007/s43154-022-00088-3
Accepted:
Published:
Issue Date:
DOI: https://doi.org/10.1007/s43154-022-00088-3
Keywords
- AI
- Underwater robotics
- AUV
- Machine learning
- Model learning
- control