Next Article in Journal
Improving the Inertial Response of a Grid-Forming Voltage Source Converter
Next Article in Special Issue
A Concept of Autonomous Multi-Agent Navigation System for Unmanned Surface Vessels
Previous Article in Journal
Household Electricity Consumer Classification Using Novel Clustering Approach, Review, and Case Study
Previous Article in Special Issue
Hill-Climb-Assembler Encoding: Evolution of Small/Mid-Scale Artificial Neural Networks for Classification and Control Problems
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Review

Review of Collision Avoidance and Path Planning Algorithms Used in Autonomous Underwater Vehicles

Faculty of Mechanical and Electrical Engineering, Polish Naval Academy, 81-127 Gdynia, Poland
Electronics 2022, 11(15), 2301; https://doi.org/10.3390/electronics11152301
Submission received: 4 July 2022 / Revised: 18 July 2022 / Accepted: 21 July 2022 / Published: 23 July 2022

Abstract

:
The rapid technological development of computing power and system operations today allows for increasingly advanced algorithm implementation, as well as path planning in real time. The objective of this article is to provide a structured review of simulations and practical implementations of collision-avoidance and path-planning algorithms in autonomous underwater vehicles (AUVs). The novelty of the review paper is to consider not only the results of numerical research but also the newest results of verifying collision-avoidance and path-planning algorithms in real applications together with a comparison of the difficulties encountered during simulations and their practical implementation. Analysing the last 20 years of AUV development, it can be seen that experiments in a real environment are dominated by classical methods. In the case of simulation studies, artificial intelligence (AI) methods are used as often as classical methods. In simulation studies, the APF approach is most often used among classical methods, whereas among AI algorithms reinforcement learning and fuzzy logic methods are used. For real applications, the most used approach is reactive behaviors, and AI algorithms are rarely used in real implementations. Finally, this article provides a general summary, future works, and a discussion of the limitations that inhibit the further development in this field.

1. Introduction

In recent years, a significant increase in the number of unmanned underwater, ground, and air vehicles (UxVs) in various environments has been observed. Most often, these vehicles are autonomous with different levels of autonomy. When speaking of autonomous vehicles, most will refer to air or ground vehicles. Less widespread and commercialised, but equally important are autonomous underwater vehicles (AUVs). This type of vehicle can be used for ocean exploration, performance of various industrial operations, or military missions. Due to the limited adaptability of humans, diving to very deep depths may be impossible or require a lot of time and preparation. In some cases, like observing the seafloor or looking for damage to pipes running along the bottom of a water reservoir, using AUV can bring many benefits to humans. To perform underwater operations properly and safely, it is necessary to equip the AUVs with all the essential systems, such as obstacle detection systems, motion- or path-planning systems, collision-avoidance systems, trajectory-planning systems, mapping systems, mission planners, path-tracking systems, etc. The underwater environment poses many difficulties for the vehicles’ movement, i.e., high signal attenuation, limited possibilities of spatial orientation in relation to reference points, the presence of sea currents, limited access to light, and disturbing signal reflections from the bottom and surface of the water. Therefore, some motion-planning solutions implemented for robots or other groups of autonomous vehicles may not be appropriate for AUVs. The rapid technological development of computing power and system operations today allow for more and more advanced algorithm implementation as well as path planning in real time. As one study [1] indicated, increasing the computing power through hardware can significantly increase the data-processing speed and system efficiency compared to the implementation of more efficient software. Reliable performance is considered a crucial condition for AUV design. Although simulation analysis of collision-avoidance algorithms and path planning usually brings satisfactory results, real vehicle implementation has caused many difficulties in past studies [2]. As scientific and technical knowledge advance, researchers attempt to systematise current achievements in this field. In [3], motion-planning approaches for robots from the years 1980–2010 were analysed, indicating how the number of heuristic algorithms changed in individual decades compared to conventional algorithms. The basics of classical and heuristics-based methods for robots were discussed in [4]. The authors of [5] analysed 80 articles from 2011–2015 on motion planning in a dynamic environment for robots and systematised individual solutions in terms of parameters such as smooth path, safety, path length, run-time, accuracy, stability, control, computation cost, and efficiency. The study [6] reviewed 3D path-planning algorithms for robots, focusing on the universality of individual algorithms implementation in aerial, ground, and underwater robots. Reference [7] elaborated on heuristic algorithms for robots, showing examples of their efficient and inefficient operation. Reference [8] reviewed sampling-based motion-planning algorithms for robots, and [9] focused on probabilistic roadmap approaches in dealing with dynamic collision, narrow passages, multi-targets, and manipulation planning for deformable linear objects. Other studies also summarized the achievements in the field of quadrupedal robots [10], AGVs (usually road vehicles) [11,12], coverage path planning for robots [13], and searching methods for environmental monitoring [14]. Together with single robots, multi-robot performance has also been studied. Reference [15] discussed navigation techniques for the single and multi-robot systems in both static and dynamic environments. In addition, reference [16] analysed the techniques of movement of the robot group depending on the shape of the formation (cluster/line flocking). The authors of [17] reviewed the available literature in terms of the multi-robot movement in normal and faulty situations, and [18] focused on methods determining desired trajectories for multi-robots. In the path-planning studies, some researchers have been focusing on solutions designed for specific types of vehicles depending on the environment in which the vehicle is moving. In [19,20], the algorithms designed for unmanned aerial systems (UASs) were analysed, and in [21,22,23] algorithms for unmanned aerial vehicles (UAVs) were discussed. Reference [24] discussed vision-based algorithms for UAVs, and [25] for multiple UAVs. Many reviews in the field of underwater robotics have also been published. In [26], the technological development and limitations that are encountered in marine robotics are analysed. The authors of [27] define the trends in construction, instrumentation, and systems for unmanned underwater vehicles (UUVs). The UUVs can be remotely operated vehicles (ROVs) and AUVs. In [28], the main systems for both a single AUV and multi-AUV are described, as well as the possible directions of AUVs’ further development. In terms of motion control of a UUV, reference [29] reviews the development of control methods and the problems encountered during the research. In turn, reference [30] provides detailed literature that analyses path-planning-related solutions for AUVs. The main surveys connected with motion planning for robots are presented in Table 1.
The objective of this article is to provide a structured review of simulations and practical implementations of collision-avoidance and path-planning algorithms in AUVs together with a comparison of the difficulties encountered during simulations and their practical implementation. The paper is organised as follows. In Section 2, the most essential path-planning and collision-avoidance algorithms for AUVs are explained. Section 3 includes a summary of simulation and practical research in this area. In Section 4, the general summary, future works, and limitations that inhabit the further development in this field are discussed. Final conclusions are presented in Section 5.

2. Fundamentals of Path-Planning Algorithms

This section presents the main path-planning algorithms for AUVs. The description of each method includes an explanation of the fundamental principles. It also analyses the advantages and disadvantages, environmental limitations, and potential difficulties in real applications. Each approach contains several application examples from different fields of robotics.

2.1. A* Algorithm

In 1986, the heuristic method [31] A* was proposed, which consists of dividing the known area into individual cells and calculating the total cost of reaching the target for each of them. Given the total distance from the starting point to the currently analysed cell and the distance from the analysed cell to the target, the total path cost is calculated with the following formula:
F ( n ) = G ( n ) + H ( n ) ,
where:
F ( n ) is the total path cost;
G ( n ) is the cost of reaching from the starting point to the analysed cell; and
H ( n ) is the cost of reaching from the analysed cell to the target.
The A* algorithm focuses on finding the shortest path to a destination in the presence of static obstacles assuming that both the environment and the location of the obstacles are known. In this method, however, an increased amount of computation is needed for large areas analysis or areas with many obstacles. This significantly increases the path planning time. For the marine vehicles, AUVs and autonomous surface vehicles (ASV), the A* algorithm method is in most cases used in combination with the visibility graph algorithm [32,33,34]. In [35], simulations of two grid-based methods in the 3D environment were compared. Compared to the Dijkstra algorithm, the multi-directional A* proved to be more efficient in terms of the number of nodes and the total length of the path. The practical implementation of this method is associated with the problem of variability of the underwater environment and the lack of precise knowledge about the location of obstacles. Another challenge for practical implementation of this method in AUV may be the unforeseen effect of sea currents.

2.2. Artificial Potential Field

The artificial potential field (APF) method has its origins in 1986 [36] and assumes the presence of a repulsive field around the obstacle and an attractive area around the target that affect a moving vehicle (e.g., AUV). As a result of the interaction of these virtual fields, the resultant force is determined according to which way the vehicle is moving. In this method, prior knowledge of the environment and the location of obstacles is not needed. It can be used regardless of whether the obstacles in the environment in which the AUV is moving are static or dynamic and whether they have regular or irregular shapes. The crucial condition for this algorithm to be efficient is accurate obstacle detection. The advantage of the APF method is the ease of implementation and low computational requirements, which makes it possible to control AUVs and avoid collisions in close to real time. Despite the many abovementioned advantages, the possibility of local minima or trap situations is considered as a significant disadvantage [37]. Under certain conditions, e.g., a U-shaped obstacle, when the resultant force acting on the AUV is balanced, the algorithm will control the movement of the AUV in a closed infinite loop without reaching the goal. In addition, the passage of the AUV between closely spaced obstacles may not be possible or cause oscillation due to the alternating influence of force fields from opposing obstacles [37,38]. Also, the AUV tends to demonstrate unstable movements when passing around obstacles. In order to solve the local minima problem, APF is combined with other methods, such as [39,40]. In the simulation-based study [41] for AUVs a solution was proposed based on the introduction of a virtual obstacle in the place where the local minimum occurs. Another way to avoid a trap situation can be by using random movements to lead the AUV out of the adverse area (randomised potential field) [42]. Despite the limitations of this method, it is used to control a swarm of robots [43,44,45,46]. Simulation-based studies also prove the possibility of controlling multi-AUV formations [47] and its application in mission planners [48]. In [49], the potential field-based method was used in the practical implementation in NPS ARIES AUV in a real-world environment. To avoid the negative impact of APF method limitations in real implementations, it is necessary to use the global path-planner module based on, e.g., heuristic methods.

2.3. Rapidly Exploring Random Tree

Introduced in 1998 [50], the motion-planning algorithm named rapid-exploring random tree (RRT) is a sampling-based method. Any node in the X r a n d spatial is randomly determined from the initial point X i n i t (Figure 1). Then, depending on the given direction of movement and the maximum length of the section from the analysed point, the intermediate X n e a r node is determined. The longer the sections’ connecting nodes, the higher the risk of moving in the wrong direction for a long time and encountering obstacles on the designated path. If any obstacle is detected between waypoints, further route calculation in that direction is ignored. If no obstacles are detected, a random point in the X r a n d spatial is determined, followed by a new intermediate point X n e w .
As a result of subsequent iterations (time steps), new edges and path points are determined. The method is easy to process and ensures the finding of a collision-free path (if there is one) in an unknown environment, both 2D and 3D. RRT can be used in both static and dynamic environments [51]. A modification of this method was used in the SPARUS-II AUV and tested in a real-world environment [52]. The study [53] shows the validity of the modified RRT* algorithm for mapping in a 3D environment for multiple AUVs. In [54], an RRT-based approach was used to solve the problem of local minima in the fast warm starting module in the Aqua2 AUV. It was noted that this method is not always efficient in an environment where the path to the target leads through a narrow opening or gap. Another limitation of this method is the need to provide information about large areas of the environment, which is not always possible in practical implementations due to the technical limitations of sensors [55,56,57]. Additionally, the calculated path is suboptimal [58] which requires the use of additional optimisation algorithms.

2.4. Artificial Neural Network

An artificial neural network (ANN) is a machine learning method based on the mathematical mapping of information processing by the human brain. The general structure consists of three layers: input layer, hidden layers, and output layers (Figure 2). The neurons in each layer are connected to all the neurons in the neighboring layer and process the inputs based on the weights in between. The data from each neuron in the input layer multiplied by weights is sent as input to hidden layers where each neuron is assigned a value (bias). Depending on the activation function and bias value, only neurons with a value higher than the threshold value are activated. The output from each layer is also the input for the next layer. The data transfer between the layers is performed only by active neurons. The ANN method requires learning, i.e., indicating the accuracy of the output data. Based on the determination of the expected results, the neural network adjusts the weights between the individual neurons in each iteration in such a way that the output data is as close to the expectations as possible.
The method has learning ability and is applicable in systems that implement complex functions, supporting many outputs based on data from multiple sensors. The algorithm is also efficient for the systems where the input data is incomplete or distorted, or in cases in which there poorly modelled, nonlinear dynamical systems [59,60,61]. The main drawback of this algorithm is the need for long-term training to achieve satisfactory results [62]. In the case of practical implementation for AUV, online learning does not bring satisfactory results due to slow learning speed and long training time [63]. Therefore, offline training for controllers is essential before the AUV can be used in a real-world environment. Reference [64] presents a collision-avoidance controller for static and dynamic obstacles based on neural networks that do not require training. The resulting behaviour of the AUV was defined by neuron weights. It should be noted, however, that this type of controller is suitable for simple AUV operational cases. In [65], the neural network method was used in real implementation in AUV-UPCT. The vehicle required prior learning in ROV mode. In [66], the neural network algorithm was used in a simulation study to control and avoid collisions for multiple AUVs in a 3D environment. In [67], the neural network was used to process real images of the underwater environment (simple, coloured monocular camera) to determine the free space enabling the escape of the AUV from the cluttered environment.

2.5. Genetic Algorithm

Genetic algorithm (GA) refers to research and optimisation methods inspired by the natural evolution process where only the fittest organisms have a chance for survival. In general, the algorithm starts looking for a solution to a problem by generating a random population of possible solutions. Depending on the applied function, a selection is made during which the least suitable solutions are eliminated [68]. For path planning, the main criterion is the energy cost required to run each path [69]. Then, through an operation called crossover, further potential solutions to the problem (offspring) are created, combining the best solutions from the previous generation (parents). Additionally, in the mutation process, random modifications of the best solutions are created. Then, the GA runs the selection again, adding to the population’s successive possible solutions that are closer and closer to the correct result until a specific final condition is reached, e.g., the number of generations. The main advantage of the GA method is the possibility of fast and global stochastic searching for optimal solutions [70]. In addition, the algorithm is easy to implement and can be used to solve complex problems, such as determining the optimal AUV path in the presence of static and dynamic obstacles in the underwater environment. Due to the random nature of searching for solutions, the algorithm reduces the risk of the local minima problem [71]. In general, the method does not require large numbers of calculations to solve the path-planning problem. However, the route may be suboptimal if too few generations are executed. As the number of generations increases, the route becomes closer and closer to the optimal one due to the constant elimination of the least optimal solutions in the population. It entails an increase in computational costs. Similarly, in a rapidly changing environment or when the environment is very extensive, the amount of computation needed to determine a solution increases significantly. In [69], a modification of the GA was presented in order to determine the energy’s optimal path. The modification involved the introduction of iterations consisting of additional runs of the algorithm with different initial conditions and the operator based on the random immigrants’ mechanism, which sets the level of randomness of the developing population. Reference [72] discussed the framework of the collision-avoidance system based on the GA. The simulation test proved the proper functioning of the method for static and dynamic obstacles. Improved GA was also used in a simulation-based study [73] to optimise energetic routing in a complex 3D environment in the presence of static and dynamic obstacles. The algorithm with improved crossover and mutation probability and the modified fitness function was tested in simulation [70] in comparison with the traditional GA method. The simulation confirmed that the improved GA allows a shorter and smoother path with fewer generations. The method worked very well in the energy optimisation of routing. It should be noted that the efficiency of this method in real testing depends on the correct detection and determination of the obstacle location as well as the target.

2.6. Fuzzy Logic

The fuzzy logic (FL) method [74,75] is based on the evaluation of the input data depending on the fuzzy rules which can be determined by using the knowledge and experience of experts. In AUV obstacle avoidance systems, the fuzzy controller sensor processes data containing information about the surrounding environment and makes decisions based on it. Then, appropriate signals are transmitted to the actuators. The first stage of the algorithm’s operation is fuzzification, i.e., assigning the input data to the appropriate membership function. Each of the functions is based on a descriptive classification of the input data, e.g., low, medium or high collision risk. Then, in the fuzzy inference process, a data evaluation is performed based on “if prerequisite then result” statements rule. Ultimately, the defuzzification process determines specific system output values (e.g., actuator control signal values). The method can be used for both static and dynamic obstacles. However, when an AUV operates in an unknown environment, the usability of the algorithm directly depends on the implemented rules, and therefore also on the knowledge and experience of experts. The main advantage of the algorithm is its usability in the case of incomplete information about the environment, even containing noises or errors [76]. The method is easy to implement and provides satisfactory results in real-time processing but requires a precise definition of membership functions and fuzzy rules [77]. Additionally, as the number of inputs increases, the amount of input data necessary for the system to process increases. An important issue affecting the effectiveness of the algorithm is also the AUV speed and the complexity of the environment. A fuzzy system usually has at least two inputs. In a very dynamic environment, the use of additional inputs can increase the efficiency of the controller [78]. In some cases, the necessity of performing complex maneuvers to avoid a collision may cause the AUV to be diverted far from the optimal path. For this reason, it is necessary to use additional algorithms that control the path in terms of energy. A simulation study [71] showed that the use of GA to optimise fuzzy logic path planner allows one to achieve greater efficiency and reduce cross-track errors and total traveled path. A modification of this method was also used in a practical implementation in a study [79] where the Bandler and Kohout product of fuzzy relations was used for preplanning in horizontal plane maneuvers. The fuzzy logic method was also used in [80] to control a single unmanned surface vehicle (USV) and in the simulation [81] to control virtual AUVs in the leader–follower formation of AUVs.

2.7. Reinforcement Learning

The reinforcement learning (RL) method is based on research about the observation of animal behaviour. As a result of strengthening the pattern of behavior by receiving a stimulus by the animal, it increases the tendency to choose actions [82]. Machine learning based on this idea was very intensively developed in the second half of the 19th century. Depending on the requirements of the environment model, the simplicity of data processing, and the iterative nature of calculations, several methods of solving RL problems have been developed, e.g., dynamic programming, Monte Carlo methods, and temporal difference learning. The most crucial method of solving RL problems is the temporal difference method. Depending on the occurrence of the policy function, it is divided into several algorithms, e.g., Actor-Critic, Q-learning or Sarsa method [82]. The actor-critic method consists of autonomous learning of the correct problem solving depending on the received reward or punishment. By performing action, the agent influences the environment by observing the effects of the action. Depending on the implemented reward function, different ways of influencing the environment are assessed. The objective of this method is to learn how to perform such actions in order to get the greatest reward. In the case of path planning, the agent will receive the greatest reward if moving toward the given destination. In general, an agent includes a combination of neural network’s actor and critic. The interaction between them is a closed-loop learning situation [83]. The actor chooses the action for performing to improve the current policy. The critic observes the effects of this action and tries to assess them. The assessment is then compared with the reward function. Based on the error rate, the critic network is updated to predict actor network behaviour in the future better. The abovementioned approach was used in [84] to control four robots. Each of them was able to avoid collisions with other robots and with obstacles. In the study [85], the RL approach was used in a two-dimensional simulation of cooperative pursuit of unauthorized UAV by using a team of UAVs in an urbanized environment. In [86], a simulation of smart ship control algorithm was presented. Moreover, in simulation studies [87,88] the RL approach was used for path planning and motion control of AUVs. The method can be used for both static and dynamic obstacles in an unknown environment. It is characterised by a strong focus on problem solving and shows high environmental adaptability. The RL algorithm can learn to solve very complex problems as long as the correct reward function is used. The inability to manually change the parameters of the learned network is considered as the main drawback of this method. To change the operation of the algorithm, the network must be redesigned, and a long learning process must be performed. Also, checking this method’s operation by simulation does not guarantee its correct operation in a real-world environment.

2.8. Comments

Among the classical and heuristic methods discussed above, it is difficult to find one that will work efficiently in various conditions and at the same time meet all the requirements for complete control and for a collision-avoidance system for the AUV. In an ideal scenario, the implemented method should assure high efficiency, real-time response, safety, path optimisation in terms of energy, low complexity, high accuracy, the shortest possible path, and the ability to operate properly in an unknown environment in relation to both static and dynamic obstacles. Each of the methods has its advantages and disadvantages depending on the given conditions. A situation in which the algorithm works very well and one in which the effectiveness of the algorithm will be very low can be found for each of the discussed methods [7]. Researchers still work on improving the parameters of individual methods by modifying them. In order to improve efficiency and eliminate defects, combinations of various algorithms are also used.

3. Chronological State of the-Art

After analysing the available literature in the field of path planning and collision avoidance for AUVs, a detailed classification of the studies was carried out in terms of chronology and in terms of the technique of testing the effectiveness of the presented algorithms. In each of the 4 intervals (until 2010, 2011–2015, 2016–2020 and from 2021 onward), the studies were divided into 2 groups, as follows.
  • The first group includes algorithms validated in numerical research containing new methods, modified methods, or a combination of existing methods that have been validated in a simulation environment. Some of the methods presented have been developed to be applied to real AUVs. This group also includes algorithms whose effectiveness has been verified in hardware-in-loop simulations.
  • The second group includes algorithms in real applications where AUV control methods are presented, the effectiveness of which has been tested in a real environment in the presence of both real and virtual obstacles.
In each of the abovementioned groups, the research was ordered from oldest to newest in the analyzed period of time.

3.1. Until 2010

The need for a collision-avoidance system for AUVs has been recognised in the last century. At that time, many researchers proved algorithms that could detect and avoid collisions for static and moving obstacles [64,89]. Studies carried out in early 2000 showed a very intensive development of AUV collision-avoidance and path-planning algorithms. The capabilities of most of them, however, were tested only with simulation-based methods. The list of algorithms validated in numerical research until 2010 is presented in Table 2. At that time, intensive research on obstacle detection and classification were carried and analysed for physical sensor use and in simulation-based methods. In some cases, the algorithms were explicitly created for practical implementation. In [90] a virtual force field (VFF)-based system for the RAIS AUV was introduced and tested by using numerical simulations and hardware-in-loop simulation methods. In [91], researchers proposed a collision-avoidance algorithm through the pitch angle change. This algorithm was intended for physical implementation in the Taipan AUV. The authors of [92] proposed a collision avoidance algorithm based on the prediction of gradient lines (static obstacle) and deformed safety zone (for dynamic obstacles) intended foran AUV called DeepC. The approach was based on determining the trajectory by using the graph method combined with the A* method. The Redermor test platform equipped with forward-looking sonar (FLS), ten echosounder, and side scan sonar in the [93] study was used to collect sonar data during underwater tests. The authors have been able to classify the obstacles and prove that it is possible to define the boundary level around the obstacle. The implementation of more advanced hardware equipped with FPGAs allowed [1] to significantly increase the speed of data processing and power efficiency. At that time, solutions were also designed to control AUVs moving in formation. The accuracy of the proposed method was tested only in simulation-based analysis. In the study [94], the method based on the potential function and behaviour rules was proven in simulations for 3 AUVs moving in formation. Also, the authors of [81] proposed a well-functioning algorithm based on FL to control the velocity of the AUV formation. An algorithm based on the artificial potential field method [95] was also developed, which has been proven, under simulation conditions, to work efficiently for static obstacles.
An example of practical implementation of collision-avoidance algorithms can be found in [49]. In this study, AUV avoided the sunken barge by changing the altitude by using a method based on the artificial Pptential field. Another practical implementation [38] was also performed with MEREDITH. 2D vector field histogram (VFH) based method functionality was tested in a real-world environment. The vehicle was able to avoid a large obstacle which was a breakwater. Also, in 2001–2009, a project code-named Autosub was carried out. At that time, several vehicles from the Autosub brand were made and practically tested during many under-ice missions. The collision-avoidance capability has been proven practically in this mission. In [105], a collision-avoidance module was triggered, and the vehicle correctly managed to avoid the obstacle. At that time, the algorithm worked only in the vertical plane. Over the years, the project’s team gained a lot of experience and gradually improved their AUVs capability. Reference [106] presented an improved collision-avoidance system capable of turning in a horizontal plane. The upgraded Autosub-I AUV, after detecting an obstacle, performs a maneuver to change the depth and then turn and move in the horizontal plane. Then, the AUV retreats and tries to avoid the obstacle. After the maneuver, it returns to the previously taken path. As the authors claimed, the algorithm copes well with large obstacles. However, small-sized obstacles and a complex environment pose a significant challenge to the vehicle. The same algorithm was also implemented in another vehicle from the Autosub group—Autosub3. The vehicle operated for four days under the ice and covered 510 km during the mission, proving practical adaptation to even difficult operations [107]. In Table 3 the list of algorithms in real applications until 2010 is presented.

3.2. 2011–2016

In the past decade, researchers focused more often on analysing the combinations of algorithms. In Table 4 the list of algorithms validated in numerical research between 2011–2016 is presented. In the simulation study [77], the particle swarm optimization (PSO) algorithm was used to regulate the membership function in the FL-based method in the AUV motion controller system. In the study [108], the method based on the combination of FL for pre-planning and reactive techniques is simulated. The authors consider collision avoidance only in the horizontal plane. The study [109] analyses the combination of potential field and edge detection to avoid collisions (only in the vertical plane). The method is designed for applications in which the AUV is responsible for inspecting the area (by using side scan sonar), where a straight course line should be kept. In [34], a combination of graph methods with the A* algorithm was used to determine the path. However, as concluded, that combination does not allow one to determine the optimal path in a completely unknown environment. In [110], the APF-based algorithm was used for local collision avoidance, and the velocity synthesis algorithm was used to optimise the AUV path. Also, modifications of the already existing algorithms were developed. The multi-point potential field method was analysed in [111]. The vehicle is steered in the direction of the field’s lowest resultant value, which is generated in many directions. Additionally, in that time, more and more focus was given to path planning and global collision avoidance. Several control systems and collision-avoidance and path-planning studies have also been developed for multi-AUV formations. In a simulation study [47], a multi-layer region control concept was used to control and avoid both static and dynamic obstacles, and a PD-based regulator controlled the shape of the formation. The authors in [66] used neural networks to simulate the multi-AUV control system in the presence of static obstacles. Other issues closely related to collision avoidance and path planning by AUV were investigated in studies at that time. The authors of [111] performed a simulation in laboratory conditions of AUV with hardware-in-loop and software-in-loop methods with real sensor data (ultrasonic sensor- for distance to the obstacle, pan and tilt angle inputs by the user) and real implementation of actuators. This method is beneficial and effective for verifying the operation of algorithms in real time.
In [65], researchers successfully tested a AUV-UPCT control system based on the neural network method in Menor Lagoon. The vehicle has the ability to move in 3D, and obstacle avoidance is implemented only in the horizontal plane. In the study [115], the successful maneuver to avoid a group of four obstacles was accomplished by making a 90 turn and bypassing the obstacle, which was the island and the points around it. However, one test resulted in AUV looping due to the local planner not being fully integrated with mission planner. The study [52] tested the possibilities of the SPARUS-II AUV in a real-world environment. In the simulation conditions, a computation time equal to 1 s was assumed, whereas in real-world conditions, it was necessary to change this to 1.5 s. This indicates that the method works quickly but is not intended for a dynamically changing environment. The study [116] proposed an algorithm based on reactive behaviours that allows it to correctly navigate and avoid obstacles in both vertical and horizontal planes. Due to the fact that the collision avoidance in both planes is not parallel, there may be cases of a non-optimal AUV trajectory. The study discusses the situation in which the AUV, to avoid an obstacle, gradually ascends to the minimum depth and then avoids the obstacle by using horizontal plane behaviours. the list of algorithms in real applications between 2011–2016 is presented in Table 5.

3.3. 2016–2020

In the next five years (2016–2020), there was an increased interest in collision avoidance and control systems for single AUV and multi-AUV formations. Researchers focused their simulation studies on modifying existing methods to improve efficiency. List of algorithms validated in numerical research between 2016 and 2020 is presented in Table 6. In the survey [117], an APF algorithm modification was introduced, consisting of the disappearance of the repulsive force effect on AUV in the case of increasing the distance from the obstacle. For this method, an obstacle is detected only when at less than 80 m distance. In the study [118], the path optimisation determined by the neural network was solved using the Radau pseudospectral method. The authors of [73] presented a solution to modify the mutation operator through a grey wolf optimiser for energy optimisation in path planning. In the modified APF-based method in [119], the amount of data necessary for the correct operation of the algorithm was reduced to provide information only about the distance between the vehicle and the obstacle. The study [78] introduced a three-input FL controller that can provide greater efficiency for fast-moving obstacles than the generally used two-input controllers. In the survey [70], a modified GA is presented by adaptively adjusted crossover and mutation probability and by assessing the diversity of the new population. The collision-avoidance and controls systems for AUV formations were also points of focus at that time. In [120], authors used the fuzzy artificial potential function and leader–follower algorithm for flocking control of group AUV. Another solution based on the neural network method for controlling AUVs and APF for collision detection and avoidance was simulated in the study [121]. Due to hardware and environmental limitations, real-time in-system simulation was performed. The results proved to be similar to the simulation run in the MATLAB environment without using AUVs. Researchers also modified well-known routing optimisation algorithms for multiple AUVs and their energy consumption [122]. Also, many other studies have been focusing on the control and avoidance of collisions for multiple AUV formations, e.g., [123,124,125], which shows that in the time period considered in this paragraph, there was a significant increase in interest not only in collision avoidance and path planning algorithms for individual AUVs but also a lot of focus has been given to the research of AUV-formation control algorithms. In [126], the authors developed a practical implementation of the 2D control method based on the Dijkstra algorithm with its testing on the ROV. The authors claimed that the method can also be easily implemented in AUVs. In the study [127], a real-world test of the biomimetic AUV (BAUV) was carried out. The study, however did not bring satisfactory results due to the insufficient accuracy of the navigation system. Also, some false obstacles were detected due to reflections from testing the BAUV in shallow water. The examples of BAUV and AUV are shown in Figure 3. Another study [128] analysed the possibilities of determining the optimal and collision-free path for the Inspection-AUV (I-AUV) with a manipulator in cluttered environments. The authors of [129] confirmed that it is possible to build a collision-avoidance controller for AUVs by using a hydroacoustic obstacle-detection system. Reference [130] analyses the collision avoidance problem for various types of underwater objects (usually vehicles) and various environmental conditions in cases of one-way communication.
The list of algorithms in real applications between 2016–2020 is presented in Table 7. In the study performed in [79], horizontal maneuvers are preferred over vertical ones. If it is impossible to calculate the path by using horizontal maneuvers, the vertical approach is activated. This approach allows one to avoid collisions in 3D, although in some cases the path on which the AUV moves may not be optimal or is far from optimal. The authors [140] tested AUV in a real-world environment with simulated obstacles in the form of a labyrinth. Therefore, obstacle detection and sensor input processing have been simplified. Nonetheless, the algorithm recalculated the path in around 5 s, which means the AUV might not be able to react appropriately in an emergency. The study [141] discussed an obstacle-avoidance algorithm, changing the AUV altitude when an obstacle appears in the scanning area. When performing evasive maneuvers, the AUV ascends vertically, and a downward-looking camera and laser monitor the obstacle, memorising the position of the obstacle’s peak of the obstacles. After executing the maneuver, the AUV returns to the before-avoidance altitude. In the study [142], the reactive algorithm enforces turning when an obstacle is detected. If not, the AUV is controlled parallel to a wall, keeping a constant distance from it. In [143], the reactive algorithm uses a combination of behaviours depending on the situation: gain altitude, reduce altitude, move forward, move backwards, and escape from hot water. The study includes photographing the bottom of the test reservoir containing hydrothermal springs. When avoiding collisions with seafloor elements, the AUV makes a vertical plane movements only. In [144], extensive simulation and practical tests (under various conditions, including regular and irregularly shaped obstacles) were conducted to confirm the correct operation of the collision-avoidance algorithm implemented on the SPARUS-II AUV. The research proved the possibility of an effective operation of the algorithm in the field of online planning with full 3D control. The authors [54] tested the Aqua2 AUV in a pool with static obstacles. Although offline path planning was successfully accomplished in 3D, and online planning was only realized in the horizontal plane.

3.4. 2021–Now

In the last two years, simulation methods for route planning and collision avoidance are still being developed. Another aspect that is becoming more important is accurate navigation, together with algorithms for reducing the navigation errors and also methods of tracking the previously determined path [63,145,146,147,148]. There is still continuing interest in control and collision avoidance systems for multi-AUV formations [149,150,151]. To improve the efficiency of simulation algorithms, combinations or improvements to the existing methods are implemented. The list of algorithms validated in numerical research from 2021 is presented in Table 8.
In [158], a real-world environment test was conducted in which the AUV, after detecting a fishing net, was to make a turn and then return to the original path. In a result, 13 out of 16 attempts were successful. For the three unsuccessful attempts, the vehicle did not react accurately due to the too high detection threshold to exclude false detections. The MRF-net was used to detect obstacles in real time. The method is suitable for detection of a single static obstacle. The study [159] examined the capabilities of the PI AUV, which is intended for damage inspection of underwater pipes. It was tested whether the AUV correctly detects a leak from the pipe. Also, the anti-collision system operation was tested in which the avoidance expert system takes over the control if an obstacle is detected at a distance of 80 m from the AUV. Depending on the obstacle in relation to the AUV, the appropriate maneuver (turn left/right or bypass left/right) is selected in the horizontal plane. The position of dynamic obstacles was predicted by using the Kalman filter. The authors [160] introduced the path-planning and collision-avoidance systems for the spherical underwater robot SUR IV. The combination of ant colony and PSO approaches allowed the researchers to avoid collisions in 3D, which was confirmed by an experiment in a real water environment. To detect obstacles in this study, a camera was used. It must be noted that placing the SUR IV in a real water environment with low transparency could interfere with the correct detection of the environment and obstacles and as a result, malfunction of the entire system. The list of algorithms in real applications from 2021 is presented in Table 9.

4. Discussion

This section summarises the results of the literature analysis, containing statistics on the use of path planning and collision-avoidance methods. Quantitative statistics include a division into simulation-tested and real-environment validated methods from 2001 to 2020. It also contains classification according to classical and artificial intelligence methods. The next part of this chapter discusses future works and limitations that inhabit the further development in this field.

4.1. Summary

After analysing the literature on motion planning and collision avoidance for AUVs, it is clear that a significant increase in publications in this area occurred only in the last decade (Figure 4). The rise in simulation tests of new, improved, or combined algorithms for path planning and collision avoidance is accompanied by an increase in the number of practical implementations in AUV motion controllers and tests in a real environment. However, the practical implementations of the control and collision-avoidance algorithms are not developed as fast as the simulation methods. A practical approach to the study requires dealing with design and technological problems, which are often time-consuming and costly. Additionally, performing tests in a real environment requires thorough preparation and logistical organisation. Analysing the last 20 years of AUV development, it can also be noticed that experiments in the physical environment are dominated by classical methods (Figure 5). In the case of simulation studies, artificial intelligence methods are used as often as classical methods. Although artificial intelligence algorithms have origins in the previous century and allow for solving very complex problems, their use by researchers has not been dominated in further studies on the development of AUV. Figure 6 shows that in simulation studies, the APF approach is most often used among classic methods, whereas among artificial intelligence algorithms RL and FL methods predominate (Figure 7). For real applications, the most used approach is reeactive behaviors (Figure 8), as can be seen in Figure 9. Artificial intelligence algorithms are rarely used in real implementations. This probably results from the fact that these methods need a lots of data to train the artificial intelligence system. Summarizing the above analysis, it can be stated that in the field of collision avoidance and path planning in underwater environment algorithms, researchers still show great interest in classical methods. Thanks to the research to date, many disadvantages of classic methods have been eliminated, which, combined with the ease of implementation, is still an alternative to the often complex methods of artificial intelligence.
The currently designed AUVs are diverse in terms of intended use. Local collision-avoidance algorithms are usually connected to a global system that analyses and optimises the path. This creates the need to develop many side areas of studies, such as the selection of the path-planning method, preplanning, algorithms and drivers for tracking the designated path, navigation and mapping related to determining the most accurate position of obstacles and the AUV. Moreover, in recent years the development of I-AUVs has also been noticeable. I-AUVs are usually equipped with an arm with several degrees of freedom and are designed to perform inspections and repairs, for example of gas and oil installations [161]. When carrying out specific underwater missions, I-AUVs must have collision-avoidance algorithms for the correct task execution and safe movement. For the I-AUV with several arms, it is also necessary to use collision-avoidance algorithms between arms. Implementing that component to the control system, however, significantly increases the complexity of the controller system. Another type of AUV is a spherical underwater robot (SUR). All control elements, electronic devices, and power sources are within that spherical shape [162,163,164]. Due to the shape and center of gravity, SURs are characterised by high stability and maneuverability, allowing for a tiny turning radius (even 0 degrees). The obstacle-avoidance and control systems for the multiple AUV formations are also studied more often recently. In such formations, the control is, however, very complex due to the need to simultaneously control multiple vehicles, their communication and cooperation, as well as to perform specific maneuvers when avoiding obstacles and then returning all formations to the previous positions. Currently, AUV control systems mostly use artificial intelligence methods to define the environment and the situation they are in, as well as to find solutions in the event of encountering problems or obstacles. Due to the limitations of individual methods in their basic versions, to increase the efficiency of the AUV motion control system, modifications or combinations of methods are used. That approach in some cases allows one to use the advantages to eliminate the disadvantages of the chosen methods.

4.2. Future Works

Over the last few decades, multiple path-planning methods and collision-avoidance methods have been proposed and simulated in the field of AUV technology. Nevertheless, there are only a few practical AUV implementations with an effective and efficient system of optimal path planning and collision avoidance. In the coming years, it will be necessary to focus more on practical implementations by using the existing knowledge gained in simulation studies. Technological development provides better possibilities for more accurate detection, and more precise navigation or increasing the computing speed. The appropriate use of evolving technology is crucial in the further development of collision avoidance and path-planning systems for AUVs. Many problems in this field have already been resolved. However, there are still issues that require extensive research. AUVs are still not able to achieve high speeds during collision-avoidance maneuvers. Additionally, despite the developing technology, the navigational uncertainties still have to be compensated with algorithms that approximate the exact location. Recently, research on the methods of following a designated path and compensating for navigational error has been developing very intensively. Another aspect that requires more analysis and further work is navigation of the AUV in shallow water. This applies particularly to AUVs that use obstacle-detection sonars, where ground and water surface reflections create fictional obstacles.

4.3. Bottlenecks of Future Development

Artificial intelligence methods usually require a large amount of computation when processing 3D data in a complex environment. The vehicle’s speed depends on how quickly the system makes decisions when detecting an obstacle or a group of obstacles. Increasing the computing power allows for more efficient operation of the control system and faster data processing and consequently making faster decisions on how to avoid collisions. Ensuring high computing power, however, requires increasing the vehicle’s size, which limits the vehicle’s maneuvering parameters. Furthermore, highly efficient systems that provide high computing power consume more energy and require more financial outlay. The solution to this problem could be, for example, the creation of wireless charging stations for underwater vehicles; however, there are still limitations related to the specificity of the underwater environment, which inhibits the development of such infrastructure [23]. Thus, the optimal selection of the computing power for path planning and collision-avoidance drivers is crucial. Another aspect that limits the development of AUV in collision avoidance and path planning is the rough conditions in the underwater environment. The greater the operating depth, the higher the technical requirements for the AUV design. The lack of reference points, poor visibility and high signal attenuation make it challenging to navigate AUVs. Moreover, sea currents make it difficult to predict the environmental impact on AUVs. Another issue is the nonlinear dynamics of AUVs. Methods based on machine learning can achieve the ability to correctly control taking into account the dynamics of the vehicle. However, this requires a very long training time and does not guarantee correct vehicle control in situations that differ slightly from those covered by the training. For this reason, vehicle dynamics plays a vital role in practical implementations.

5. Conclusions

This article presented quantitative and qualitative comparisons of path-planning and collision-avoidance systems verified by using numerical tests and also real applications. We performed a literature review and analysis, summarizing the achievements, future works, and aspects limiting the further development of AUVs, especially in terms of path planning and collision avoidance.
Although since the 1990’s many of the AUV’s collision avoidance-related issues, such as the local minima problem, mapping the optimal path in an unknown environment, 3D path planning, re-planning and real-time decision-making, have been addressed and resolved by using mainly numerical studies, there are still many issues, which have not been entirely resolved, e.g., moving in a complex environment at high speed, nonlinear dynamics of the AUV, detection disruptions related to shallow water and a limited environment, or accurate navigation in the underwater environment. Moreover, it is difficult to indicate the best method or group of methods for collision avoidance, based on the state-of-the-art analysis. Depending on the circumstances, various methods were used with success for different cases. Quite often, hybrid methods showed good efficiency. Each method has disadvantages that reduce its effectiveness in a challenging underwater environment. The presented results show that the most frequently used algorithms tested in the simulated environment are APF, RL, and FL. These algorithms appear to be the most suitable for use in a real environment. Currently, in real implementations, the most frequently used method is the application of behavioural rules based on reacting to changes in the environment in a specific way. Although artificial intelligence methods have long dominated the field of collision avoidance for robots [3], in AUV, they are used in numerical research as often as classical methods. However, in real applications, mainly classical methods are still used.

Funding

This research received no external funding.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Not applicable.

Conflicts of Interest

The authors declare no conflict of interest.

Abbreviations

The following abbreviations are used in this manuscript:
AGVsAutonomous Ground Vehicles
AIArtificial Inteligence
ANNArtificial Neural Network
APFArtificial Potential Field
ASVAutonomous Surface Vehicle
AUVsAutonomous Underwater Vehicles
BAUVBiomimetic AUV
FLFuzzy Logic
FLSForward Looking Sonar
GAGenetic Algorithm
I-AUVInspection AUV
PSOParticle Swarm Optimization
RLReinfircement Learning
ROVRemotely Operated Vehicles
RRTRapidly-exploring Random Tree
SURSpherical Underwater Robot
UASUnmanned Aerial Systems
UAVUnmanned Aerial Vehicle
USVUnmanned Surface Vehicle
UUVUnmanned Underwater Vehicle
UxVsUnmanned Underwater, Ground and Air Vehicles
VFFVirtual Force Field
VFHVector Field Histogram

References

  1. Karabchevsky, S.; Kahana, D.; Guterman, H. Acoustic real-time, low-power FPGA based obstacle detection for AUVs. In Proceedings of the 2010 IEEE 26th Convention of Electrical and Electronics Engineers in Israel, Eilat, Israel, 17–20 November 2010; pp. 655–659. [Google Scholar]
  2. Sayyaadi, H.; Ura, T.; Fujii, T. Collision avoidance controller for AUV systems using stochastic real value reinforcement learning method. In Proceedings of the SICE 2000 IEEE 39th SICE Annual Conference, Iizuka, Japan, 28 July 2000; pp. 165–170. [Google Scholar]
  3. Tang, S.H.; Khaksar, W.; Ismail, N.; Ariffin, M. A review on robot motion planning approaches. Pertanika J. Sci. Technol. 2012, 20, 15–29. [Google Scholar]
  4. Atyabi, A.; Powers, D. Review of classical and heuristic-based navigation and path planning approaches. Int. J. Adv. Comput. Technol. (IJACT) 2013, 5, 14. [Google Scholar]
  5. Kamil, F.; Tang, S.; Khaksar, W.; Zulkifli, N.; Ahmad, S. A review on motion planning and obstacle avoidance approaches in dynamic environments. Adv. Robot. Autom. 2015, 4, 134–142. [Google Scholar]
  6. Yang, L.; Qi, J.; Song, D.; Xiao, J.; Han, J.; Xia, Y. Survey of robot 3D path planning algorithms. J. Control Sci. Eng. 2016, 2016, 7426913. [Google Scholar] [CrossRef] [Green Version]
  7. Ferguson, D.; Likhachev, M.; Stentz, A. A guide to heuristic-based path planning. In Proceedings of the International Workshop on Planning under Uncertainty for Autonomous Systems, International Conference on Automated Planning and Scheduling (ICAPS), Monterey, CA, USA, 5–10 June 2005; pp. 9–18. [Google Scholar]
  8. Sánchez López, A.; Zapata, R.; Osorio Lama, M.A. Sampling-based motion planning: A survey. Comput. Sist. 2008, 12, 5–24. [Google Scholar]
  9. Saha, M. Motion Planning with Probabilistic Roadmaps; ProQuest: Cambridge, UK, 2006. [Google Scholar]
  10. Biswal, P.; Mohanty, P.K. Development of quadruped walking robots: A review. Ain Shams Eng. J. 2021, 12, 2017–2031. [Google Scholar] [CrossRef]
  11. González, D.; Pérez, J.; Milanés, V.; Nashashibi, F. A review of motion planning techniques for automated vehicles. IEEE Trans. Intell. Transp. Syst. 2015, 17, 1135–1145. [Google Scholar] [CrossRef]
  12. Sharma, O.; Sahoo, N.C.; Puhan, N.B. Recent advances in motion and behavior planning techniques for software architecture of autonomous vehicles: A state-of-the-art survey. Eng. Appl. Artif. Intell. 2021, 101, 104211. [Google Scholar] [CrossRef]
  13. Galceran, E.; Carreras, M. A survey on coverage path planning for robotics. Robot. Auton. Syst. 2013, 61, 1258–1276. [Google Scholar] [CrossRef] [Green Version]
  14. Bayat, B.; Crasta, N.; Crespi, A.; Pascoal, A.M.; Ijspeert, A. Environmental monitoring using autonomous vehicles: A survey of recent searching techniques. Curr. Opin. Biotechnol. 2017, 45, 76–84. [Google Scholar] [CrossRef] [Green Version]
  15. Patle, B.; Pandey, A.; Parhi, D.; Jagadeesh, A. A review: On path planning strategies for navigation of mobile robot. Def. Technol. 2019, 15, 582–606. [Google Scholar] [CrossRef]
  16. Beaver, L.E.; Malikopoulos, A.A. An overview on optimal flocking. Annu. Rev. Control 2021, 51, 88–99. [Google Scholar] [CrossRef]
  17. Kamel, M.A.; Yu, X.; Zhang, Y. Formation control and coordination of multiple unmanned ground vehicles in normal and faulty situations: A review. Annu. Rev. Control 2020, 49, 128–144. [Google Scholar] [CrossRef]
  18. Madridano, Á.; Al-Kaff, A.; Martín, D.; de la Escalera, A. Trajectory planning for multi-robot systems: Methods and applications. Expert Syst. Appl. 2021, 173, 114660. [Google Scholar] [CrossRef]
  19. Ragel, R.; Maza, I.; Caballero, F.; Ollero, A. Comparison of motion planning techniques for a multi-rotor UAS equipped with a multi-joint manipulator arm. In Proceedings of the 2015 IEEE Workshop on Research, Education and Development of Unmanned Aerial Systems (RED-UAS), Cancún, México, 23–25 November 2015; pp. 133–141. [Google Scholar]
  20. Fraga-Lamas, P.; Ramos, L.; Mondéjar-Guerra, V.; Fernández-Caramés, T.M. A review on IoT deep learning UAV systems for autonomous obstacle detection and collision avoidance. Remote Sens. 2019, 11, 2144. [Google Scholar] [CrossRef] [Green Version]
  21. Goerzen, C.; Kong, Z.; Mettler, B. A survey of motion planning algorithms from the perspective of autonomous UAV guidance. J. Intell. Robot. Syst. 2010, 57, 65–100. [Google Scholar] [CrossRef]
  22. Naus, K.; Szymak, P.; Piskur, P.; Niedziela, M.; Nowak, A. Methodology for the Correction of the Spatial Orientation Angles of the Unmanned Aerial Vehicle Using Real Time GNSS, a Shoreline Image and an Electronic Navigational Chart. Energies 2021, 14, 2810. [Google Scholar] [CrossRef]
  23. Mohsan, S.A.H.; Islam, A.; Khan, M.A.; Mahmood, A.; Rokia, L.S.; Mazinani, A.; Amjad, H. A Review on Research Challenges, Limitations and Practical Solutions for Underwater Wireless Power Transfer. Int. J. Adv. Comput. Sci. Appl. 2020, 11, 554–562. [Google Scholar] [CrossRef]
  24. Al-Kaff, A.; Martin, D.; Garcia, F.; de la Escalera, A.; Armingol, J.M. Survey of computer vision algorithms and applications for unmanned aerial vehicles. Expert Syst. Appl. 2018, 92, 447–463. [Google Scholar] [CrossRef]
  25. Huang, S.; Teo, R.S.H.; Tan, K.K. Collision avoidance of multi unmanned aerial vehicles: A review. Annu. Rev. Control 2019, 48, 147–164. [Google Scholar] [CrossRef]
  26. Zereik, E.; Bibuli, M.; Mišković, N.; Ridao, P.; Pascoal, A. Challenges and future trends in marine robotics. Annu. Rev. Control 2018, 46, 350–368. [Google Scholar] [CrossRef]
  27. Neira, J.; Sequeiros, C.; Huamani, R.; Machaca, E.; Fonseca, P.; Nina, W. Review on unmanned underwater robotics, structure designs, materials, sensors, actuators, and navigation control. J. Robot. 2021, 2021, 5542920. [Google Scholar] [CrossRef]
  28. Orlowski, M. Directions of development of the autonomous unmanned underwater vehicles. A review. Parameters 2021, 2, 24. [Google Scholar] [CrossRef]
  29. Yildiz, Ö.; Gökalp, R.B.; Yilmaz, A.E. A review on motion control of the underwater vehicles. In Proceedings of the 2009 IEEE International Conference on Electrical and Electronics Engineering-ELECO 2009, Bursa, Turkey, 5–8 November 2009; pp. II-337–II-341. [Google Scholar]
  30. Cheng, C.; Sha, Q.; He, B.; Li, G. Path planning and obstacle avoidance for AUV: A review. Ocean Eng. 2021, 235, 109355. [Google Scholar] [CrossRef]
  31. Hart, P.E.; Nilsson, N.J.; Raphael, B. A formal basis for the heuristic determination of minimum cost paths. IEEE Trans. Syst. Sci. Cybern. 1968, 4, 100–107. [Google Scholar] [CrossRef]
  32. Eichhorn, M. An obstacle avoidance system for an autonomous underwater vehicle. In Proceedings of the 2004 IEEE International Symposium on Underwater Technology (IEEE Cat. No. 04EX869), Taipei, Taiwan, 20–23 April 2004; pp. 75–82. [Google Scholar]
  33. Casalino, G.; Turetta, A.; Simetti, E. A three-layered architecture for real time path planning and obstacle avoidance for surveillance USVs operating in harbour fields. In Proceedings of the Oceans 2009 IEEE-Europe, Bremen, Germany, 11–14 May 2009; pp. 1–8. [Google Scholar]
  34. Li, J.H.; Lee, M.J.; Park, S.H.; Kim, J.G. Real time path planning for a class of torpedo-type AUVs in unknown environment. In Proceedings of the 2012 IEEE/OES Autonomous Underwater Vehicles (AUV), Southampton, UK, 24–27 September 2012; pp. 1–6. [Google Scholar]
  35. Li, M.; Zhang, H. AUV 3D path planning based on A* algorithm. In Proceedings of the 2020 IEEE Chinese Automation Congress (CAC), Shanghai, China, 6–8 November 2020; pp. 11–16. [Google Scholar]
  36. Khatib, O. Real-time obstacle avoidance for manipulators and mobile robots. In Autonomous Robot Vehicles; Springer: New York, NY, USA, 1986; pp. 396–404. [Google Scholar]
  37. Koren, Y.; Borenstein, J. Potential field methods and their inherent limitations for mobile robot navigation. In Proceedings of the ICRA, Sacramento, CA, USA, 9–11 April 1991; Volume 2, pp. 1398–1404. [Google Scholar]
  38. Teo, K.; Ong, K.W.; Lai, H.C. Obstacle detection, avoidance and anti collision for MEREDITH AUV. In Proceedings of the OCEANS IEEE 2009, Biloxi, MS, USA, 26–29 October 2009; pp. 1–10. [Google Scholar]
  39. Qing, L.; Li-jun, W.; Bo, C.; Zhou, Z.; Yi-xin, Y. An improved artificial potential field method with parameters optimization based on genetic algorithms. J. Univ. Sci. Technol. 2012, 34, 202–206. [Google Scholar]
  40. Barraquand, J.; Latombe, J.C. Robot motion planning: A distributed representation approach. Int. J. Robot. Res. 1991, 10, 628–649. [Google Scholar] [CrossRef]
  41. Solari, F.J.; Rozenfeld, A.F.; Villar, S.A.; Acosta, G.G. Artificial potential fields for the obstacles avoidance system of an AUV using a mechanical scanning sonar. In Proceedings of the 2016 3rd IEEE/OES South American International Symposium on Oceanic Engineering (SAISOE), Buenos Aires, Arhentina, 14–17 June 2016; pp. 1–6. [Google Scholar]
  42. Youakim, D.; Ridao, P. Motion planning survey for autonomous mobile manipulators underwater manipulator case study. Robot. Auton. Syst. 2018, 107, 20–44. [Google Scholar] [CrossRef]
  43. Leonard, N.E.; Fiorelli, E. Virtual leaders, artificial potentials and coordinated control of groups. In Proceedings of the 40th IEEE Conference on Decision and Control (Cat. No. 01CH37228), Orlando, FL, USA, 4–7 December 2001; Volume 3, pp. 2968–2973. [Google Scholar]
  44. Gazi, V. Swarm aggregations using artificial potentials and sliding-mode control. IEEE Trans. Robot. 2005, 21, 1208–1214. [Google Scholar] [CrossRef]
  45. Olfati-Saber, R. Flocking for multi-agent dynamic systems: Algorithms and theory. IEEE Trans. Autom. Control 2006, 51, 401–420. [Google Scholar] [CrossRef] [Green Version]
  46. Meng, Z.; Lin, Z.; Ren, W. Leader–follower swarm tracking for networked Lagrange systems. Syst. Control Lett. 2012, 61, 117–126. [Google Scholar] [CrossRef]
  47. Hou, S.P.; Cheah, C.C. Can a simple control scheme work for a formation control of multiple autonomous underwater vehicles? IEEE Trans. Control Syst. Technol. 2010, 19, 1090–1101. [Google Scholar] [CrossRef]
  48. Sorbi, L.; De Capua, G.P.; Toni, L.; Fontaine, J.G. Target detection and recognition: A mission planner for Autonomous Underwater Vehicles. In Proceedings of the IEEE OCEANS’11 MTS/IEEE KONA, Waikoloa, HI, USA, 19–22 September 2011; pp. 1–5. [Google Scholar]
  49. Horner, D.; Healey, A.; Kragelund, S. AUV experiments in obstacle avoidance. In Proceedings of the IEEE OCEANS 2005 MTS/IEEE, Washington, DC, USA, 17–23 September 2005; pp. 1464–1470. [Google Scholar]
  50. LaValle, S.M. Rapidly-Exploring Random Trees: A New Tool for Path Planning. Available online: https://www.cs.csustan.edu/~xliang/Courses/CS4710-21S/Papers/06 (accessed on 1 July 2022).
  51. Tan, C.S.; Sutton, R.; Chudley, J. An integrated collision avoidance system for autonomous underwater vehicles. Int. J. Control 2007, 80, 1027–1049. [Google Scholar] [CrossRef]
  52. Hernández, J.D.; Vidal, E.; Vallicrosa, G.; Galceran, E.; Carreras, M. Online path planning for autonomous underwater vehicles in unknown environments. In Proceedings of the 2015 IEEE International Conference on Robotics and Automation (ICRA), Seattle, WA, USA, 26–30 May 2015; pp. 1152–1157. [Google Scholar]
  53. Cui, R.; Li, Y.; Yan, W. Mutual information-based multi-AUV path planning for scalar field sampling using multidimensional RRT. IEEE Trans. Syst. Man Cybern. Syst. 2015, 46, 993–1004. [Google Scholar] [CrossRef]
  54. Xanthidis, M.; Karapetyan, N.; Damron, H.; Rahman, S.; Johnson, J.; O’Connell, A.; O’Kane, J.M.; Rekleitis, I. Navigation in the presence of obstacles for an agile autonomous underwater vehicle. In Proceedings of the 2020 IEEE International Conference on Robotics and Automation (ICRA), Paris, France, 31 May–31 August 2020; pp. 892–899. [Google Scholar]
  55. Tan, C.S. A Collision Avoidance System for Autonomous Underwater Vehicles. Available online: https://pearl.plymouth.ac.uk/handle/10026.1/2258 (accessed on 1 July 2022).
  56. Piskur, P.; Szymak, P.; Jaskólski, K.; Flis, L.; Gąsiorowski, M. Hydroacoustic system in a biomimetic underwater vehicle to avoid collision with vessels with low-speed propellers in a controlled environment. Sensors 2020, 20, 968. [Google Scholar] [CrossRef] [Green Version]
  57. Piskur, P.; Gasiorowski, M. Digital Signal Processing for Hydroacoustic System in Biomimetic Underwater Vehicle. NAŠE MORE Znan. časopis Za More I Pomor. 2020, 67, 14–18. [Google Scholar] [CrossRef] [Green Version]
  58. Tan, C.S.; Sutton, R.; Chudley, J. An incremental stochastic motion planning technique for autonomous underwater vehicles. IFAC Proc. 2004, 37, 483–488. [Google Scholar] [CrossRef]
  59. Zhao, S.; Lu, T.F.; Anvar, A. Multiple obstacles detection using fuzzy interface system for auv navigation in natural water. In Proceedings of the 2010 IEEE 5th Conference on Industrial Electronics and Applications, Taichung, Taiwan, 15–17 June 2010; pp. 50–55. [Google Scholar]
  60. Piskur, P.; Szymak, P.; Flis, L.; Sznajder, J. Analysis of a Fin Drag Force in a Biomimetic Underwater Vehicle. NAŠE MORE Znan. časopis Za More I Pomor. 2020, 67, 192–198. [Google Scholar] [CrossRef]
  61. Piskur, P.; Szymak, P.; Przybylski, M.; Naus, K.; Jaskólski, K.; Żokowski, M. Innovative energy-saving propulsion system for low-speed biomimetic underwater vehicles. Energies 2021, 14, 8418. [Google Scholar] [CrossRef]
  62. Szymak, P.; Piskur, P.; Naus, K. The Effectiveness of Using a Pretrained Deep Learning Neural Networks for Object Classification in Underwater Video. Remote Sens. 2020, 12, 3020. [Google Scholar] [CrossRef]
  63. Meng, F.; Liu, A.; Jing, S.; Zu, Y. FSM trajectory tracking controllers of OB-AUV in the horizontal plane. In Proceedings of the 2021 IEEE International Conference on Intelligence and Safety for Robotics (ISR), Tokoname, Japan, 4–6 March 2021; pp. 204–208. [Google Scholar]
  64. DeMuth, G.; Springsteen, S. Obstacle avoidance using neural networks. In Proceedings of the IEEE Symposium on Autonomous Underwater Vehicle Technology, Washington, DC, USA, 5–6 June 1990; pp. 213–215. [Google Scholar]
  65. Guerrero-González, A.; García-Córdova, F.; Gilabert, J. A biologically inspired neural network for navigation with obstacle avoidance in autonomous underwater and surface vehicles. In Proceedings of the OCEANS 2011 IEEE, Santander, Spain, 6–9 June 2011; pp. 1–8. [Google Scholar]
  66. Ding, G.; Zhu, D.; Sun, B. Formation control and obstacle avoidance of multi-AUV for 3-D underwater environment. In Proceedings of the 33rd IEEE Chinese Control Conference, Nanjing, China, 28–30 July 2014; pp. 8347–8352. [Google Scholar]
  67. Gaya, J.O.; Gonçalves, L.T.; Duarte, A.C.; Zanchetta, B.; Drews, P.; Botelho, S.S. Vision-based obstacle avoidance using deep learning. In Proceedings of the 2016 XIII IEEE Latin American Robotics Symposium and IV Brazilian Robotics Symposium (LARS/SBR), Recife, Brazil, 8–12 October 2016; pp. 7–12. [Google Scholar]
  68. Jurczyk, K.; Piskur, P.; Szymak, P. Parameters identification of the flexible fin kinematics model using vision and Genetic Algorithms. Pol. Marit. Res. 2020, 27, 39–47. [Google Scholar] [CrossRef]
  69. Alvarez, A.; Caiti, A.; Onken, R. Evolutionary path planning for autonomous underwater vehicles in a variable ocean. IEEE J. Ocean. Eng. 2004, 29, 418–429. [Google Scholar] [CrossRef]
  70. Yan, S.; Pan, F. Research on route planning of auv based on genetic algorithms. In Proceedings of the 2019 IEEE International Conference on Unmanned Systems and Artificial Intelligence (ICUSAI), Xi’an, China, 22–24 November 2019; pp. 184–187. [Google Scholar]
  71. Wu, X.; Feng, Z.; Zhu, J.; Allen, R. Line of sight guidance with intelligent obstacle avoidance for autonomous underwater vehicles. In Proceedings of the OCEANS 2006 IEEE, Singapore, 16–19 May 2006; pp. 1–6. [Google Scholar]
  72. Chang, Z.H.; Tang, Z.D.; Cai, H.G.; Shi, X.C.; Bian, X.Q. GA path planning for AUV to avoid moving obstacles based on forward looking sonar. In Proceedings of the 2005 IEEE International Conference on Machine Learning and Cybernetics, Waikoloa, HI, USA, 10–12 October 2005; Volume 3, pp. 1498–1502. [Google Scholar]
  73. Yao, P.; Zhao, S. Three-dimensional path planning for AUV based on interfered fluid dynamical system under ocean current (June 2018). IEEE Access 2018, 6, 42904–42916. [Google Scholar] [CrossRef]
  74. Zadeh, L. Fuzzy sets. Inf. Control 1965, 8, 338–353. [Google Scholar] [CrossRef] [Green Version]
  75. Zadeh, L. Fuzzy algorithms. Inf. Control 1968, 12, 94–102. [Google Scholar] [CrossRef] [Green Version]
  76. Galarza, C.; Masmitja, I.; Prat, J.; Gomaríz, S. Design of obstacle detection and avoidance system for Guanay II AUV. In Proceedings of the 2016 IEEE 24th Mediterranean Conference on Control and Automation (MED), Athens, Greece, 21–24 June 2016; pp. 410–414. [Google Scholar]
  77. Zhu, D.; Yang, Y.; Yan, M. Path planning algorithm for AUV based on a Fuzzy-PSO in dynamic environments. In Proceedings of the 2011 IEEE Eighth International Conference on Fuzzy Systems and Knowledge Discovery (FSKD), Shanghai, China, 26–28 July 2011; Volume 1, pp. 525–530. [Google Scholar]
  78. Li, X.; Wang, W.; Song, J.; Liu, D. Path planning for autonomous underwater vehicle in presence of moving obstacle based on three inputs fuzzy logic. In Proceedings of the 2019 IEEE 4th Asia-Pacific Conference on Intelligent Robot Systems (ACIRS), Nagoya, Japan, 13–15 July 2019; pp. 265–268. [Google Scholar]
  79. Braginsky, B.; Guterman, H. Obstacle avoidance approaches for autonomous underwater vehicle: Simulation and experimental results. IEEE J. Ocean. Eng. 2016, 41, 882–892. [Google Scholar] [CrossRef]
  80. Szymak, P. Zorientowany na Sterowanie Model Ruchu oraz Neuro-Ewolucyjno-Rozmyta Metoda Sterowania bezzałOgowymi Jednostkami Pływającymi; Politechnika Krakowska: Krakow, Poland, 2015. [Google Scholar]
  81. Huang, W.; Fang, H.; Li, L. Obstacle avoiding policy of multi-AUV formation based on virtual AUV. In Proceedings of the 2009 IEEE Sixth International Conference on Fuzzy Systems and Knowledge Discovery, Tianjin, China, 14–16 August 2009; Volume 4, pp. 131–135. [Google Scholar]
  82. Sutton, R.S.; Barto, A.G. Introduction to Reinforcement Learning. Introduction to Reinforcement Learning. Available online: https://login.cs.utexas.edu/sites/default/files/legacy_files/research/documents/1%20intro%20up%20to%20RL%3ATD.pdf (accessed on 1 July 2022).
  83. Szepesvári, C. Algorithms for reinforcement learning. Synth. Lect. Artif. Intell. Mach. Learn. 2010, 4, 1–103. [Google Scholar]
  84. Arai, Y.; Fujii, T.; Asama, H.; Kaetsu, H.; Endo, I. Collision avoidance in multi-robot systems based on multi-layered reinforcement learning. Robot. Auton. Syst. 1999, 29, 21–32. [Google Scholar] [CrossRef]
  85. Du, W.; Guo, T.; Chen, J.; Li, B.; Zhu, G.; Cao, X. Cooperative pursuit of unauthorized UAVs in urban airspace via Multi-agent reinforcement learning. Transp. Res. Part C Emerg. Technol. 2021, 128, 103122. [Google Scholar] [CrossRef]
  86. Chen, C.; Chen, X.Q.; Ma, F.; Zeng, X.J.; Wang, J. A knowledge-free path planning approach for smart ships based on reinforcement learning. Ocean Eng. 2019, 189, 106299. [Google Scholar] [CrossRef]
  87. Gore, R.; Pattanaik, K.; Bharti, S. Efficient Re-Planned Path for Autonomous Underwater Vehicle in Random Obstacle Scenario. In Proceedings of the 2019 IEEE 5th International Conference for Convergence in Technology (I2CT), Bombay, India, 29–31 March 2019; pp. 1–5. [Google Scholar]
  88. Li, W.; Yang, X.; Yan, J.; Luo, X. An obstacle avoiding method of autonomous underwater vehicle based on the reinforcement learning. In Proceedings of the 2020 IEEE 39th Chinese Control Conference (CCC), Shenyang, China, 27–29 July 2020; pp. 4538–4543. [Google Scholar]
  89. Williams, G.N.; Lagace, G.E.; Woodfin, A. A collision avoidance controller for autonomous underwater vehicles. In Proceedings of the IEEE Symposium on Autonomous Underwater Vehicle Technology, Washington, DC, USA, 5–6 June 1990; pp. 206–212. [Google Scholar]
  90. Antonelli, G.; Chiaverini, S.; Finotello, R.; Schiavon, R. Real-time path planning and obstacle avoidance for RAIS: An autonomous underwater vehicle. IEEE J. Ocean. Eng. 2001, 26, 216–227. [Google Scholar] [CrossRef]
  91. Creuze, V.; Jouvencel, B. Avoidance of underwater cliffs for autonomous underwater vehicles. In Proceedings of the IEEE/RSJ International Conference on Intelligent Robots and Systems, Lausanne, Switzerland, 30 September–4 October 2002; Volume 1, pp. 793–798. [Google Scholar]
  92. Healey, A.J. Obstacle avoidance while bottom following for the REMUS autonomous underwater vehicle. IFAC Proc. 2004, 37, 251–256. [Google Scholar]
  93. Quidu, I.; Hétet, A.; Dupas, Y.; Lefèvre, S. AUV (Redermor) obstacle detection and avoidance experimental evaluation. In Proceedings of the IEEE OCEANS 2007-Europe, Aberdeen, Scotland, 18–21 June 2007; pp. 1–6. [Google Scholar]
  94. Jia, Q.; Li, G. Formation control and obstacle avoidance algorithm of multiple autonomous underwater vehicles (AUVs) based on potential function and behavior rules. In Proceedings of the 2007 IEEE International Conference on Automation and Logistics, Jinan, China, 18–21 August 2007; pp. 569–573. [Google Scholar]
  95. Fan, S.; Feng, Z.; Lian, L. Collision free formation control for multiple autonomous underwater vehicles. In Proceedings of the OCEANS’10 IEEE Sydney, Sydney, Australia, 24–27 May 2010; pp. 1–4. [Google Scholar]
  96. Conte, G.; Zanoli, S. A sonar based obstacle avoidance system for AUVs. In Proceedings of the IEEE Symposium on Autonomous Underwater Vehicle Technology (AUV’94), Cambridge, MA, USA, 19–20 July 1994; pp. 85–91. [Google Scholar]
  97. Zapata, R.; Lepinay, P. Collision avoidance and bottom following of a torpedo-like AUV. In Proceedings of the OCEANS 96 MTS/IEEE Conference Proceedings, The Coastal Ocean-Prospects for the 21st Century, Fort Lauderdale, FL, USA, 23–26 September 1996; Volume 2, pp. 571–575. [Google Scholar]
  98. Petillot, Y.; Ruiz, I.T.; Lane, D.M. Underwater vehicle obstacle avoidance and path planning using a multi-beam forward looking sonar. IEEE J. Ocean. Eng. 2001, 26, 240–251. [Google Scholar] [CrossRef] [Green Version]
  99. Fodrea, L.R.; Healey, A.J. Obstacle avoidance control for the REMUS autonomous underwater vehicle. IFAC Proc. 2003, 36, 103–108. [Google Scholar] [CrossRef]
  100. Kawano, H. Real-time obstacle avoidance for underactuated autonomous underwater vehicles in unknown vortex sea flow by the mdp approach. In Proceedings of the 2006 IEEE/RSJ International Conference on Intelligent Robots and Systems, Beijing, China, 9–13 October 2006; pp. 3024–3031. [Google Scholar]
  101. Barišić, M.; Vukić, Z.; Mišković, N. A kinematic virtual potentials trajectory planner for AUV-s. IFAC Proc. Vol. 2007, 40, 90–95. [Google Scholar] [CrossRef] [Green Version]
  102. Yakimenko, O.A. Real-Time Computation of Spatial and Flat Obstacle Avoidance Trajectories for UUVs. IFAC Proc. 2008, 41, 202–207. [Google Scholar] [CrossRef]
  103. Eichhorn, M. A new concept for an obstacle avoidance system for the AUV “SLOCUM Glider” operation under ice. In Proceedings of the IEEE Oceans 2009-Europe, Bremen, Germany, 11–14 May 2009; pp. 1–8. [Google Scholar]
  104. Xu, H.; Feng, X. An AUV fuzzy obstacle avoidance method under event feedback supervision. In Proceedings of the IEEE Oceans 2009, Biloxi, MS, USA, 26–29 October 2009; pp. 1–6. [Google Scholar]
  105. Wadhams, P.; Wilkinson, J.P.; McPhail, S. A new view of the underside of Arctic sea ice. Geophys. Res. Lett. 2006, 33. [Google Scholar] [CrossRef]
  106. Pebody, M. Autonomous underwater vehicle collision avoidance for under-ice exploration. Proc. Inst. Mech. Eng. Part M J. Eng. Marit. Environ. 2008, 222, 53–66. [Google Scholar] [CrossRef]
  107. McPhail, S.D.; Furlong, M.E.; Pebody, M.; Perrett, J.; Stevenson, P.; Webb, A.; White, D. Exploring beneath the PIG Ice Shelf with the Autosub3 AUV. In Proceedings of the IEEE Oceans 2009-Europe, Bremen, Germany, 11–14 May 2009; pp. 1–8. [Google Scholar]
  108. Braginsk, B.; Karabchevsk, S.; Guterma, H. Two layers obstacle avoidance algorithm for autonomous underwater vehicle. In Proceedings of the 2012 IEEE 27th Convention of Electrical and Electronics Engineers in Israel, Eilat, Israel, 14–17 November 2012; pp. 1–5. [Google Scholar]
  109. Karabchevsky, S.; Braginsky, B.; Guterman, H. AUV real-time acoustic vertical plane obstacle detection and avoidance. In Proceedings of the 2012 IEEE/OES Autonomous Underwater Vehicles (AUV), Southampton, UK, 24–27 September 2012; pp. 1–6. [Google Scholar]
  110. Cheng, C.; Zhu, D.; Sun, B.; Chu, Z.; Nie, J.; Zhang, S. Path planning for autonomous underwater vehicle based on artificial potential field and velocity synthesis. In Proceedings of the 2015 IEEE 28th Canadian Conference on Electrical and Computer Engineering (CCECE), Halifax, NS, Canada, 3–6 May 2015; pp. 717–721. [Google Scholar]
  111. Subramanian, S.; George, T.; Thondiyath, A. Hardware-in-the-Loop verification for 3D obstacle avoidance algorithm of an underactuated flat-fish type AUV. In Proceedings of the 2012 IEEE International Conference on Robotics and Biomimetics (ROBIO), Guangzhou, China, 11–14 December 2012; pp. 545–550. [Google Scholar]
  112. Yang, Y.; Zhu, D. Research on dynamic path planning of auv based on forward looking sonar and fuzzy control. In Proceedings of the 2011 IEEE Chinese Control and Decision Conference (CCDC), Mianyang, China, 23–25 May 2011; pp. 2425–2430. [Google Scholar]
  113. Sun, Y.; Wu, H.; Zhang, Y.; Li, C. Obstacle avoidance of autonomous underwater vehicle based on improved balance of motion. In Proceedings of the 2013 IEEE 2nd International Conference on Measurement, Information and Control, Harbin, China, 16–18 August 2013; Volume 2, pp. 788–792. [Google Scholar]
  114. Wang, H.; Wang, L.; Li, J.; Pan, L. A vector polar histogram method based obstacle avoidance planning for AUV. In Proceedings of the 2013 MTS/IEEE OCEANS-Bergen, Bergen, Norway, 10–14 June 2013; pp. 1–5. [Google Scholar]
  115. Millar, G. An obstacle avoidance system for autonomous underwater vehicles: A reflexive vector field approach utilizing obstacle localization. In Proceedings of the 2014 IEEE/OES Autonomous Underwater Vehicles (AUV), Oxford, MS, USA, 6–9 October 2014; pp. 1–4. [Google Scholar]
  116. Xu, H.; Gao, L.; Liu, J.; Wang, Y.; Zhao, H. Experiments with obstacle and terrain avoidance of autonomous underwater vehicle. In Proceedings of the Oceans 2015-MTS/IEEE Washington, Washington, DC, USA, 19–22 October 2015; pp. 1–4. [Google Scholar]
  117. Yan, Z.; Li, J.; Jiang, A.; Wang, L. An Obstacle Avoidance Algorithm for AUV Based on Obstacle’s Detected Outline. In Proceedings of the 2018 IEEE 37th Chinese Control Conference (CCC), Wuhan, China, 25–27 July 2018; pp. 5257–5262. [Google Scholar]
  118. Chu, Z.; Zhu, D. Obstacle Avoidance Trajectory Planning and Trajectory Tracking Control for Autonomous Underwater Vehicles. In Proceedings of the 2018 IEEE 13th World Congress on Intelligent Control and Automation (WCICA), Changsha, China, 4–8 July 2018; pp. 450–454. [Google Scholar]
  119. Haoran, L.; Hongjun, D.; Yakun, Z. Avoidance for AUV with mobile obstacles based on current interference. In Proceedings of the 2019 3rd International Symposium on Autonomous Systems (ISAS), Shanghai, China, 29–31 May 2019; pp. 137–142. [Google Scholar] [CrossRef]
  120. Sahu, B.K.; Subudhi, B. Flocking control of multiple AUVs based on fuzzy potential functions. IEEE Trans. Fuzzy Syst. 2017, 26, 2539–2551. [Google Scholar] [CrossRef]
  121. Li, X.; Zhu, D. An adaptive SOM neural network method for distributed formation control of a group of AUVs. IEEE Trans. Ind. Electron. 2018, 65, 8260–8270. [Google Scholar] [CrossRef]
  122. Wu, J.; Song, C.; Fan, C.; Hawbani, A.; Zhao, L.; Sun, X. DENPSO: A distance evolution nonlinear PSO algorithm for energy-efficient path planning in 3D UASNs. IEEE Access 2019, 7, 105514–105530. [Google Scholar] [CrossRef]
  123. Hou, X.; Pan, X.; Bi, M. Research on Non-collision Coordination Control Technology for Formation Autonomous Underwater Vehicle. In Proceedings of the 2019 IEEE 3rd Advanced Information Management, Communicates, Electronic and Automation Control Conference (IMCEC), Chongqing, China, 11–13 October 2019; pp. 1178–1183. [Google Scholar]
  124. Zhu, Y. A multi-AUV searching algorithm based on neuron network with obstacle. In Proceedings of the 2019 IEEE 3rd International Symposium on Autonomous Systems (ISAS), Shanghai, China, 29–31 May 2019; pp. 131–136. [Google Scholar]
  125. Ma, X.; Yanli, C.; Bai, G.; Liu, J. Multi-AUV collaborative operation based on time-varying navigation map and dynamic grid model. IEEE Access 2020, 8, 159424–159439. [Google Scholar] [CrossRef]
  126. Grefstad, Ø.; Schjølberg, I. Navigation and collision avoidance of underwater vehicles using sonar data. In Proceedings of the 2018 IEEE/OES Autonomous Underwater Vehicle Workshop (AUV), Porto, Portugal, 6–9 November 2018; pp. 1–6. [Google Scholar]
  127. Praczyk, T.; Szymak, P.; Naus, K.; Pietrukaniec, L.; Hożyń, S. Report on research with biomimetic autonomous underwater vehicle—Navigation and autonomous operation. Zesz. Nauk. Akad. Mar. Wojennej 2018, 59. [Google Scholar] [CrossRef] [Green Version]
  128. Yu, H.; Lu, W.; Liu, D. A unified closed-loop motion planning approach for an I-AUV in cluttered environment with localization uncertainty. In Proceedings of the 2019 IEEE International Conference on Robotics and Automation (ICRA), Montreal, QC, Canada, 20–24 May 2019; pp. 4646–4652. [Google Scholar]
  129. Felski, A.; Jaskolski, K.; Zwolak, K.; Piskur, P. Analysis of Satellite Compass Error’s Spectrum. Sensors 2020, 20, 4067. [Google Scholar] [CrossRef]
  130. Ferreira, F.; Petroccia, R.; Alves, J. Underwater/surface collision avoidance using underwater acoustic communications-a preliminary analysis. In Proceedings of the IEEE Oceans 2019-Marseille, Marseille, France, 17–20 June 2019; pp. 1–10. [Google Scholar]
  131. Eriksen, B.O.H.; Breivik, M.; Pettersen, K.Y.; Wiig, M.S. A modified dynamic window algorithm for horizontal collision avoidance for AUVs. In Proceedings of the 2016 IEEE Conference on Control Applications (CCA), Buenos Aires, Argentina, 19–22 September 2016; pp. 499–506. [Google Scholar]
  132. Simoni, R.; Rodríguez, P.R.; Cieślak, P.; Youakim, D. A novel approach to obstacle avoidance for an I-AUV. In Proceedings of the 2018 IEEE/OES Autonomous Underwater Vehicle Workshop (AUV), Porto, Portugal, 6–9 November 2018; pp. 1–6. [Google Scholar]
  133. Kappagantula, S.; Ramadass, G.; Adlinge, S.D. Design of a Biomimetic Robot Fish for Realization of Coefficient of Drag with Control Architecture and Fuzzy Logic Algorithm for Autonomous Obstacle Avoidance. In Proceedings of the 2018 IEEE 3rd International Conference for Convergence in Technology (I2CT), Pune, India, 6–8 April 2018; pp. 1–9. [Google Scholar]
  134. Yan, Z.; Li, J.; Wu, Y.; Yang, Z. A novel path planning for AUV based on objects’ motion parameters predication. IEEE Access 2018, 6, 69304–69320. [Google Scholar] [CrossRef]
  135. Vibhute, S. Adaptive dynamic programming based motion control of autonomous underwater vehicles. In Proceedings of the 2018 IEEE 5th International Conference on Control, Decision and Information Technologies (CoDIT), Thessaloniki, Greece, 10–13 April 2018; pp. 966–971. [Google Scholar]
  136. Liu, R.D.; Chen, Z.G.; Wang, Z.J.; Zhan, Z.H. Intelligent path planning for AUVs in dynamic environments: An EDA-based learning fixed height histogram approach. IEEE Access 2019, 7, 185433–185446. [Google Scholar] [CrossRef]
  137. Fanelli, F.; Fenucci, D.; Marlow, R.; Pebody, M.; Phillips, A.B. Development of a multi-platform obstacle avoidance system for autonomous underwater vehicles. In Proceedings of the 2020 IEEE/OES Autonomous Underwater Vehicles Symposium (AUV), St Johns, NL, Canada, 30 September–2 October 2020; pp. 1–6. [Google Scholar]
  138. Liu, Y.; Liu, L.; Yu, X.; Wang, C. Optimal Path Planning Algorithm of AUV State Space Sampling Based on Improved Cost Function. In Proceedings of the 2020 IEEE 39th Chinese Control Conference (CCC), Shenyang, China, 27–29 July 2020; pp. 3747–3752. [Google Scholar]
  139. Praczyk, T. Neural collision avoidance system for biomimetic autonomous underwater vehicle. Soft Comput. 2020, 24, 1315–1333. [Google Scholar] [CrossRef] [Green Version]
  140. McMahon, J.; Plaku, E. Mission and motion planning for autonomous underwater vehicles operating in spatially and temporally complex environments. IEEE J. Ocean. Eng. 2016, 41, 893–912. [Google Scholar] [CrossRef]
  141. Okamoto, A.; Sasano, M.; Seta, T.; Inaba, S.; Sato, K.; Tamura, K.; Nishida, Y.; Ura, T. Obstacle avoidance method appropriate for the steep terrain of the deep seafloor. In Proceedings of the 2016 IEEE Techno-Ocean (Techno-Ocean), Kobe, Japan, 6–8 October 2016; pp. 195–198. [Google Scholar]
  142. McEwen, R.S.; Rock, S.P.; Hobson, B. Iceberg wall following and obstacle avoidance by an AUV. In Proceedings of the 2018 IEEE/OES Autonomous Underwater Vehicle Workshop (AUV), Porto, Portugal, 6–9 November 2018; pp. 1–8. [Google Scholar]
  143. Okamoto, A.; Sasano, M.; Seta, T.; Hirao, S.C.; Inaba, S. Deployment of the auv hobalin to an active hydrothermal vent field with an improved obstacle avoidance system. In Proceedings of the 2018 IEEE OCEANS-MTS/IEEE Kobe Techno-Oceans (OTO), Kobe, Japan, 28–31 May 2018; pp. 1–6. [Google Scholar]
  144. Hernández, J.D.; Vidal, E.; Moll, M.; Palomeras, N.; Carreras, M.; Kavraki, L.E. Online motion planning for unexplored underwater environments using autonomous underwater vehicles. J. Field Robot. 2019, 36, 370–396. [Google Scholar] [CrossRef]
  145. Zheng, J.; Song, L.; Liu, L.; Yu, W.; Wang, Y.; Chen, C. Fixed-time sliding mode tracking control for autonomous underwater vehicles. Appl. Ocean Res. 2021, 117, 102928. [Google Scholar] [CrossRef]
  146. Chen, Y.L.; Hu, X.Y.; Ma, X.W.; Bai, G.Q. Adaptive location correction and path re-planning based on error estimation method in underwater sensor networks. Ocean Eng. 2022, 252, 111257. [Google Scholar] [CrossRef]
  147. Elhaki, O.; Shojaei, K.; Mehrmohammadi, P. Reinforcement learning-based saturated adaptive robust neural-network control of underactuated autonomous underwater vehicles. Expert Syst. Appl. 2022, 197, 116714. [Google Scholar] [CrossRef]
  148. Heshmati-Alamdari, S.; Nikou, A.; Dimarogonas, D.V. Robust trajectory tracking control for underactuated autonomous underwater vehicles in uncertain environments. IEEE Trans. Autom. Sci. Eng. 2020, 18, 1288–1301. [Google Scholar] [CrossRef]
  149. Chen, B.; Ma, H.; Kang, H.; Liang, X. Multi-agent Distributed Formation Control Based on Improved Artificial Potential Field and Neural Network for Connectivity Preservation. In Proceedings of the 2021 IEEE International Conference on Unmanned Systems (ICUS), Beijing, China, 15–17 October 2021; pp. 455–460. [Google Scholar]
  150. Zhu, D.; Zhou, B.; Yang, S.X. A Novel Algorithm of Multi-AUVs Task Assignment and Path Planning Based on Biologically Inspired Neural Network Map. IEEE Trans. Intell. Veh. 2021, 6, 333–342. [Google Scholar] [CrossRef]
  151. Zhang, J.; Liu, M.; Zhang, S.; Zheng, R.; Dong, S. Multi-AUV Adaptive Path Planning and Cooperative Sampling for Ocean Scalar Field Estimation. IEEE Trans. Instrum. Meas. 2022, 71, 1–14. [Google Scholar] [CrossRef]
  152. Sun, Y.; Luo, X.; Ran, X.; Zhang, G. A 2D Optimal Path Planning Algorithm for Autonomous Underwater Vehicle Driving in Unknown Underwater Canyons. J. Mar. Sci. Eng. 2021, 9, 252. [Google Scholar] [CrossRef]
  153. Scharff Willners, J.; Gonzalez-Adell, D.; Hernández, J.D.; Pairet, È.; Petillot, Y. Online 3-dimensional path planning with kinematic constraints in unknown environments using hybrid A* with tree pruning. Sensors 2021, 21, 1152. [Google Scholar] [CrossRef]
  154. Yuan, J.; Wang, H.; Zhang, H.; Lin, C.; Yu, D.; Li, C. AUV obstacle avoidance planning based on deep reinforcement learning. J. Mar. Sci. Eng. 2021, 9, 1166. [Google Scholar] [CrossRef]
  155. Qiu, X.; Feng, C.; Shen, Y. Obstacle avoidance planning combining reinforcement learning and RRT* applied to underwater operations. In Proceedings of the OCEANS 2021: San Diego–Porto IEEE, San Diego, France, 20–23 September 2021; pp. 1–6. [Google Scholar]
  156. Lim, H.S.; King, P.; Chin, C.K.; Chai, S.; Bose, N. Real-time implementation of an online path replanner for an AUV operating in a dynamic and unexplored environment. Appl. Ocean Res. 2022, 118, 103006. [Google Scholar] [CrossRef]
  157. Liu, J.; Zhao, M.; Qiao, L. Adaptive barrier Lyapunov function-based obstacle avoidance control for an autonomous underwater vehicle with multiple static and moving obstacles. Ocean Eng. 2022, 243, 110303. [Google Scholar] [CrossRef]
  158. Qin, R.; Zhao, X.; Zhu, W.; Yang, Q.; He, B.; Li, G.; Yan, T. Multiple receptive field network (MRF-Net) for autonomous underwater vehicle fishing net detection using forward-looking sonar images. Sensors 2021, 21, 1933. [Google Scholar] [CrossRef] [PubMed]
  159. Zhang, H.; Zhang, S.; Wang, Y.; Liu, Y.; Yang, Y.; Zhou, T.; Bian, H. Subsea pipeline leak inspection by autonomous underwater vehicle. Appl. Ocean Res. 2021, 107, 102321. [Google Scholar] [CrossRef]
  160. An, R.; Guo, S.; Zheng, L.; Hirata, H.; Gu, S. Uncertain moving obstacles avoiding method in 3D arbitrary path planning for a spherical underwater robot. Robot. Auton. Syst. 2022, 151, 104011. [Google Scholar] [CrossRef]
  161. Ridao, P.; Carreras, M.; Ribas, D.; Sanz, P.J.; Oliver, G. Intervention AUVs: The next challenge. Annu. Rev. Control 2015, 40, 227–241. [Google Scholar] [CrossRef] [Green Version]
  162. Yue, C.; Guo, S.; Shi, L. Hydrodynamic analysis of the spherical underwater robot SUR-II. Int. J. Adv. Robot. Syst. 2013, 10, 247. [Google Scholar] [CrossRef]
  163. Li, Y.; Guo, S.; Wang, Y. Design and characteristics evaluation of a novel spherical underwater robot. Robot. Auton. Syst. 2017, 94, 61–74. [Google Scholar] [CrossRef]
  164. Gu, S.; Guo, S.; Zhang, L.; Yao, Y. A hybrid propulsion device for the spherical underwater robot (SUR III). In Proceedings of the 2017 IEEE International Conference on Mechatronics and Automation (ICMA), Kagawa, Japan, 6–9 August 2017; pp. 387–392. [Google Scholar]
Figure 1. An illustration of the RRT mechanism.
Figure 1. An illustration of the RRT mechanism.
Electronics 11 02301 g001
Figure 2. Neural network architecture.
Figure 2. Neural network architecture.
Electronics 11 02301 g002
Figure 3. BAUV examples made at the Polish Naval Academy [own source].
Figure 3. BAUV examples made at the Polish Naval Academy [own source].
Electronics 11 02301 g003
Figure 4. Number of publications in the field of simulation methods and practical implementations of control and collision avoidance systems for AUV in the last 20 years.
Figure 4. Number of publications in the field of simulation methods and practical implementations of control and collision avoidance systems for AUV in the last 20 years.
Electronics 11 02301 g004
Figure 5. Percentage of classical methods used in simulations studies and real applications in the last 20 years.
Figure 5. Percentage of classical methods used in simulations studies and real applications in the last 20 years.
Electronics 11 02301 g005
Figure 6. Classical methods validated in numerical research.
Figure 6. Classical methods validated in numerical research.
Electronics 11 02301 g006
Figure 7. Artificial intelligence methods validated in numerical research.
Figure 7. Artificial intelligence methods validated in numerical research.
Electronics 11 02301 g007
Figure 8. Classical methods in real applications.
Figure 8. Classical methods in real applications.
Electronics 11 02301 g008
Figure 9. Artificial intelligence methods in real applications.
Figure 9. Artificial intelligence methods in real applications.
Electronics 11 02301 g009
Table 1. Surveys connected with motion planning for robots.
Table 1. Surveys connected with motion planning for robots.
ReviewField of AnalisysYearMain Focus
 [7]Robots2005This review elaborated on heuristic algorithms for robots, showing examples of their efficient and inefficient operation.
 [9]Robots2006This review focused on probabilistic foadmap approaches in dealing with dynamic collision, narrow passages, multi-targets, and manipulation planning for deformable linear objects.
 [8]Robots2008This study reviewed sampling-based motion planning algorithms for robots.
 [3]Robots2012This study reviewed motion planning approaches for robots from the years 1980–2010 indicating how the number of heuristic algorithms changed in individual decades compared to conventional algorithms
 [13]Robots2013This study reviewed coverage path planning issues for robots
 [4]Robots2015This study presented the basics of classical and heuristics-based methods for robots.
 [5]Robots2015This review analysed 80 articles from 2011–2015 on motion planning in a dynamic environment for robots and systematised individual solutions in terms of parameters such as smooth path, safety, path length, run-time, accuracy, stability, control, computation cost, efficiency.
 [6]Robots2016This study reviewed 3D path-planning algorithms for robots, focusing on the universality of individual algorithms implementation in aerial, ground, and underwater robots.
 [14]Robots2017This study reviewed searching methods for environmental monitoring
 [15]Robots (Single and multi-robot)2019This study discussed navigation techniques for the single and multi-robot systems in both static and dynamic environments.
 [17]Robots (Multi-robot)2020This study reviewed the available literature in terms of the multi-robot movement in normal and faulty situations.
 [18]Robots (Multi-robot)2021This study focused on methods of determining desired trajectories for multi-robots.
 [16]Robots (Multi-robot)2021This study analysed the techniques of movement of the robot group depending on the shape of the formation.
 [10]Robots2021This study summarized the achievements in the field of quadrupedal robots
 [11]Ground Robots (AV)2015This study presented relevant works in the overtaking and obstacle avoidance maneuvers and also makes an overview of the state-of-the-art implementation of motion planning techniques for automated driving.
 [12]Ground Robots (AV)2021This study reviewed existing approaches on motion and behavior planning for AVs in terms of their feasibility, capability in handling dynamic constraints and obstacles, and optimality of motion for comfort.
 [21]Aerial Robots (UAVs)2010This study presented existing motion-planning algorithms and recent developments in the robotics and aerospace guidance and control fields. The review also analysed perspectives and practical examples from UAV guidance approaches.
 [19]Aerial Robots (UAS)2015This study presented a comparison between different motion-planning algorithms for a multi-rotor UAS with a multi-joint robotic arm.
 [24]Aerial Robots (UAVs)2018This study discussed vision-based algorithms for UAVs.
 [25]Aerial Robots (multi-UAV)2019This study presented a state-of-the-art overview of various approaches for multi-UAV collision avoidance.
 [20]Aerial Robots (multi-UAV)2019This study presented the most relevant Deep Learning techniques for autonomous collision avoidance as well as their application to UAV systems.
 [23]Aerial Robots (UAV)2020This study presented an extensive review of UAVs including physical characteristics, classification, standardization, battery charging, security challenges, and solutions. The research also discussed the perspective of using UAVs in 5G networks, Internet of Things Networks, and different applications.
 [22]Aerial Robots (UAV)2021This study presented the methodology for spatial orientation angle correction for UAV.
 [29]Marine robots(UUV)2009This study reviewed the development of control methods and the problems encountered during the research connected with motion control of UUVs.
 [26]Marine robots2018This study analysed the technological development and limitations that are encountered in marine robotics.
 [27]Marine robots (UUV)2021This study defined the trends in construction, instrumentation, and systems for UUVs.
 [28]Marine robots (single and multi-AUV)2021This study described the main systems for both a single AUV and multi-AUV as well as the possible directions of AUV’s further development.
 [30]Marine robots (AUV)2021This study provides detailed literature that analyses path planning related solutions for AUVs.
This reviewMarine robots (AUV)2022This study provides a structured review of simulations and practical implementations of collision avoidance and path planning algorithm in AUV together with a comparison of the difficulties encountered during simulations and their practical implementation.
Table 2. List of algorithms validated in numerical research until 2010.
Table 2. List of algorithms validated in numerical research until 2010.
ResearchAlgorithmMain Characteristics
 [89]Modified Potential Field method
  • Static and dynamic obstacles
  • Local path planning
  • Simulated clustering sonar returns
 [64]Neural Network
  • Static and dynamic obstacles
  • Local path planning
  • Not necessarily adaptive training, neuron weights defined by the desired AUV response
 [96]Increase or decrease velocity, heading control
  • Dynamic obstacles
  • Sonar data analyse in 2D (horizontal plane)
 [97]Deformable Virtual Zone
  • Static obstacles
  • Local path planning
  • 25 ultrasonic sensors to scan front space in 25 directions
 [2]Reinforcement Learning based on the stochastic real value function
  • Local path planning
  • For AUV named Twin Burger 2
  • In the real application, only detection was achieved. Avoidance behaviors were not obtained due to the complexity of the implemented method.
 [90]Virtual Force Field (VFF)
  • For AUV named RAIS
  • Numerical and Hardware in Loop simulation
 [98]Nonlinear programming technique
  • Local path planning
  • 2D environment
  • Tested on ROV
 [91]Changing pitch angle
  • Static obstacles (underwater cliffs)
  • Local path planning
  • For AUV named Taipan
 [99]Fuzzy Logic
  • 2D environment
  • For AUV named REMUS
 [32]Two-layer control Path planning by Graph method with A* method Reactive control based on Deformable Safety Zone
  • Static and dynamic obstacles
  • For AUV named DeepC
  • Simulations in 2D and 3D environment
 [72]Genetic Algorithm
  • Static and dynamic obstacles
  • 2D simulation
  • Smooth collision-free path
  • Real-time algorithm
 [100]Markov decision process
  • Uncertain static obstacles and vortex
  • 2D environment
  • Real-time algorithm
 [71]Genetic Algorithm tuned Fuzzy Logic planner
  • Static obstacles
  • Global Path Planning
  • Better results than conventional fuzzy logic planners
 [101]Virtual Potential Method
  • 2D environment
  • Static obstacles
 [102]Direct-method-based procedure
  • Horizontal and vertical path planning
  • Static and dynamic obstacles
 [103]Graph algorithm based on time-varying ocean flow
  • Static and dynamic obstacles
  • For AUV named SLOCUM
 [104]Fuzzy Logic
  • Static obstacles
  • 5 possible behaviours for AUV
Table 3. List of algorithms in real applications until 2010.
Table 3. List of algorithms in real applications until 2010.
ResearchAlgorithmMain Characteristics
 [49]Artificial Potential Field
  • Collision avoidance realised by changing depth
  • Equipped with FLS and light underwater camera
 [38]Vector Field Histogram +
  • Static and dynamic obstacles
  • Only 2D heading
 [106,107]Reactive behaviours
  • Static and dynamic obstacles
  • The simplified collision avoidance system
  • Efficient for large obstacles
Table 4. List of algorithms validated in numerical research between 2011–2016.
Table 4. List of algorithms validated in numerical research between 2011–2016.
ResearchAlgorithmMain Characteristics
 [112]Fuzzy interface controller with A/B (accelerate/break) module
  • Static and dynamic obstacles
  • More human-like module’s decision making confirmed by simulation
 [77]Fuzzy-PSO controller with A/B (accelerate/break) module
  • Static and dynamic obstacles
  • Improved navigation performance with great real-time
 [108]Potential Field and Edge Detection methods
  • Increased precision compared to other methods
  • Horizontal plane only
  • Intended for the AUV called Blue Fin 12
 [109]Potential Field and Edge detection methods
  • Vertical plane only
  • The algorithm strongly focuses on safety
 [34]Graph method with A* path find algorithm
  • Not allowed to determine the optimal path in a completely unknown environment
  • Simulation conducted for static obstacles
 [111]Multi-Point Potential Field
  • Static and dynamic obstacles
  • HIL and SIL simulation
 [113]Modified balance points of motion
  • Static and dynamic obstacles
  • Attempt to combine local and global planning
 [114]Vector Polar Histogram (VPH)
  • Uses real sonar data for the simulation
  • Memory function for trap environment
 [110]Velocity synthesis algorithm and Artificial Potential Field method
  • APF method used to avoid obstacles effectively
  • Velocity synthesis algorithm to achieve the optimal path
Table 5. List of algorithms in real applications between 2011–2016.
Table 5. List of algorithms in real applications between 2011–2016.
ResearchAlgorithmMain Characteristics
 [65]Neural Network
  • Sonar and camera
  • Requires learning in ROV mode
  • Moving in 3D but avoiding obstacles only in the horizontal plane
  • Can track the seafloor
 [115]Combination of the vector field, reactive algorithm and object mapping algorithm
  • Static and dynamic obstacles
  • Data from 3 sonars
  • 2D maneuvers
 [52]Optimal Rapidly exploring Random Tree (RRT*)
  • 2D workspace
  • Static obstacles
 [116]Reactive behaviours
  • Test performed only for static obstacles
  • Sonar
  • Vertical and horizontal plane reactive maneuvers
Table 6. List of algorithms validated in numerical research between 2016 and 2020.
Table 6. List of algorithms validated in numerical research between 2016 and 2020.
ResearchAlgorithmMain Characteristics
 [41]Artificial Potential Field
  • 2D static environment
  • Local minima problem solved by introducing a virtual obstacle in local minimum position
 [131]Dynamic Window
  • Horizontal plane collision avoidance
  • Simulation conducted using nonlinear model of AUV named HUGIN 1000
  • The algorithm is prone to trapping in the local minima
 [76]Fuzzy reactive architecture for different forward speed
  • Simulation specifically for Guanay II AUV
  • Various obstacles changing location and shape
 [67]Deep Learning
  • Simulation-based on real camera images
  • Finding a collision free space and determining the direction of AUV escape
 [132]Safety spheres
  • Relates to I-AUV
  • The obstacles are represented by Octrees obtained from the Octomap implementation
 [117]Improved APF
  • Static obstacles
  • APF modification consists in determining the distance of 80 m between the obstacle and the AUV beyond which the repulsive force disappears
 [118]Radial Basis Function (RBF) Neural Networks
  • Horizontal plane only
  • Path planning simulation conducted with dynamic obstacle
 [133]Fuzzy Logic
  • Higher degree security and safety
  • The Infrared Sensor module for obstacle distance information
 [134]Rapid random search tree algorithm
  • Static and dynamic obstacles Real-time path planning
 [73]Improved Interfered Fluid Dynamical System, Improved Genetic Algorithm for energy optimal path obtaining
  • Static and dynamic obstacles
  • 3D path planning with complex obstacles and the ocean flow
 [135]Machine Learning-based algorithm
  • Static obstacles
  • Real-time path planning
 [87]Image segmentation and Reinforcement Learning
  • Static and dynamic obstacles
  • Estimates path dynamically
 [119]Modified Potential Field
  • Static and dynamic obstacles
  • No need to know the exact position of the AUV, only the distance between the obstacle and the AUV
 [78]Three inputs Fuzzy Logic
  • Static and dynamic obstacles
  • Increased efficiency compared to 2 inputs Fuzzy Logic System
 [136]Improved histogram-based EDA (LFHH-Learning Fixed-Height Histogram)
  • Static and dynamic obstacles
  • 2D and 3D environments
 [70]Improved Genetic Algorithm
  • Static obstacles
  • Improved crossover and mutation probability
  • Modified fitness function
 [137]Reactive behaviours
  • Vertical plane only
  • The ability to maintain a constant or varying distance from an obstacle above or below the vehicle
 [88]Reinforcement learning
  • Static obstacles
  • 2D environment
 [138]APF based method
  • Improves the suboptimal solution of the traditional trajectory planning algorithm
  • Selection of cost function is optimised by potential field intensity
 [35]3D Multi direction A*
  • Static environment
  • More satisfying results compared to Dijkstra Algorithm
 [139]Evolutionary Neural Network
  • Static obstacles (AUVs operate in mountainous and underwater areas)
  • An algorithm designed for BAUV
Table 7. List of algorithms in real applications between 2016–2020.
Table 7. List of algorithms in real applications between 2016–2020.
ResearchAlgorithmMain Characteristics
 [79]Two-layer algorithm Fuzzy Logic for preplanning, potential field and edge detection to reactive maneuvers
  • Horizontal maneuvers, if no routing possible, then the vertical approach activated
  • Strongly focused on safety
 [140]RRT based algorithm
  • Experiment with artificially imposed obstacles
  • Around 5 s to calculate the path
 [141]Reactive behaviours
  • Cameras, line lasers (image processing techniques)
  • Change the altitude when obstacle detected
 [142]Reactive behaviours
  • Forward Looking Sonar
  • AUV moving in 3D, collision avoidance only in 2D
 [143]Reactive behaviours
  • Forward Looking Sonar, Forward Looking Camera-Laser
  • Vertical plane collision avoidance maneuvers
  • Improved the existing system with Forward Looking Sonar, backward movement and thermometer (high-temperature water detection—hydrothermal vent fields.
 [144]Optimal RRT* based algorithm
  • Static and dynamic obstacles
  • Online path planning in 3D unknown environment
 [54]Sequential convex optimisation
  • The experiment in the pool with static obstacles
  • Offline path planning realised in 3D
  • Online path planning—only horizontal plane maneuvers
Table 8. List of algorithms validated in numerical research from 2021.
Table 8. List of algorithms validated in numerical research from 2021.
ResearchAlgorithmMain Characteristics
 [152]Improved Deep Deterministic Policy Gradient (DDPG)
  • Static and dynamic obstacles
  • APF method to set continuous rewards
  • 2D environment
 [153]HA* (Hybrid A*)
  • Static and dynamic obstacles
  • 3D path planning
 [154]Deep Reinforcement Learning
  • Static and dynamic obstacles
  • 2D environment
 [155]Reinforcement Learning—RRT*
  • Static obstacles
  • Validated in an unknown virtual maze
 [156](SDEQPSO) algorithm Selective Differential Evolution Quantum-behaved Particle Swarm Optimisation
  • Static and dynamic obstacles
  • HIL test validated
  • MOOS-IvP framework
 [157]Dynamic Virtual AUV principle and Barrier Lyapunov function
  • Static and dynamic obstacles
  • Vertical plane avoidance maneuvers
Table 9. List of algorithms in real applications from 2021.
Table 9. List of algorithms in real applications from 2021.
ResearchAlgorithmMain Characteristics
 [158]Reactive behaviours
  • Static obstacles
  • MRF-net to obstacle detection
 [159]Reactive behaviours (APF based)
  • Static and dynamic obstacles
  • Kalman filters for the motion prediction of dynamic obstacles
  • Multibeam echosounder and FLS
 [160]Merged Ant Colony and PSO algorithms
  • Static and dynamic obstacles
  • 3D path planning
  • Spherical Underwater Robot
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Kot, R. Review of Collision Avoidance and Path Planning Algorithms Used in Autonomous Underwater Vehicles. Electronics 2022, 11, 2301. https://doi.org/10.3390/electronics11152301

AMA Style

Kot R. Review of Collision Avoidance and Path Planning Algorithms Used in Autonomous Underwater Vehicles. Electronics. 2022; 11(15):2301. https://doi.org/10.3390/electronics11152301

Chicago/Turabian Style

Kot, Rafał. 2022. "Review of Collision Avoidance and Path Planning Algorithms Used in Autonomous Underwater Vehicles" Electronics 11, no. 15: 2301. https://doi.org/10.3390/electronics11152301

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

Article Metrics

Back to TopTop