Next Article in Journal
Maritime Data Collection Framework for Container Port Benchmarking
Next Article in Special Issue
Underwater Acoustically Guided Docking Method Based on Multi-Stage Planning
Previous Article in Journal
A Unified Numerical Method for Broaching and Loss of Stability in Astern Seas
Previous Article in Special Issue
Optimal Path Planning Method for Unmanned Surface Vehicles Based on Improved Shark-Inspired Algorithm
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Review

A Review of Path Planning for Unmanned Surface Vehicles

1
College of Engineering Science and Technology, Shanghai Ocean University, Shanghai 201306, China
2
Shanghai Zhongchuan NERC-SDT Co., Ltd., Shanghai 201114, China
3
Department of Ship Engineering, Weihai Ocean Vocational College, Weihai 264315, China
4
Shanghai Marine Diesel Engine Research Institute, Shanghai 201108, China
5
College of Intelligent System Science and Engineering, Harbin Engineering University, Harbin 150001, China
*
Author to whom correspondence should be addressed.
These authors contributed equally to this work.
J. Mar. Sci. Eng. 2023, 11(8), 1556; https://doi.org/10.3390/jmse11081556
Submission received: 23 May 2023 / Revised: 13 July 2023 / Accepted: 3 August 2023 / Published: 6 August 2023
(This article belongs to the Special Issue Motion Control and Path Planning of Marine Vehicles)

Abstract

:
With the continued development of artificial intelligence technology, unmanned surface vehicles (USVs) have attracted the attention of countless domestic and international specialists and academics. In particular, path planning is a core technique for the autonomy and intelligence process of USVs. The current literature reviews on USV path planning focus on the latest global and local path optimization algorithms. Almost all algorithms are optimized by concerning metrics such as path length, smoothness, and convergence speed. However, they also simulate environmental conditions at sea and do not consider the effects of sea factors, such as wind, waves, and currents. Therefore, this paper reviews the current algorithms and latest research results of USV path planning in terms of global path planning, local path planning, hazard avoidance with an approximate response, and path planning under clustering. Then, by classifying USV path planning, the advantages and disadvantages of different research methods and the entry points for improving various algorithms are summarized. Among them, the papers which use kinematic and dynamical equations to consider the ship’s trajectory motion planning for actual sea environments are reviewed. Faced with multiple moving obstacles, the literature related to multi-objective task assignment methods for path planning of USV swarms is reviewed. Therefore, the main contribution of this work is that it broadens the horizon of USV path planning and proposes future directions and research priorities for USV path planning based on existing technologies and trends.

1. Introduction

With the rapid development of science and technology, the USV is an indispensable means to accomplish tasks at sea. In addition, it is the outstanding advantage of USV that it is intelligent [1]. Individual USVs can perform intelligence acquisition, surface search and rescue, and marine resource exploration, while cluster of USVs can perform cooperative sensing and formation, intelligent escorting, and other operational tasks [2,3]. USV path planning is one of the most significant aspects of its safe navigation in the working environment, which directly affects the safety and economy of USVs during navigation [4]. Path planning is also one of the prominent technologies for the automation and intelligence of USVs and for performing complex tasks [5]. The evaluation criteria for USV path planning are to seek a safe and feasible optimal path from a defined starting point to an endpoint in an obstacle-ridden working environment. The aim of the path planning algorithm is the optimal selection of routes to maximize efficiency. An optimal path is predicted by analyzing the path length, smoothness, safety, and other indicators to save time and energy consumption.
The research method for this paper is the literature research method. New findings are obtained through extensive reading of the latest current literature to gain a comprehensive and correct understanding of the problems associated with USV path planning. In the past five years, several review papers [2,3,4,6,7,8,9,10,11,12] have been published summarizing the advancement of research on path planning. The following is a list of the most relevant review papers:
Ref. [2] describes the progress of USV path planning research based on multi-modality constraints in three stages: route planning, trajectory planning, and motion planning. Ref. [3] provides a comprehensive review of the development of USV from target tracking, trajectory tracking, path tracking, and cooperative formation control. This study focuses on intelligent motion control with less description of path planning. Ref. [4] addresses the USV local path planning problem and describes the characteristics of various algorithms at two levels of path search and trajectory optimization. Ref. [6] reviews recent advances and new breakthroughs in AUV path planning and obstacle avoidance methods, and compares constraints and marine environmental impacts of AUV from global and local path planning algorithms. Ref. [7] explores a path planning algorithm for autonomous maritime vehicles and its collision regulation correlation. This study focuses on USVs and COLREGs from the perspective of the safety of navigation.
Next, we will present the purpose and contribution of our review paper and emphasize the necessity of this work in comparison to current review papers. We present an up-to-date review of USV path planning. Not only are traditional graph-based search and sampling methods covered, but recent developments in reinforcement learning, neural networks, and swarm-intelligence-based optimization algorithms are also included. The innovation of this paper is to point out the limitations of current path planning methods, namely, most of them ignore the effects of winds, waves, and currents at sea on the ship. However, this paper systematically and comprehensively introduces new developments in current research into path planning algorithms in the face of unknown complex maritime situations. Secondly, in the face of multiple moving obstacles, this paper introduces the relevant algorithms to accomplish multi-objective task assignment planning and cooperation using USV clusters to achieve autonomous obstacle avoidance of vehicles. The rest of the paper is structured as follows: Section 2 presents and compares conventional as well as evolutionary algorithms under global path planning; Section 3 presents algorithms related to local path planning; Section 4 presents types of and methods for hazard avoidance in proximity response; Section 5 presents path planning algorithms under clustering; Section 6 gives conclusions and analyzes valuable future research directions in this area.

2. Global Path Planning

Global path planning is a large-scale offline path planning method based on provided information about the marine environment (electronic charts) to obtain information about static obstacles in the area that USV passes through. The global path planning algorithm acquires information about the entire environment, modeling the environment based on the obtained information pairs and performing the preliminary planning for a given path [13]. Global path planning is a viable path from the starting point to the ending point of the USV in a known operating environment. Once in sophisticated maritime environments, or when obstacles suddenly appear in the route, it can easily lead to a local optimization situation. Currently, the main global path planning methods are traditional algorithms such as the Dijkstra algorithm and A start (*) heuristic search algorithm, and evolutionary algorithms such as the genetic algorithm and neural network algorithm, as shown in Figure 1.

2.1. Dijkstra Algorithm

The Dijkstra algorithm, a classical shortest-path search algorithm, was formulated by E.W. Dijkstra in 1959 [14]. By searching the graph and choosing any starting point among the schema, it is possible to calculate the closest path to all vertices. Due to the Dijkstra algorithm computing all vertices during the search process, it is less efficient to run. To address the problem of low operational efficiency, ref. [15] proposed an improved Dijkstra algorithm to add key nodes and divide regions, which can effectively reduce the computation time and improve the operational effectiveness of the algorithm. In [16], another improved Dijkstra algorithm was proposed, which needs to select the nearest node. As a result, the computation of non-critical nodes decreased, which saves time and speeds up the path-planning operation. Nevertheless, the method does not select an optimal route for the appearance of multiple paths with the same shortest distance. In [17], a running time calculation function was introduced to calculate the optimal route by running time when several paths of the same length occur. Once the data are heavy, the method consumes a lot of time. To address the inefficiency caused by a large amount of data, ref. [18] proposed a hierarchical Dijkstra improvement algorithm. It saves the location information that has been searched to be synchronized to avoid repeated searches for the same location. The algorithm can quickly find a more suitable path when there are large amounts of data. In a way, it saves time and improves efficiency, even if it is not the best path. For considering the effect of under static obstacles, ref. [19] raised a distance-seeking Dijkstra algorithm based on electronic nautical charts to solve the global path planning problem for USVs. By finding the node with the shortest path, the algorithm speeds up planning, optimizes the global route, and makes the planned path smoother. In [20], a three-dimensional Dijkstra optimization algorithm was proposed to generate globally optimal routes. Compared with the two-dimensional Dijkstra algorithm, this algorithm has a high global search capability, finds the globally optimal path more precisely, and saves time and fuel costs. Considering the effect of dynamic obstacles on global paths, ref. [21] presented a D*Lite algorithm. The prediction of dynamic path planning using dynamic information from the first computed path enables a bi-directional variable search in an unknown environment. If the map changes too much, it will calculate duplicate nodes and result in a slow planning efficiency. Moreover, the results are not convergent and the algorithm becomes stuck in a dead loop. In [22], a path planning algorithm was raised, based on the improved D*Lite algorithm was by enhancing the path cost function and reducing the expansion range of nodes. As a result, it avoids double-node computation and raises computational efficiency.

2.2. A* Algorithm

The A* algorithm, proposed by Cove in 1967 [23], was a heuristic search algorithm for discovering the shortest route between two nodes. The A* algorithm is simple in principle, and quicker than Dijkstra’s algorithm. Using an optimal search approach ensures that the path has the lowest cost and enhances the efficiency of the operation. However, it relies more on heuristic functions. Once the heuristic functions are complex or invalid, it produces poor smoothness and continuity of the paths, which are not detrimental to the navigation of the vessel [24]. At present, the main improvements of the A* algorithm in academia include: firstly, expanding the number of neighboring points to be searched to improve the smoothness; secondly, optimizing the heuristic function to reduce the computation time; and thirdly, reducing the computation of the raster to hence efficiency. In [25], a finite angle FFA* algorithm was proposed by introducing a safety distance parameter. This algorithm expands the search range and increases the number of adjacent points, thus improving the smoothness of the generated route and increasing the safety of ship navigation. However, adding branches leads to more computing time and less efficiency. In [26], a limited destructive A* (LDA*) was raised, based on the problem of the slow running of the FFA* algorithm. By optimizing the heuristic function, the shortest path from the starting point to the endpoint is found in the grid environment to save time. The method is fast for static obstacles and generates feasible routes, but the performance is not optimal. In [27], another constrained A* algorithm was proposed. In a simulated closed ocean environment, the effects of static and dynamic obstacles are considered to generate a safer route by maintaining a safe distance. It reduces the computation time and improves operational efficiency by optimizing the heuristic function, which adapts to the globally optimal path planning. In [28], an R-RA* algorithm was proposed. As only a fraction of the grid map, it is possible to significantly reduce the length of the route, saving computational time and improving the operational efficiency of the algorithm. However, the generated paths are not globally optimal. In [29], a rectangular grid instead of a hexagonal grid was presented. With the reduction in intermediate nodes, it makes the path smoother. The optimization is also performed in the path length to ensure the robustness and safety of the ship.

2.3. Genetic Algorithm (GA)

The genetic algorithm (GA) was proposed by John Holland, and adheres to the principles of genetics and natural selection [30]. The main benefit of GA is that it is available for complex problems and is a general approach to solving search methods. However, classical GA suffered from low convergence and function-dependent optimization [31]. The slow processing speed makes it unsuitable for real-time route planning in dynamic and unknown situations. GA improvements have focused on improving the crossover and variation operators, choosing better coding methods, and adjusting genetic parameters. In [32], a new crossover operator to solve the complicated case of the USV path planning problem was utilized. With the aim of minimizing the overall flight cost, the algorithm randomly selects the child paths from the parent and generates paths to find the globally optimal solution and improve the convergence speed. In [33], an artificial adaptation function and two custom genetic operators were proposed, dealing with the path planning problem of USVs in the static case. It is shown that the method enables fast optimal solutions in a static environment but is hard to obtain in dynamic obstacle avoidance. In [34], a hybrid repetition-free string selection operator and heuristic multiple variables operators was proposed to find optimal paths and extend the population search. It obtains smooth flight paths and reduces the computational time of the algorithm. In [35], an adaptive genetic algorithm (AGA) was proposed that focuses on solving complex optimization problems. The hierarchical approach to selecting operators reduces time and speeds up convergence. The algorithm can shorten the length of the global path, improve quality, and find globally optimal routes in static environments. In [36], an improved particle swarm genetic algorithm (IPSO-GA) was proposed for UAV path planning, which optimizes continuously by swarm mating variation operations. The algorithm saves time and improves efficiency compared to greedy algorithms. It is more suitable for computationally intensive and complex situations to achieve collision avoidance of dynamic obstacles, but the quality of generating globally optimal paths in complex environments. In [37], a multi-objective enhanced genetic algorithm (EGA) was developed. Using crossing and variational operators, it takes full account of path smoothness and path length in ensuring that the generated paths are safe and feasible, and improves running time and efficiency. However, the method needs further improvement for dynamic obstacle avoidance. In [38], an improved multi-objective genetic algorithm (IMOGA) was proposed. Decreasing the path length is achieved by removing the redundant nodes of the running path. The optimized path quality is achieved by improving the mobility of the mobile robot, reducing the number of turning movements, and improving smoothness. However, the method does not consider the dynamic obstacle avoidance problem in the underwater environment.

2.4. Neural Network (NN)

The Neural Network (NN), introduced by McCulloch Pitts in 1944 [39], also becomes the Artificial Neural Network (ANN). It also describes the NN method to navigate in an unknown environment [40]. In [41], an NN based the COLREG rule and the risk of avoiding collisions with static obstacles was considered, to ensure the safety of MASS. However, the generated global path is not optimal by the limited environmental information. In [42], a CNN to extract information and collect visual data through two-dimensional images was proposed. Furthermore, considering COLREG, the algorithm changes the motion vector to avoid collisions. However, the data do not update in real-time and the path planning for dynamic obstacles is not accurate enough. In [43], a residual convolutional neural network (R-CNN) algorithm was investigated. It improves the capability of real-time path planning path quality by collecting previous global information, training by reinforcement, and avoiding dynamic obstacles in a real-time environment. At the same time, it can generate optimal paths on global paths. In [44], a GNN model to use features extracted from graphs by NN was proposed. With consideration of the structure and node characteristics of the graph, it improves the smoothness and speeds up the computation. However, using the GNN model directly on large-scale graphs can be computationally challenging [45]. In [46], a graph convolution network (GCN) was proposed. It is a semi-supervised learning method based on graphical data. Using a model of GCN, nodes with previously unknown data are created to capture global information to predict traffic states [47] and to achieve global path planning. The method has few weight parameters and fast convergence. However, it has a poor performance when it is applied to maritime USVs and works for planning globally optimal paths on the ground. In [48], a bio-inspired neural network (BINN) algorithm was proposed and applied to full-coverage path planning for robots on land. It is able to find the shortest path by a full-coverage approach while avoiding static obstacles. Applied to USV, it generates paths with too large turning angles and not smooth enough paths. To adapt full-coverage path planning for USV over the sea, ref. [49] proposed a full-coverage neural network (CCNN) algorithm for USV path planning. It can greatly reduce the computation time and improve coverage efficiency. The turning angle is further reduced to make the path smoother and to avoid all dynamic obstacles to obtain the globally optimal path.

2.5. Summary of Global Path Planning Algorithms

The above research uses tools such as shortening the path length and smoothing the generated paths when designing path planning algorithms to make the planned paths more compatible with navigation practice. The use of hierarchical processing of data in constraints to avoid repeated searches and the introduction of genetic crossover operators make the paths more convergent and efficient while reducing the solution time of the algorithm to meet practical needs. The safety distance parameter is entered, following COLREGs, to improve the safety and robustness of the ship. The global path algorithm is dependent on perceived environmental information and cannot optimally deal with unknown and dynamic obstacles. As shown in Table 1, it compares different algorithms for global path planning and considers various factors for optimal paths.

3. Local Path Planning

In contrast to the global path planning algorithm, local path planning is the optimal path from the current node to a targeted node. It uses sensors to obtain data from the surrounding location environment, senses the obstacle distribution in the region, and performs local path planning in a real-time path search. Due to the lack of global environment information, it is easy for the pathway to fall into local optimum. Typical local path planning algorithms include artificial potential field (APF), fast extended random tree (RRT), velocity obstacle (VO), and dynamic window method (DWA). As shown in Figure 2, the typical local algorithms are analyzed for their advantages and disadvantages and the corresponding optimization algorithms.

3.1. Artificial Potential Field (APF)

The artificial potential field (APF) method is a well-known USV local path planning algorithm proposed by Khatib [50]. Although the APF method has the advantages of a single structure, fast speed, and good real-time performance, it suffers from problems such as local optimum and poor path smoothing. In [51], the APF method is applied to the local path planning of USVs to solve the problem of avoiding static obstacles during navigation and ensuring the safety of the ship’s trajectory. However, when the target points near obstacles are difficult to detect, there is poor performance of the generated global paths. To solve the problem of dead loops, ref. [52] proposed an improved APF approach using map expansion to reprogram local routes. When an infinite loop occurs, the map is transformed and starts searching for travelable paths, but does not take into account the problem of unreachability due to obstacles being too close to the target point. In [35], a vector artificial potential field method (VAPF) was proposed that improves the use of the space vector method to calculate the total force of AUVs. It allows USVs to reach static targets and track dynamic targets. The improved algorithm improves computational efficiency and reduces the cumbersome time in AUV dynamic avoidance. It can avoid dynamic obstacles effectively in real-time and reduces the cost of AUVs. However, when the target points near obstacles are difficult to detect, there is poor performance of the generated global paths. In [53], the discrete artificial potential field (DAPF) method was proposed. The results show that the algorithm not only efficiently and quickly computes safe routes in static and dynamic obstacle environments but also solves local optimization methods. Using the path optimization algorithm can reduce the path length and improve the smoothness. In [54], the Ant Colony Potential Field Algorithm (APF-ACO) global obstacle avoidance scheme was used, where the real-time information from a LiDAR sensor can avoid local obstacles, and a method to create a potential field without local extrema was proposed. The length of the path is optimized to reduce steering during driving and to ensure the robustness and safety of the ship itself. In [55], a model prediction strategy and an artificial potential field (MPAPF) was proposed. It overcomes the drawbacks of the traditional APF and other algorithms and solves the difficulty of becoming stuck in the local optimum. At the same time, it considers the head-on and cross-encounter situations of ships, effectively avoiding dynamic obstacles in real-time and ensuring the safety of USVs under complex conditions.

3.2. Rapidly Expanding Random Tree (RRT)

The rapidly expanding Random Tree (RRT), formulated by Lavalle [56], is a sampling-based path planning algorithm. As the creation of new nodes is random, node creation will stop once the node determines the target location. However, the RRT algorithm provides a preferred path that generates many nodes, which consumes time and generates a not sufficiently smooth path. In [57], the algorithm reduces the randomness of the final path by deselecting the parent node.The shortest path is found by increasing the number of iterations, but it can fall into local optimality. In [58], RRT* trajectory optimization is used to create smoother paths and reduce path lengths. However, convergence to the optimal path solution is slow and consumes considerable memory and time. In [59], a Q-Learning-based RRT* (Q-RRT*) method was proposed that reduces the path length and accelerates convergence to the optimal solution by extending the search. However, it yields paths that are not globally optimal and obstacle avoidance for dynamic obstacles requires further consideration. In [60], the RRT-Connect algorithm was proposed, which is a simple and efficient stochastic algorithm. The greedy heuristic algorithm needs to speed up the search capability and the convergence process by searching from the starting and target points but is prone to local optima. To address the case of falling into a local optimum, ref. [61] proposed a path extension-based heuristic sampling RRT* algorithm (EP-RRT*). Based on RRT-Connect, the sampling-based asymptotically optimal path planning algorithm is proposed, which can quickly explore the global environment and find feasible paths. In [62], a novel probabilistic smoothed bi-directional RRT (PSBi-RRT) algorithm was presented. A greedy algorithm and biasing strategy require searching for nearby points. As a result, it avoids collisions in the environment, significantly reduces running time, and decreases the likelihood of local optimization. In [63], a method combining APF and RRT* (P-RRT*) was presented. By introducing randomized gradient descent (RGD), the algorithm sufficiently reduces the number of iterations and the time and converges to the optimal path solution more quickly. The algorithm solves the local minima problem, but the real-time performance needs to be enhanced. In [64], an improved heuristic Bi-RRT algorithm based on the Bi-RRT algorithm was presented. Not only can dynamic obstacles in the real-time environment be avoided, but further improvements are also achieved in the efficiency of algorithm operation and path length, and smoothness.

3.3. Velocity Obstacle (VO)

To address the dynamic obstacle avoidance of USVs, Fiorini and Shiller [65] proposed the velocity obstacle (VO) approach in 1998 and incorporated the velocity characteristics of obstacles into the scope. However, the algorithm failed to consider the dynamic changes in the velocity of the obstacle and the dynamic performance of the USV. In [66,67], a VO-based dynamic avoidance algorithm was designed for USV to avoid moving obstacles. Since COLREGs are not considered, the experiments verify that USV is ineffective for moving and unknown obstacle avoidance, and the safety of the generated paths needs further enhancement. In [68], an enhanced velocity obstacle-based method with a particular triangular obstacle geometry model for autonomous dynamic obstacle avoidance of USVs was proposed. COLREGs should be considered to optimize the heading angle and improve the portability of the ship. It also reduces the USV path length and fuel cost by ensuring accurate obstacle avoidance. In [69], a hybrid VO-APF algorithm for obstacle avoidance of dynamic obstacles was raised, which enhances the real-time performance of obstacle avoidance and integrates COLREGS rules and path optimization functions. However, the algorithm can easily fall into a local optimum and cannot generate a globally optimal path. To tackle the situation of falling into a local optimum, in [70], a path planning method, based on the COLREGs, was displayed, combining the VO algorithm with the ACO algorithm to realize dynamic obstacle transitions relative to the stationary state of the USV at a given instant. The method can effectively avoid dynamic obstacles and obtain a reasonable risk avoidance strategy that provides the globally optimal path. However, owing to the uncertainty of the obstacle motion state, the predicted obstacle information i nevitably appears inaccurate. Based on the Generalized Velocity Obstacle (GVO) algorithm [71,72] proposed a collision avoidance system (GVO-CAS). The method, based on COLREG, visualizes the collision course and velocity for collision avoidance of multiple dynamic obstacles at close range. The algorithm takes into account the ship dynamics to improve collision avoidance performance and provides the globally optimal path. In [73], a novel efficient path planning algorithm was presented, the Constraint Locked Sweep Method and Velocity Obstacles (CLSM-VO). The algorithm optimizes global search performance, increases computational efficiency, and enhances generated path smoothness. It is suitable for complex environments with multiple dynamic obstacles and enables fast and effective dynamic obstacle avoidance by providing USV initial yaw angle and constraint layer optimization.

3.4. Dynamic Window Approach (DWA)

The Dynamic Window Approach (DWA) is a commonly used path planning method, originally proposed by FOX et al. [74,75] in 1997. The algorithm samples multiple velocity values in velocity space and simulates the trajectory generated by the robot at each velocity. To avoid the influence of dynamic obstacles, in [76], a “dynamic collision model” was introduced for the conventional DWA to predict possible future collisions, taking into account obstacle movements. The DWA algorithm for real-time path planning reduces wasted space and time by simulating the obstacle shape based on the obstacle. In [77], a local virtual target dynamic window (DW-VG) obstacle avoidance method was proposed. Introducing virtual target points selects the optimal amount of motion control. As a result, the algorithm can avoid all dynamic obstacles and predict an optimal path. In [78], the DWA-VO algorithm was proposed. The algorithm can speed up the search and improve the efficiency of the operation. It only considers local moving and unknown obstacles, which solves the information error caused by dynamic obstacles encountered by USV. It fails to identify accurately the global obstacles and leads to a local optimum. To address the condition of being trapped in a local minimum, ref. [79] proposed a path planning system with DWA and A* algorithms, where USV can avoid unknown obstacles by selecting the optimal speed. USV can adapt to global and local maritime obstacles by choosing the best velocity to avoid unknown obstacles and avoid local optimum problems. In [80], an improved dynamic window approach (IDWA) was proposed to improve the efficiency of USV navigation. Combined with the idea of non-uniform theta*, the reverse search is performed from the target node to reduce the path length and improve the navigation efficiency and the real-time performance of the USV. The algorithm prevents the USV from falling into local minima and enhances the ability of the USV to avoid dynamic obstacles at close distances. In [81], the ant colony optimization (ACO) and dynamic window approach (DWA) were combined to solve local path planning. The global path length is optimized by enhancing the search capability and removing redundant points through a dual population heuristic function. Adaptive navigation strategies are used to achieve obstacle avoidance for unknown dynamic obstacles and to solve the local optimum problem.

3.5. Summary of Local Path Planning Algorithms

The above research focuses on solving local optimization problems. Using the sensor’s ability to sense the maritime environment, it can efficiently and quickly avoid dynamic obstacles, making the generated paths smoother, and can calculate safe routes. By using space vectors, employing extended search, and introducing greedy algorithms, the length of the path is reduced while reducing the solution time of the algorithm to meet practical needs. Using a dynamic collision model and considering the speed variation of dynamic obstacles, it can avoid all obstacles in real time. However, local paths ignore the effects of wind and wave currents in real sea conditions. There is no good solution to the problem in the face of complex situations. Table 2 compares different algorithms for local path planning and considers the factors of the optimal path.

4. Proximity Responsive Hazard Avoidance

Proximity-responsive hazard avoidance is where a USV, following a set course, needs to adjust its response in time to effectively avoid a collision with an obstacle if the uncertainty of a dynamic obstacle is detected suddenly. In contrast, close-range collision avoidance requires consideration of the vessel’s shape and turning angle. Hazard avoidance and multi-vessel collision avoidance in complex marine conditions are also hot topics of current research.

4.1. Hazard Avoidance in a Complex Environment

For USV path planning in complex environments, an increasing number of hybrid algorithms are used to deal with the above problem. In [82], a multi-layer path planner (MPP) was proposed, which combines the fast marching method (FMM) [83] and the SDCE model to simulate a static environment. Collision Avoidance (CA) decisions are used to introduce safety parameters to achieve obstacle avoidance for dynamic and unknown obstacles and reefs in the coastal environment. The method does not consider the effects of wind, waves, and currents. In [84], a combined GA and APF approach was presented. It can perform path planning for various complex dynamic obstacle situations and find the best path among the obstacles on three sides around the starting point. However, the method only plans for simple geometries and coastlines, which does not work well in actual maritime environments. To consider realistic factors at sea, ref. [85] improved the multi-objective route planning method of PSO-GA and proposed a risk assessment model for wind and waves. Meanwhile, the length of the path, smoothness, and speed of the ship are taken into account. The genetic algorithm is used for cross-calculation, which improves operational efficiency. However, it does not consider the effect of ocean currents. If you want to consider the impact of ocean currents on path planning, building a kinematic USV model is a key choice, as shown in Figure 3.
In [86], an improved imperial competition algorithm (ICA) was proposed. Based on a three-dimensional current model and the influence of static obstacles at sea, the locally optimal solution is solved effectively and the AUV can obtain the global optimal path. However, the method cannot be adapted to dynamic obstacles. In [87], the steering angle of the ship is incorporated into the cost by building a cost model of the effect of ocean currents on the energy consumption of the AUV. The algorithm uses an improved D* algorithm and considers the kinematic and dynamical equations to plan the path with the minimum energy consumption, but the path is not optimal. In [88], a VF-RRT* algorithm was proposed, which improves its effectiveness in the current environment by introducing a virtual field sampling function and an ocean current constraint function. As a result, it greatly reduces the navigation time and energy consumption of the USV. In [89], an improved sparrow search algorithm (SSA) was designed, which considers the effects of time-varying characteristics of ocean currents, wind and wave factors, and dynamic obstacles on the navigation of AUVs in complex ocean environments. Convergence speed and search capability are improved by building a 3D underwater model and optimizing the coefficient weights. The algorithm can avoid all the obstacles underwater and find the globally optimal path in the complex ocean environment.
Using machine learning algorithms is another way to deal with path planning in complex environments. In [90,91], a deep Q network (DQN) is developed for ship path tracking and heading control in calm seas without considering the actual sea environment. In [92], an improved DQN algorithm for vehicle path tracking using a nonlinear dynamic model was shown. It also ensures the safety and robustness of ship navigation in a windy and rough marine environment. Due to the complex environment of wind, waves, and currents, USV need to constantly change their speed and direction, considering the dynamics and kinematics of USV. In [93], a combination of Q-learning and neural networks (Q-NN) was proposed for path planning in unknown and harsh environments. It is able to avoid obstacles in real time and considers the kinematics of USVs, but it does not consider the effect of ocean currents. In [94], harsh environments such as wind, waves, and currents on USV path planning were considered. The optimization using the least squares strategy considers the dynamics and kinematics of the USV. However, the method is mainly applicable to static obstacle avoidance and textcolorred needs further breakthroughs for dynamic and unknown obstacles. In [95], an improved deep reinforcement learning algorithm (DRL) was presented. A two-dimensional ocean current model and a planar kinematic model are developed with energy cost as an important constraint. The global optimal path is solved by utilizing an improved reward function, action set, and state set and using B spline smoothing optimization.

4.2. Multi-Vessel Collision Hazard Avoidance

The multi-vessel collision problem is a common traffic accident at sea [96,97]. Currently, AIS ship trajectory data analysis is mainly used to require compliance with COLREG to prevent ship collisions as much as possible. The distance to the point of closest approach (DCPA) and the time to the point of closest approach (TCPA) are important indicators of a ship’s collision risk [98]. Figure 4 shows the positional relationship between the ship and the target ship. The DCPA Collision Hazard Model is used to determine the distance from the vessel to the hazardous vessel for collision hazard assessment. In [99] DCPA and TCPA were combined to calculate hazard classes and analyses collision hazard classes in the context of ship safety domains, ship domains, and dynamic boundaries. A full-coverage algorithm is used to enable collision avoidance for multiple vessels. In [100], a full-coverage path planning algorithm based on deep reinforcement Q-learning neural network (DQN) was proposed, which uses convolutional layers to perceive the raster map and construct and train deep reinforcement learning. However, the traditional DQN suffers from low learning efficiency and low coverage. In [101,102], a method to improve its action selection mechanism was proposed. Training data is selected based on the priority of the task. A dynamic reward mechanism ensures that valuable data is trained and reduces the risk of dangerous USV action selection during the learning process. The method improves the convergence and efficiency of full-area coverage, and can effectively avoid other vessels. As shown in Figure 5, the improved DQN algorithm can achieve full coverage, which is able to avoid all obstacles and has fewer repeated paths. It is also feasible to apply this algorithm to collision avoidance of multiple vessels. In [103], a sliding window algorithm (SWA) was raised for accurately detecting ship collision avoidance behavior from AIS trajectory data, but the real-time performance is not strong enough. In [104], AIS and spatial-temporal was used to analyze the massive data of vessel traffic conditions in past waters, and used simulated vessel traffic demand and temporal characteristics to predict vessel trajectories. The method achieves global ship collision avoidance and cannot monitor the risk of ship collision in real-time. For the issue of weak real-time monitoring of the risk of ship collision, in [105], using AIS data and ACO-APF algorithm, real-time dynamic avoidance is performed to plan a safe route. It achieves real-time dynamic collision avoidance for multiple vessels and effectively reduces the risk of collision vessels. In [106], a practical rule-aware time-varying conflict risk (R-TCR) for multi-ship collision avoidance was raised, considering vessel maneuverability and COLREGs. In [107], a synergy ship domain (SSD) was proposed to construct a collision risk model in a two-ship situation, which can identify the risk of ship collision in real time. By simulating frontal collision, side collision, and cross-collision, it identifies the dynamic changes in collision risk. For the local optimal problem in multi-objective complex situations, ref. [108] investigated collision avoidance considering COLREGs for solving multi-ship encounter problems. To obtain an optimal decision to avoid ship collisions, multiple objective decision-making (MODM) was combined with CGA. The algorithm keeps the ship moving safely as it avoids dynamic obstacles. In the case of multiple objectives, it takes a global view rather than just considering optimizing one target. In [109], a RACO combination of the ant colony algorithm (ACO) with the rolling window method (RWM) [110] was proposed. To address the complexity of collisions, the algorithm considers three possible approaches: frontal collision, side collision, and random collision. By introducing secondary safety distances and complying with COLREGs, it achieves real-time collision avoidance safely and effectively and finds the globally optimal path.

4.3. Summary of Hazard Avoidance Algorithm

The above study considers the problem of reactive avoidance of proximity in the design of path-planning algorithms. In the face of complex environments, a hybrid algorithm using hierarchical processing and a grid-based model prevents repeated searches and makes paths more efficient. In realistic marine environments, the effects of wind, waves, currents, and other factors are also considered to ensure safety and to produce globally optimal paths. Based on AIS data, COLREGs and machine learning algorithms combine historical data with real-time data for route planning to ensure safe navigation and avoid multi-vessel head-on collisions, cross-collisions, and random collisions. Table 3 compares different algorithms for hazard avoidance and considers the factors of the optimal path.

5. Cluster Path Planning

USVs cluster path planning technology is rapidly developing as a core key technology. USVs cluster path planning is the key to cluster path generation, obstacle avoidance, collision avoidance, and other navigation and coordination tasks assignment. It is essentially a multi-constrained combinatorial optimization algorithm. The cluster intelligence optimization algorithm focusing on the bionic approach and the multi-task assignment strategy are essential assets to solve the cluster path planning problem [111].

5.1. Bionic Algorithm

For large-scale, high-dimensional, and non-linear USV cluster path planning problems, it is a good choice to use a bionic optimization algorithm. In [112], a firefly-based Approach (FA) for robot cluster path planning is proposed, where Firefly social behavior optimizes group behavior. Since the path planning problem is an NP complexity problem, multi-objective evolutionary algorithms are an effective way to solve this problem. In [113], a cluster path-planning algorithm based on ant colony optimization (ACO) [114] in a dynamic environment is proposed to perform path-planning optimization and establish the path-planning optimization objective function in a multi-tasking scenario. In [115], based artificial bee colony (ABC) algorithm [116], an efficient artificial bee colony (EABC) algorithm is proposed. It solves online path planning collision avoidance for multiple mobile robots by selecting appropriate objective functions for the target, obstacles, and robots. It utilizes elite individuals to maintain good evolution, improve performance and shorten path length. The method improves the quality of path planning for clusters, but it tends to fall into local optimality. For USV clusters caught in a local optimum, ref. [117] proposed an improved particle swarm optimization(PSO) algorithm based on an adaptive sensitivity decision operator that is more adapted to 3D path. It solves the drawback that traditional PSO is prone to fall into local optimality [118], improves the convergence accuracy and cooperative operation of clusters, and predicts the globally optimal planning. In [119], it proposed a decision support algorithm to use an artificial fish swarming algorithm (AFSA) [120] based on AIS data for path-planning decisions in USV clusters. It can calculate the optimal avoidance turn to time and avoidance angle, and the algorithm possesses excellent robustness and converges quickly. In [121], a hybrid improved artificial fish swarm algorithm (HIAFSA) was proposed to address the problem of falling into local optima. It combines the A* algorithm with AFSA for further optimization in global suboptimal paths. It introduces decay functions to enhance the visual range and motion steps to improve the convergence speed. The algorithm offers access to local optimum avoidance, convergence speed, and accuracy. In [122], the salp swarm algorithm (SSA) [123] optimization algorithm was used to divide the task area using Voronoi diagrams to achieve collaborative path planning for USV clusters. This optimization algorithm avoids repeated searches, improves search efficiency and accuracy, and effectively avoids collisions between obstacles and USVs. However, the method does not consider the influence of COLREGs and the actual environment at sea. To consider USV clusters in realistic environmental scenarios at sea, ref. [124] proposed a simulated annealing-bacterial foraging optimization algorithm (SA-BFO). The bacterial foraging optimization algorithm (BFO) is a population intelligence optimization algorithm with good search efficiency and robustness [125]. The hybrid approach, based on COLREGs, can perform real-time avoidance of dynamic obstacles using USV cooperative control. It is able to plan collision-free paths efficiently, moving away from local optima and converging to global optima.

5.2. Multi-Objective Task Assignment Algorithm

When faced with multiple target missions, it is difficult for a single USV to perform complex tasks in unknown underwater environments. Then, USV clustering can improve the performance of the system, shorten the mission time and increase the probability of the search success. Multi-objective search task assignment is the key to USV clustering path collaboration [126,127]. As shown in Figure 6, multiple search tasks are assigned to multiple specific USVs. Currently, reinforcement learning algorithms (RL) are more suitable for task assignment, and path planning [128,129]. In [130], combining HER with DQN and introducing a reward mechanism can increase the validity of the sample and the speed of convergence. In [131], a pheromone mechanism using ACO on the classical Q-learning approach is investigated. It solves the information-sharing problem in reinforcement learning systems and improves the efficiency of robot cluster path planning. In [132], a hexagonal area search (HAS-DQN) was proposed. It solves the collaborative path planning problem for UAVs, maximizes the data collected by UAVs, minimizes the total energy consumption, and extends the lifetime. However, due to the effects of offshore winds, waves, currents, etc., the above multi-task and multi-objective optimization decisions based on reinforcement learning do not work well when applied to USVs. In [133], an improved self-organizing map (SOM) [134] with collision avoidance capability was proposed, based on a fast marching square (FMS) [135] path planning algorithm. It is adapted to multi-task assigned USVs cluster for complex tasks, such as maritime patrol search and rescue and environmental detection. The algorithm first assigns tasks to each USV and enables the function of fast task assignment and optimized execution sequences. Not only does it achieve avoidance of all static and dynamic obstacles, but it also takes into account COLREGs. However, the algorithm does not consider the complex terrain and time-varying currents under the sea. In [136], an improved the K-means algorithm to accommodate unsupervised learning of competing strategies was proposed. The algorithm first assigns different tasks to multiple USVs and performs the task assignment by the SOM algorithm. It can autonomously undertake complex maritime missions in a limited environment and verifies its effectiveness by simulating it in a real marine environment. In [137], an improved SOM combined with spectral clustering (SC), is used to solve collaborative path planning for USVs cluster and multi-task allocation. The method allows for the selection of the globally optimal path with minimal energy consumption in a collision-free manner. To make the generated routes smoother, a dual smoothing strategy with B-samples and indirect adaptive disturbance observer-based line-of-sight (IADO-LOS) [138] are used to achieve the precise path following of the USV. The method also accounts for the effect of ocean currents on ship driving and is more in line with the realistic environment at sea.

5.3. Summary of Cluster Path Planning Algorithm

The above study uses the bionic optimization concept for path planning algorithms in USV clusters to optimize multi-objective paths for multi-task, multi-constraint models. Using AIS big data, COLREG and machine learning algorithms are used to combine historical and real-time data for path planning to ensure safe navigation while completing multi-tasking assignment strategies at sea. Table 4 compares different algorithms for the USV cluster and considers the factors of the optimal path.

6. Conclusions

Path planning is a hot and complex area of research in the USV field and a key technology to ensure its autonomy in the marine environment. This paper mainly reviews and analyzes the literature related to USV path planning in recent years. Path planning is divided into four aspects: global path planning, local path planning, hazard avoidance with approximate responses, and path planning under clustering. The advantages and disadvantages of different algorithms for global and local path planning are analyzed in Section 2 and Section 3. As shown in Table 5, global path planning can cover the whole map and find the global optimal solution. However, the computational complexity is high, the operation efficiency is slow, and it cannot cope with dynamic environmental changes. The local path planning algorithm is simple, responsive, and can adapt to the dynamic environment. However, it cannot handle the dead ends and obstacles in global path planning, and it is easy to fall into local optimal solutions. In addition, most of the improved algorithms for global and local path planning ignore the influence of real environments, such as ocean currents and wind waves. Modeling USV kinematics and dynamic constraints is important for path planning when considering the effects of wind, waves, and currents on safe avoidance and energy consumption. Using USV clusters with multi-task assignment and path collaboration strategies is also the right choice when facing multiple tasks.

7. Prospects

Firstly, the future direction of current path planning optimization algorithms is multi-algorithm fusion, based on traditional optimization algorithms combined with deep reinforcement learning, digital twins, and other artificial intelligence optimization algorithms, which holds the promise of dynamic and online path planning.
Secondly, the evaluation system of the path and the collision risk assessment models need to be further improved. Under the premise of ensuring safety, it considers factors such as path length, smoothness, time consumption, and efficiency, and also further considers the motion performance of angular velocity, acceleration, and turning angle of the ship.
Finally, USV cluster collaboration for path planning is also a hot research topic for the future. How to make USV clusters perform multiple tasks while performing integrated obstacle avoidance is also a problem that needs to be tackled in the future. Improving the perception of the navigation area and the autonomous decision-making capability is a significant part of the solution to this problem.

Author Contributions

Conceptualization, B.X.; methodology, B.X., M.Y. and B.L.; writing—original draft preparation, M.Y., B.X. and Z.L.; writing—review and editing, B.X., M.Y. and B.L.; supervision, B.X., Y.S., Z.L. and Y.T.; project administration, B.X., Y.T. and Y.S.; funding acquisition, B.X. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by Shanghai Science and Technology Committee (STCSM) Local Universities Capacity-building Project (No. 22010502200).

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

The data are available on request.

Acknowledgments

The authors would like to express their gratitude for the support of Fishery Engineering and Equipment Innovation Team of Shanghai High-level Local University.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Yu, W.; Low, K.H.; Chen, L. Cooperative path planning for heterogeneous unmanned vehicles in a search-and-track mission aiming at an underwater target. IEEE Trans. Veh. Technol. 2020, 69, 6782–6787. [Google Scholar]
  2. Zhou, C.H.; Gu, S.D.; Wen, Y.Q.; Du, Z.; Xiao, C.S.; Huang, L.; Zhu, M. The review unmanned surface vehicle path planning: Based on multi-modality constraint. Ocean Eng. 2020, 200, 107043. [Google Scholar] [CrossRef]
  3. Meng, J.E.; Ma, C.; Liu, T.H.; Gong, H.B. Intelligent motion control of unmanned surface vehicles: A critical review. Ocean Eng. 2023, 280, 114562. [Google Scholar]
  4. Liu, X.; Ye, X.M.; Wang, Q.B.; Li, W.G.; Gao, H.L. Review on the research of local path planning algorithms for unmanned surface vehicles. Chin. J. Ship Res. 2021, 16 (Suppl. 1), 12–14. [Google Scholar]
  5. Wu, G.X.; Xu, T.T.; Sun, Y.S.; Zhang, J.W. Review of multiple unmanned surface vessels collaborative search and hunting based on swarm intelligence. Int. J. Adv. Robot. Syst. 2022, 19, 17298806221091885. [Google Scholar] [CrossRef]
  6. Cheng, C.X.; Sha, Q.X.; He, B.; Li, G.L. Path planning and obstacle avoidance for AUV: A review. Ocean Eng. 2021, 235, 109355. [Google Scholar] [CrossRef]
  7. Ülkü, Ö.; Melih, A.; Tarık, A. A review of path planning algorithms in maritime autonomous surface ships: Navigation safety perspective. Ocean Eng. 2022, 252, 111010. [Google Scholar]
  8. Liu, L.X.; Wang, X.; Yang, X.; Liu, H.J.; Li, J.P.; Wang, P.F. Path planning techniques for mobile robots: Review and prospect. Expert Syst. Appl. 2023, 227, 120254. [Google Scholar] [CrossRef]
  9. Liu, J.; Wang, J. Overview of obstacle avoidance path planning algorithm for unmanned surface vehicle. J. Comput. Appl. Softw. 2020, 37, 1–10+20. (In Chinese) [Google Scholar] [CrossRef]
  10. Abdulsaheb, J.A.; Kadhim, D.J. Classical and Heuristic Approaches for Mobile Robot Path Planning: A Survey. Robotics 2023, 12, 93. [Google Scholar] [CrossRef]
  11. Lin, S.; Liu, A.; Wang, J.; Kong, X. A Review of Path-Planning Approaches for Multiple Mobile Robots. Machines 2022, 10, 773. [Google Scholar] [CrossRef]
  12. Gul, F.; Mir, I.; Abualigah, L.; Sumari, P.; Forestiero, A. A Consolidated Review of Path Planning and Optimization Techniques: Technical Perspectives and Future Directions. Electronics 2021, 10, 2250. [Google Scholar] [CrossRef]
  13. Gan, L.; Yan, Z.; Zhang, L.; Liu, K.Z.; Zheng, Y.Z.; Zhou, C.H.; Shu, Y.Q. Ship path planning based on safety potential field in inland rivers. J. Ocean Eng. 2022, 260, 111928. [Google Scholar] [CrossRef]
  14. Dijkstra, E.W. A Note on Two Problems in Connection with Graphs. J. Numer. Math. 1959, 1, 269–271. [Google Scholar] [CrossRef] [Green Version]
  15. Borkar, P.; Sarode, M.V.; Malik, L.G. Acoustic signal based optimal route selection problem: Performance comparison of multi-attribute decision making methods. J. Trans. Internet Inf. Syst. 2016, 10, 647–669. [Google Scholar]
  16. Sekaran, J.F.; Kaluvan, H. Path Planning of Robot Using Modified Dijkstra Algorithm. In Proceedings of the 2018 National Power Engineering Conference (NPEC), Madurai, India, 9–10 March 2018. [Google Scholar]
  17. Guo, Q.; Zhang, Z.; Xu, Y. Path-Planning of Automated Guided Vehicle Based on Improved Dijkstra Algorithm. In Proceedings of the 2017 29th Chinese Control And Decision Conference (CCDC), Chongqing, China, 28–30 May 2017. [Google Scholar]
  18. Kang, W.H.; Xu, Y.C. Hierarchical Dijkstra algorithm for node-constrained shortest paths. J. South China Univ. Technol. 2017, 45, 66–73. [Google Scholar]
  19. Zhuang, J.Y.; Wan, L.; Liao, Y.L.; Sun, H.B. Research on global path planning of surface unmanned boats based on electronic nautical charts. J. Comput. Sci. 2011, 38, 211–214. [Google Scholar]
  20. Wang, H.L.; Mao, W.G.; Eriksson, L. A Three-Dimensional Dijkstra’s algorithm for multi-objective ship voyage optimization. J. Ocean Eng. 2019, 186, 106131. [Google Scholar] [CrossRef]
  21. Koenig, S.; Likhachev, M.; Furcy, D. Lifelong planning A*. J. Artif. Intell. 2004, 155, 93–146. [Google Scholar] [CrossRef] [Green Version]
  22. Yu, J.B.; Yang, M.; Zhao, Z.Y.; Wang, X.Y.; Bai, Y.B.; Wu, J.G.; Xu, J.P. Path planning of unmanned surface vessel in an unknown environment based on improved D*Lite algorithm. J. Ocean Eng. 2022, 266, 112873. [Google Scholar] [CrossRef]
  23. Hart, P. Nearest neighbor pattern classification. J. IEEE Trans. Inf. Theory 1967, 13, 21–27. [Google Scholar]
  24. Sang, H.Q.; You, Y.S.; Sun, X.J.; Zhou, Y.; Liu, F. The hybrid path planning algorithm based on improved A* and artificial potential field for unmanned surface vehicle formations. Ocean Eng. 2021, 223, 107809. [Google Scholar] [CrossRef]
  25. Yang, J.M.; Tseng, C.M.; Tseng, P.S. Path Planning on Satellite Images for Unmanned Surface Vehicles. Int. J. Nav. Archit. Ocean Eng. 2015, 7, 87–99. [Google Scholar] [CrossRef] [Green Version]
  26. Bayili, S.; Polat, F. Limited-damage A*: A path search algorithm that considers damage as a feasibility criterion. Knowl. Based Syst. 2011, 24, 501–512. [Google Scholar] [CrossRef]
  27. Singh, Y.; Sharma, S.; Sutton, R.; Hatton, D.; Khan, A. A constrained A* approach towards optimal path planning for an unmanned surface vehicle in a maritime environment containing dynamic obstacles and ocean currents. Ocean Eng. 2018, 169, 187–201. [Google Scholar] [CrossRef] [Green Version]
  28. Campbell, S.; Abu-Tair, M.; Naeem, W. An automatic COLREGs-compliant obstacle avoidance system for an unmanned surface vehicle. J. Eng. Marit. Environ. 2014, 228, 108–121. [Google Scholar] [CrossRef]
  29. Wang, Y.L.; Yu, X.M.; Liang, X. Design and Implementation of Global Path Planning System for Unmanned Surface Vehicle among Multiple Task Points. J. Int. J. Veh. Auton. Syst. 2018, 14, 82–105. [Google Scholar] [CrossRef] [Green Version]
  30. Holland, J. Adaptation in Natural and Artificial Systems. In Applying Genetic Algorithm to Increase the Efficiency of a Data Flow-Based Test Data Generation Approach; University of Michigan Press: Ann Arbor, MI, USA, 1975. [Google Scholar]
  31. Tsai, C.C.; Huang, H.C.; Chan, C.K. Parallel elite genetic algorithm and its application to global path planning for autonomous robot navigation. IEEE Trans. Ind. Electron 2011, 58, 4813–4821. [Google Scholar] [CrossRef]
  32. Xiao, C.H.; Zou, Y.Y.; Li, S.Y. Path planning of multi–target points for multi UAV in obstacle area. Space Control Technol. Appl. 2019, 45, 46–52. [Google Scholar]
  33. Yao, Z.; Ma, L. A Static Environment-Based Path Planning Method by Using Genetic Algorithm. In Proceedings of the 2010 International Conference on Computing, Control and Industrial Engineering, Wuhan, China, 5–6 June 2010. [Google Scholar]
  34. Huang, S.Z.; Tian, J.W.; Qian, L.; Wang, Q.; Su, Y. Unmanned aerial vehicle path planning based on improved genetic algorithm. J. Comput. Appl. 2021, 41, 390–397. [Google Scholar]
  35. Hao, K.; Zhao, J.L.; Li, Z.S.; Liu, Y.L.; Zhao, L. Dynamic path planning of a three-dimensional underwater AUV based on an adaptive genetic algorithm. Ocean Eng. 2022, 263, 112421. [Google Scholar] [CrossRef]
  36. Hu, G.K.; Zhong, J.H.; Li, Y.Z.; Li, W.H. UAV 3D path planning based on IPSO-GA algorithm. J. Mod. Electron. Tech. 2023, 46, 115–120. [Google Scholar]
  37. Nazarahari, M.; Khanmirza, E.; Doostie, S. Multi-objective multi-robot path planning in continuous environment using an enhanced genetic algorithm. Expert Syst. Appl. 2019, 115, 106–120. [Google Scholar] [CrossRef]
  38. Li, K.R.; Hu, Q.Q.; Liu, J.P. Path planning of mobile robot based on improved multi-objective genetic algorithm Wireless. Commun. Mob. Comput. 2021, 2021, 8836615. [Google Scholar]
  39. Mcculloch, W.S.; Pitts, W. A logical calculus of the ideas immanent in nervous activity. Bull. Math. Biophys. 1943, 5, 115–133. [Google Scholar] [CrossRef]
  40. Chen, Y.; Liang, J.; Wang, Y.; Pan, Q. Autonomous mobile robot path planning in unknown dynamic environments using neural dynamics. Soft Comput. 2020, 24, 13979–13995. [Google Scholar] [CrossRef]
  41. Praczyk, T. Neural anti-collision system for autonomous surface vehicle. Neurocomputing 2015, 149, 559–572. [Google Scholar] [CrossRef]
  42. Xu, Q.; Zhang, C.; Zhang, L. Deep Convolutional Neural Network Based Unmanned Surface Vehicle Maneuvering. In Proceedings of the 2017 Chinese Automation Congress (CAC), Jinan, China, 20–22 October 2017. [Google Scholar]
  43. Liu, Y.; Zheng, Z.; Qin, F.Y.; Zhang, X.Y.; Yao, H.N. A residual convolutional neural network based approach for real-time path planning. Knowl. Based Syst. 2022, 242, 108400. [Google Scholar] [CrossRef]
  44. Sperduti, A.; Starita, A. Supervised neural networks for the classification of structures. IEEE Trans. Neural Netw. 1997, 8, 714–735. [Google Scholar] [CrossRef] [Green Version]
  45. Waikhom, L.; Patgiri, R. A survey of graph neural networks in various learning paradigm: Methods, applications, and challenges. Artif. Intell. Rev. 2022, 56, 6295–6364. [Google Scholar] [CrossRef]
  46. Kipf, T.N.; Welling, M. Semi-supervised classification with graph convolutional networks. arXiv 2017, arXiv:1609.02907. [Google Scholar]
  47. Zhao, L.; Song, Y.; Zhang, C.; Liu, Y.; Wang, P.; Lin, T.; Deng, M.; Li, H.F. T-GCN: A temporal graph convolutional network for traffic prediction. IEEE Trans. Intell. Transp. Syst. 2019, 21, 3848–3858. [Google Scholar] [CrossRef] [Green Version]
  48. Luo, C.; Yang, S.X. A Real-Time Cooperative Sweeping Strategy for Multiple Cleaning Robots. In Proceedings of the IEEE Internatinal Symposium on Intelligent Control, Vancouver, BC, Canada, 30–30 October 2002. [Google Scholar]
  49. Xu, P.F.; Ding, Y.X.; Luo, J.C. Complete Coverage Path Planning of an Unmanned Surface Vehicle Based on a Complete Coverage Neural Network Algorithm. J. Mar. Sci. Eng. 2021, 9, 1163. [Google Scholar] [CrossRef]
  50. Khatib, O. Real-Time Obstacle Avoidance for Manipulators and Mobile Robots. Int. J. Robot. Res. 1986, 5, 90–98. [Google Scholar] [CrossRef]
  51. Mielniczuk, M. A Method of Artificial Potential Fields for the Determination of Ship’s Safe Trajectory. Sci. J. Marit. Univ. Szczec. 2017, 51, 45–49. [Google Scholar]
  52. Azmi, M.Z.; Ito, T. Artificial potential field with discrete map transformation for feasible indoor path planning. J. Appl. Sci. 2020, 10, 8987. [Google Scholar] [CrossRef]
  53. Lazarowska, A. Discrete Artificial Potential Field Approach to Mobile Robot Path Planning. IFAC-PapersOnLine 2019, 52, 277–282. [Google Scholar] [CrossRef]
  54. Wu, P.; Xie, S.; Luo, J.; Qu, D.; Li, Q. The USV path planning based on the combinatorial algorithm. Rev. Tec. Fac. Ing. Univ. Zulia 2015, 38, 62–70. [Google Scholar]
  55. He, Z.H.; Chu, X.M.; Liu, C.G.; Wu, W.X. A novel model predictive artificial potential field based ship motion planning method considering COLREGs for complex encounter scenarios. ISA Trans. 2023, 134, 58–73. [Google Scholar] [CrossRef]
  56. Lavalle, S.M. Rapidly-Exploring Random Trees: A New Tool for Path Planning. Res. Rep. 1998. Available online: https://cir.nii.ac.jp/crid/1573950399665672960 (accessed on 22 May 2023).
  57. Karaman, S.; Frazzoli, E. Optimal Kinodynamic Motion Planning Using Incremental Sampling-based Methods. In Proceedings of the 49th IEEE Conference on Decision and Control (CDC), Atlanta, GA, USA, 15–17 December 2010. [Google Scholar]
  58. Feng, N. A Path Planning Method for Autonomous Mobile Robot Based on RRT Algorithm; Dalian University of Technology: Dalian, China, 2014. [Google Scholar]
  59. Jeong, I.B.; Lee, S.J.; Kim, J.H. Quick-RRT*: Triangular inequality-based implementation of RRT* with improved initial solution and convergence rate. Expert Syst. 2019, 123, 82–90. [Google Scholar] [CrossRef]
  60. Kuffner, J.J.; LaValle, S.M. RRT-connect: An efficient approach to single-query path planning. IEEE Int. Conf. Robot. Autom. Symp. Proc. 2000, 2, 995–1002. [Google Scholar]
  61. Ding, J.; Zhou, Y.X.; Huang, X.; Song, K.; Lu, S.Q.; Wang, L.S. An improved RRT* algorithm for robot path planning based on path expansion heuristic sampling. J. Comput. Sci. 2023, 67, 101937. [Google Scholar] [CrossRef]
  62. Ma, G.J.; Duan, Y.L.; Li, M.Z.; Xie, Z.B.; Zhu, J. A probability smoothing Bi-RRT path planning algorithm for indoor robot. Future Gener. Comput. Syst. 2023, 143, 349–360. [Google Scholar] [CrossRef]
  63. Qureshi, A.H.; Ayaz, Y. Potential functions based sampling heuristic for optimal path planning. Autom. Robots 2016, 40, 1079–1093. [Google Scholar] [CrossRef] [Green Version]
  64. Zhang, X.; Zhu, T.; Du, L.; Hu, Y.; Liu, H. Local Path Planning of Autonomous Vehicle Based on an Improved Heuristic Bi-RRT Algorithm in Dynamic Obstacle Avoidance Environment. Sensors 2022, 22, 7968. [Google Scholar] [CrossRef]
  65. Fiorini, P.; Shiller, Z. Motion planning in dynamic environments using velocity obstacles. Int. J. Robot. Res. 1998, 17, 760–772. [Google Scholar] [CrossRef]
  66. Zhuang, J.Y.; Zhang, G.C. Obstacle avoidance method for USV. J. Southeast Univ. 2013, 43, 126–130. [Google Scholar]
  67. Cho, Y.; Han, J.; Kim, J.; Lee, P.; Park, S.B. Experimental validation of a velocity obstacle based collision avoidance algorithm for unmanned surface vehicles. IFAC-PapersOnLine 2019, 52, 329–334. [Google Scholar] [CrossRef]
  68. Wang, J.; Wang, R.; Lu, D.; Zhou, H.; Tao, T. USV Dynamic Accurate Obstacle Avoidance Based on Improved Velocity Obstacle Method. Electronics 2022, 11, 2720. [Google Scholar] [CrossRef]
  69. Song, L.F.; Su, Y.R.; Dong, Z.P.; Shen, W.; Xiang, Z.Q.; Mao, P.X. A Two-Level Dynamic Obstacle Avoidance Algorithm for Unmanned Surface Vehicles. J. Ocean Eng. 2018, 170, 351–360. [Google Scholar] [CrossRef]
  70. Du, K.J.; Mao, Y.S.; Xiang, Z.Q.; Zhou, Y.Q.; Song, L.F.; Liu, B. A dynamic obstacle avoidance method of USV based on COLREGS. J. Ship Eng. 2015, 3, 119–124. (In Chinese) [Google Scholar]
  71. Bareiss, D.; Berg, V.D. Generalized reciprocal collision avoidance. J. Robot. Res. 2015, 34, 1501–1514. [Google Scholar] [CrossRef]
  72. Huang, Y.M.; Chen, L.Y.; Gelder, V.P. Generalized velocity obstacle algorithm for preventing ship collisions at sea. J. Ocean Eng. 2019, 173, 142–156. [Google Scholar] [CrossRef]
  73. Su, Y.M.; Luo, J.; Zhuang, J.Y.; Song, S.Q.; Huang, B.; Zhang, L. A constrained locking sweeping method and velocity obstacle based path planning algorithm for unmanned surface vehicles in complex maritime traffic scenarios. J. Ocean Eng. 2023, 279, 113538. [Google Scholar] [CrossRef]
  74. Fox, D.; Burgard, W.; Thrun, S. The dynamic window approach to collision avoidance. IEEE Robot. Autom. Mag. 1997, 4, 23–33. [Google Scholar] [CrossRef] [Green Version]
  75. Brock, O.; Khatib, O. High-Speed Navigation Using the Global Dynamic Window Approach. In Proceedings of the 1999 IEEE International Conference on Robotics and Automation, Detroit, MI, USA, 10–15 May 1999. [Google Scholar]
  76. Lin, X.G.; Fu, Y. Research of USV Obstacle Avoidance Strategy Based on Dynamic Window. In Proceedings of the 2017 IEEE International Conference on Mechatronics and Automation (ICMA), Takamatsu, Japan, 6–9 August 2017. [Google Scholar]
  77. Yu, X.Y.; Zhu, Y.C.; Lu, L.; Ou, L.L. Dynamic window with virtual goal (DW-VG): A new reactive obstacle avoidance approach based on motion prediction. J. Robot. 2019, 37, 1438–1456. [Google Scholar]
  78. Zhang, Y.Y.; Qu, D.; Ke, J.; Li, S.M. Dynamic obstacle avoidance of unmanned surface boats based on velocity barrier method and dynamic window method. J. Shanghai Univ. 2017, 23, 1–16. [Google Scholar]
  79. Wang, N.; Gao, Y.; Zheng, Z.; Zhao, H.; Yin, J. A Hybrid Path-Planning Scheme for an Unmanned Surface Vehicle. In Proceedings of the 2018 Eighth International Conference on Information Science and Technology (ICIST), Cordoba, Granada, and Seville, Spain, 30 June–6 July 2018. [Google Scholar]
  80. Han, S.; Wang, L.; Wang, Y.T.; He, H.C. A dynamically hybrid path planning for unmanned surface vehicles based on non-uniform Theta* and improved dynamic windows approach. Ocean Eng. 2022, 257, 111655. [Google Scholar] [CrossRef]
  81. Wang, Q.; Li, J.; Yang, L.; Yang, Z.; Li, P.; Xia, G. Distributed Multi-Mobile Robot Path Planning and Obstacle Avoidance Based on ACO–DWA in Unknown Complex Terrain. Electronics 2022, 11, 2144. [Google Scholar] [CrossRef]
  82. Wang, N.; Jin, X.Z.; Er, J.M. A multilayer path planner for a USV under complex marine environments. Ocean Eng. 2019, 184, 1–10. [Google Scholar] [CrossRef]
  83. Sethian, J.A. A fast marching level set method for monotonically advancing fronts. Proc. Natl. Acad. Sci. USA 1996, 93, 1591–1595. [Google Scholar] [CrossRef]
  84. Wang, A.G.; Zhi, P.F.; Zhu, W.L.; Qiu, H.Y.; Wang, H.; Wang, W.R. Path Planning of Unmanned Surface Vehicle Based on a Algorithm Optimization Considering the Influence of Risk Factors. In Proceedings of the 2021 4th IEEE International Conference on Industrial Cyber-Physical Systems (ICPS), Victoria, BC, Canada, 10–12 May 2021. [Google Scholar]
  85. Zhao, W.; Wang, Y.; Zhang, Z.; Wang, H. Multicriteria Ship Route Planning Method Based on Improved Particle Swarm Optimization–Genetic Algorithm. J. Mar. Sci. Eng. 2021, 9, 357. [Google Scholar] [CrossRef]
  86. Yin, S.; Mao, J.; Li, B. AUV 3D Path Planning Based on Improved Empire Competition Algorithm in Ocean Current Environment. In Proceedings of the 6th International Conference on Computing, Control and Industrial Engineering (CCIE 2021), Hangzhou, China, 15–16 January 2021; pp. 36–49. [Google Scholar]
  87. Sun, B.; Zhang, W.; Li, S.Q.; Zhu, X.X. Energy optimised D* AUV path planning with obstacle avoidance and ocean current environment. J. Navig. 2022, 75, 685–703. [Google Scholar] [CrossRef]
  88. Yu, J.B.; Chen, Z.H.; Zhao, Z.Y.; Yao, P.; Xu, J.P. A traversal multi-target path planning method for multi-unmanned surface vessels in space-varying ocean current. Ocean Eng. 2023, 278, 114423. [Google Scholar] [CrossRef]
  89. Li, B.; Mao, J.; Yin, S.; Fu, L.; Wang, Y. Path Planning of Multi-Objective Underwater Robot Based on Improved Sparrow Search Algorithm in Complex Marine Environment. J. Mar. Sci. Eng. 2022, 10, 1695. [Google Scholar] [CrossRef]
  90. Zhang, R.B.; Tang, P.P.; Yang, G.; Li, X.Y.; Shi, C.T. Convergence analysis of adaptive hazard avoidance decision process for surface unmanned boats. J. Comput. Res. Dev. 2014, 12, 2644–2652. (In Chinese) [Google Scholar]
  91. Sivaraj, S.; Rajendran, S.; Prasad, L.P. Data driven control based on deep Q-network algorithm for heading control and path following of a ship in calm water and waves. Ocean Eng. 2022, 259, 111802. [Google Scholar] [CrossRef]
  92. Rohit, D.R.S.; Sanjeev, K.; Md Shadab, A.; Abhilash, S. Deep reinforcement learning based controller for ship navigation. Ocean Eng. 2023, 273, 113937. [Google Scholar]
  93. Bhopale, P.; Kazi, F.; Singh, N. Reinforcement learning based obstacle avoidance for autonomous underwater vehicle. J. Mar. Sci. Appl. 2019, 18, 228–238. [Google Scholar] [CrossRef]
  94. Vibhute, S. Adaptive Dynamic Programming Based Motion Control of Autonomous Underwater Vehicles. In Proceedings of the 2018 5th International Conference on Control, Decision and Information Technologies (CoDIT), Thessaloniki, Greece, 10–13 April 2018; pp. 966–971. [Google Scholar]
  95. Li, P.J.; Yan, T.W.; Yang, S.T.; Li, R.; Du, J.F.; Qian, F.F.; Liu, Y.T. Energy-optimal Path Planning Algorithm for Unmanned Surface Vessel Based on Reinforcement Learning. J. Unmanned Undersea Syst. 2023, 31, 237–243. (In Chinese) [Google Scholar]
  96. Huang, Y.M.; Chen, L.Y.; Chen, P.F. Ship collision avoidance methods: State-of-the-art. Saf. Sci. 2020, 121, 451–473. [Google Scholar] [CrossRef]
  97. Melih, A.; Petter, S.; Tor, A.J. Collaborative collision avoidance for Maritime Autonomous Surface Ships: A review. Ocean Eng. 2022, 250, 110920. [Google Scholar]
  98. Zhang, X.Y.; Wang, C.B.; Jian, L.L.; An, L.X.; Yang, R. Collision-avoidance navigation systems for Maritime Autonomous Surface Ships: A state of the art survey. Ocean Eng. 2021, 235, 109380. [Google Scholar] [CrossRef]
  99. Zhu, Z.; Lyu, H.; Zhang, J.; Yin, Y. Decision supporting for ship collision avoidance in restricted waters. Int. J. Simul. Process Model. 2020, 15, 40–51. [Google Scholar]
  100. Dong, J.X. Area Coverage Path Planning of UAV Based on Deep Reinforcement Learning. J. Ind. Control Comput. 2021, 34, 80–82. [Google Scholar]
  101. Yang, L.; Xing, B.W.; Zhang, Z.Y.; Li, L.H. An Algorithm of Complete Coverage Path Planning Based on Improved DQN. Lect. Notes Electr. Eng. 2022, 845, 3728–3738. [Google Scholar]
  102. Xing, B.W.; Wang, X.; Yang, L.; Liu, Z.; Wu, Q. An Algorithm of Complete Coverage Path Planning for Unmanned Surface Vehicle Based on Reinforcement Learning. J. Mar. Sci. Eng. 2023, 11, 645. [Google Scholar] [CrossRef]
  103. Rong, H.; Teixeira, A.P.; Guedes, S.C. Ship collision avoidance behaviour recognition and analysis based on AIS data. J. Ocean Eng. 2022, 245, 110479. [Google Scholar] [CrossRef]
  104. Zhang, L.; Meng, Q. A Big AIS data based spatial-temporal analyses of ship traffic in Singapore port waters Transportation Research. Logist. Transp. Rev. 2019, 129, 287–304. [Google Scholar] [CrossRef]
  105. Gao, P.; Zhou, L.; Zhao, X.; Shao, B. Research on ship collision avoidance path planning based on modified potential field ant colony algorithm. Ocean Coast. Manag. 2023, 235, 106482. [Google Scholar] [CrossRef]
  106. Li, M.; Mou, J.; Chen, L.; He, Y.; Huang, Y. A rule-aware time-varying conflict risk measure for MASS considering maritime practice Reliab. J. Eng. Syst. 2021, 215, 107816. [Google Scholar]
  107. Zhou, X.Y.; Liu, Z.J.; Wang, F.W.; Ni, S.K. Collision Risk Identification of Autonomous Ships Based on the Synergy Ship Domain. In Proceedings of the 2018 Chinese Control And Decision Conference (CCDC), Shenyang, China, 9–11 June 2018; pp. 6746–6752.
  108. Ning, J.; Chen, H.; Li, T.; Li, W.; Li, C. COLREGs-compliant unmanned surface vehicles collision avoidance based on multi-objective genetic algorithm. IEEE Access 2020, 8, 190367–190377. [Google Scholar] [CrossRef]
  109. Jin, Q.B.; Tang, C.N.; Cai, W. Research on dynamic path planning based on the fusion algorithm of improved ant colony optimization and rolling window method. IEEE Access 2022, 10, 28322–28332. [Google Scholar] [CrossRef]
  110. Zhang, C.G.; Xi, Y.G. Robot rolling path planning based on locally detected information. Acta Autom. Sin. 2003, 29, 38–44. [Google Scholar]
  111. Gao, M.; Tang, H.; Zhang, P. Current status of research on robot cluster path planning technology. J. Natl. Univ. Def. Technol. 2021, 43, 127–138. [Google Scholar]
  112. Hidalgo-Paniagua, A.; Vega-Rodríguez, M.A.; Ferruz, J.; Pavón, N. Solving the multi-objective path planning problem in mobile robotics with a firefly-based approach. J. Soft Comput. 2017, 21, 949–964. [Google Scholar] [CrossRef]
  113. Su, M.M.; Cheng, Y.M.; Hu, J.W.; Zhao, C.H.; Jia, C.J.; Xu, Z.; Zhang, J.F. Combined optimization of swarm task allocation and path planning based on improved ant colony algorithm. J. Unmanned Syst. Technol. 2021, 4, 40–50. (In Chinese) [Google Scholar]
  114. Dorigo, M.; Blum, C. Ant colony optimization theory: A survey. Theor. Comput. Sci. 2005, 344, 243–278. [Google Scholar] [CrossRef]
  115. Liang, J.H.; Lee, C.H. Efficient collision-free path-planning of multiple mobile robots system using efficient artificial bee colony algorithm. Adv. Eng. Softw. 2015, 79, 45–56. [Google Scholar] [CrossRef]
  116. Karaboga, D. An Idea Based on Honey Bee Swarm for Numerical Optimization; Technical Report; R. Computers Engineering Department, Engineering Faculty, Erciyes University: Kayseri, Türkiye, 2005. [Google Scholar]
  117. Liu, Y.; Zhang, X.; Guan, X.; Delahaye, D. Adaptive sensitivity decision based path planning algorithm for unmanned aerial vehicle with improved particle swarm optimization. Aerosp. Sci. Technol. 2016, 58, 92–102. [Google Scholar] [CrossRef]
  118. Gen, Q.; Zhao, Z. A Kind of Route Planning Method for UAV Based on Improved PSO Algorithm. In Proceedings of the 2013 25th Chinese Control and Decision Conference (CCDC), Guiyang, China, 25–27 May 2013; pp. 2328–2331. [Google Scholar]
  119. Chen, P.; Shi, G.Y.; Liu, S.; Zhangi, Y.Q. Decision Support Based On Artificial Fish Swarm For Ship Collision Avoidance From Ais Data. In Proceedings of the 2018 International Conference on Machine Learning and Cybernetics (ICMLC), Chengdu, China, 15–18 July 2018; pp. 31–36. [Google Scholar]
  120. Li, X.L.; Shao, Z.J.; Qian, J.X. Optimizing method based on autonomous animats: Fish-swarm algorithm. Syst. Eng. Theory Pract. 2002, 22, 32–38. (In Chinese) [Google Scholar]
  121. Zhang, Y.; Hua, Y.H. Path planning of mobile robot based on hybrid improved artificial fish swarm algorithm. Vibroeng. Proc. 2018, 17, 130–136. [Google Scholar] [CrossRef] [Green Version]
  122. Zhao, Z.; Zhu, B.; Zhou, Y.; Yao, P.; Yu, J. Cooperative Path Planning of Multiple Unmanned Surface Vehicles for Search and Coverage Task. Drones 2023, 7, 21. [Google Scholar] [CrossRef]
  123. Mirjalili, S.; Gandomi, A.H.; Mirjalili, S.Z.; Saremi, S.; Faris, H.; Mirjalili, S.M. Salp Swarm Algorithm: A bio-inspired optimizer for engineering design problems. Adv. Eng. Softw. 2017, 114, 163–191. [Google Scholar] [CrossRef]
  124. Long, Y.; Liu, S.; Qiu, D.; Li, C.; Guo, X.; Shi, B.; AbouOmar, M.S. Local Path Planning with Multiple Constraints for USV Based on Improved Bacterial Foraging Optimization Algorithm. J. Mar. Sci. Eng. 2023, 11, 489. [Google Scholar] [CrossRef]
  125. Long, Y.; Su, Y.; Shi, B.; Zuo, Z.; Li, J. A multi-subpopulation bacterial foraging optimisation algorithm with deletion and immigration strategies for unmanned surface vehicle path planning. Intell. Serv. Robot. 2021, 14, 303–312. [Google Scholar] [CrossRef]
  126. Qu, X.Q.; Gan, W.H.; Song, D.L.; Zhou, L.Q. Pursuit-evasion game strategy of USV based on deep reinforcement learning in complex multi-obstacle environment. Ocean Eng. 2023, 273, 114016. [Google Scholar] [CrossRef]
  127. Wang, L.L.; Zhu, D.Q.; Pang, W.; Zhang, Y.M. A survey of underwater search for multi-target using Multi-AUV: Task allocation, path planning, and formation control. Ocean Eng. 2023, 278, 114393. [Google Scholar] [CrossRef]
  128. Venturini, F.; Mason, F.; Pase, F.; Testolin, A.; Zanella, A.; Zorzi, M. Distributed reinforcement learning for flexible and efficient UAV swarm control. J. Cogn. Commun. Netw. 2021, 7, 955–968. [Google Scholar] [CrossRef]
  129. Mou, Z.Y.; Zhang, Y.; Gao, F.F.; Wang, H.G.; Zhang, T.; Han, Z. Deep reinforcement learning based three dimensional area coverage With UAV swarm. IEEE J. Sel. Areas Commun. 2021, 39, 3160–3176. [Google Scholar] [CrossRef]
  130. Wang, J.; Yang, Y.X.; Li, L. Mobile robot path planning based on improved deep reinforcement learning. Electron. Meas. Technol. 2021, 44, 19–24. [Google Scholar]
  131. Shi, Z.; Zhang, Q. Improved Q-Learning Algorithm Based on Pheromone Mechanism for Swarm Robot System. In Proceedings of the 32nd Chinese Control Conference, Xi’an, China, 26–28 July 2013. [Google Scholar]
  132. Zhu, X.M.; Wang, L.L.; Li, Y.M.; Song, S.D.; Ma, S.Y.; Yang, F.; Zhai, L.B. Path planning of multi-UAVs based on deep Q-network for energy-efficient data collection in UAVs-assisted IoT. Veh. Commun. 2022, 36, 100491. [Google Scholar] [CrossRef]
  133. Liu, Y.C.; Song, R.; Bucknall, R.; Zhang, X.Y. Intelligent multi-task allocation and planning for multiple unmanned surface vehicles (USVs) using self-organising maps and fast marching method. Inf. Sci. 2019, 496, 180–197. [Google Scholar] [CrossRef]
  134. Kohonen, T. The self-organizing map. Proc. IEEE 1990, 78, 1464–1480. [Google Scholar] [CrossRef]
  135. Garrido, S.; Moreno, L.; Blanco, D.; Martin, F. FM2: A Real-Time Fast Marching Sensor-Based Motion Planner. In Proceedings of the 2007 IEEE/ASME International Conference on Advanced Intelligent Mechatronics, Zurich, Switzerland, 4–7 September 2007. [Google Scholar]
  136. Liu, Z.X.; Zhang, Y.M.; Yu, X.; Yuan, C. Unmanned surface vehicles: An overview of developments and challenges. Annu. Rev. Control 2016, 41, 71–93. [Google Scholar] [CrossRef]
  137. Peng, Y.; Lou, Y.T.; Zhang, K.M. Multi-USV cooperative path planning by window update based self-organizing map and spectral clustering. J. Ocean Eng. 2023, 275, 114140. [Google Scholar]
  138. Du, P.Z.; Yang, W.C.; Chen, Y.; Huang, S.H. Improved indirect adaptive line-of-sight guidance law for path following of under-actuated AUV subject to big ocean currents. J. Ocean Eng. 2023, 281, 114729. [Google Scholar] [CrossRef]
Figure 1. Global path planning algorithm.
Figure 1. Global path planning algorithm.
Jmse 11 01556 g001
Figure 2. Local path planning algorithm.
Figure 2. Local path planning algorithm.
Jmse 11 01556 g002
Figure 3. USV kinematic model.
Figure 3. USV kinematic model.
Jmse 11 01556 g003
Figure 4. Vessel collision avoidance route map based on DCPA.
Figure 4. Vessel collision avoidance route map based on DCPA.
Jmse 11 01556 g004
Figure 5. Path planning of improved DQN [102].
Figure 5. Path planning of improved DQN [102].
Jmse 11 01556 g005
Figure 6. USV cluster multi-objective task assignment.
Figure 6. USV cluster multi-objective task assignment.
Jmse 11 01556 g006
Table 1. Characteristics of different algorithms for global path planning.
Table 1. Characteristics of different algorithms for global path planning.
ReferencesMethodsLengthSmoothSafetyCOLREGTimeDuplicateDOAEfficiency
[14]DijkstraFFFFTFFF
[15,16]improved DijkstraTFFFTFFT
[18]hierachial DijkstraTFTTTFFT
[20]3D-DijkstraTFTFTFFT
[21,22]D*LiteTFFFTTTT
[23]A*TFFFTTFT
[25]FFA*TFTFTTTT
[26]LDA*TFTFTFFT
[28,29]R-RA*TTFFTTFT
[35]AGATTFFTFFT
[36]improved GATTFFTTFT
[37]EGATTTFTFFT
[38]IMGATTTFTTFT
[42]CNNTFTTTFFT
[44]GNNTTTFTFFT
[46]GCNTTTFTFFT
[48]BINNTTTFTFFT
[49]CINNTTTFTFTT
Note: consider (T), no consider (F), dynamic obstacle avoidance (DOA), * (start).
Table 2. Characteristics of different algorithms for local path planning.
Table 2. Characteristics of different algorithms for local path planning.
ReferencesMethodsLengthSmoothEfficiencyDOAGOACOLREGReal-TimeOptimal
[35]VAPFTTTTTFTF
[51]APFTFFFFFTF
[52]improved APFTTTTTTTF
[53]DAPFTTTTFFTT
[54]APF-ACOTTTTTFTT
[55]MPAPFTTTTFTTT
[56]RRTTFTFFFFF
[58]RRT*TTFTFFTF
[59]Q-RRT*TTFTTFTF
[60]RRT-ConnectTTTTFFTT
[63]P-RRT*TTFTFFFT
[64]improved BI-RRTTTTTTFTT
[61]PSBI-RRTTTTTTFTF
[66]VOTFFTTTFF
[68]improved VOTTTTTTTF
[69]VO-APFTFTTFTTF
[70]VO-ACOTTTTFTTT
[72]GVO-CASTTTTFTTF
[73]CLSM-VOTTTTTTTF
[76]DWAFFTTFFTF
[79]DWA-A*TTTTFTTF
[78]DWA-VOTTTTTTTF
[80]IDWATTTTFFTT
[81]DWA-ACOTTTTTFTT
Note: consider (T), no consider (F), dynamic obstacle avoidance (DOA), global obstacle avoidance (GOA), * (start).
Table 3. Characteristics of different algorithms for hazard avoidance.
Table 3. Characteristics of different algorithms for hazard avoidance.
ReferenceMethodEfficiencyDOACOLREGReal-TimeAISWindCurrentDynamics
[82]MPPFTFTFFFF
[84]GA-APFTFTTFFFF
[85]PSO-GATTTTFTFF
[86]ICATTTTFTTT
[89]SSATTTTFTTT
[87]improved D*TTTFFTTT
[88]VF-RRT*TTTTFTTT
[91]DQNTFFTFFFT
[92]IDQNTTFTFTFT
[90]RLFFTTFFFF
[93]Q-NNTFFTFTFT
[95]DRLTFFTFTTT
[102]CCPPTTFTFTTT
[103]SWATFTFTFFT
[105]ACO-APFTTTTTFFT
[107]SSDFTTTTFFT
[108]MODM-CGATTFTTFFF
[109]ACO-RWMTTTTFFFT
Note: consider (T), no consider (F), DOA (dynamic obstacle avoidance), * (start).
Table 4. Characteristics of different algorithms for clusters.
Table 4. Characteristics of different algorithms for clusters.
ReferencesMethodsMassEfficiencyConvergenceCOLREGReal-TimeMutiEnvironment
[112]FATTTFFTF
[113]ACOFTFFFFT
[115]EABCTTTFTFF
[117]improved PSOTTTFTTF
[119]AFSAFTTFTFF
[121]HIAFSATTTFTTF
[123]SSATTTFTTF
[124]SA-BFOTTTTTTF
[128]RLTTTFFTT
[130]HER-DQNTTTFTFF
[132]HAS-DQNTTTFTFF
[133]improved SOMFTTFTTT
[137]SOM-SCTTTFTTT
Note: consider (T), no consider (F), Muti (muti-objective).
Table 5. Global path planning strategy and local path planning strategy contrast and analysis.
Table 5. Global path planning strategy and local path planning strategy contrast and analysis.
CharacteristicsGlobal Path Planning StrategyLocal Path Planning Strategy
Informationknown and allsensor acquisition
Functionglobal optimization searchlocal optimization search
Calculation volumecomplex and slowsimple and quick
Application scenariostatic environmentsdynamic environments
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Xing, B.; Yu, M.; Liu, Z.; Tan, Y.; Sun, Y.; Li, B. A Review of Path Planning for Unmanned Surface Vehicles. J. Mar. Sci. Eng. 2023, 11, 1556. https://doi.org/10.3390/jmse11081556

AMA Style

Xing B, Yu M, Liu Z, Tan Y, Sun Y, Li B. A Review of Path Planning for Unmanned Surface Vehicles. Journal of Marine Science and Engineering. 2023; 11(8):1556. https://doi.org/10.3390/jmse11081556

Chicago/Turabian Style

Xing, Bowen, Manjiang Yu, Zhenchong Liu, Yinchao Tan, Yue Sun, and Bing Li. 2023. "A Review of Path Planning for Unmanned Surface Vehicles" Journal of Marine Science and Engineering 11, no. 8: 1556. https://doi.org/10.3390/jmse11081556

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