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.

Fig. 1
figure 1

Dual-arm intervention AUV Cuttlefish hovering in upright manipulation pose in front of a subsea panel at DFKI RIC’s test basin

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

$$\begin{aligned} \varvec{\tau } = \varvec{M}\dot{\varvec{\nu }} + \varvec{C}(\varvec{\nu })\varvec{\nu } + \varvec{d}_{\varvec{\nu }}(\varvec{\nu }) + \varvec{b}(\mathbf {R}_b^i) \end{aligned}$$
(1)

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.

Fig. 2
figure 2

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.