Next Article in Journal
Numerical Simulation of Bionic Underwater Vehicle Morphology Drag Optimisation and Flow Field Noise Analysis
Next Article in Special Issue
Ship Segmentation via Combined Attention Mechanism and Efficient Channel Attention High-Resolution Representation Network
Previous Article in Journal
Blockchain-Based Cold Chain Traceability with NR-PBFT and IoV-IMS for Marine Fishery Vessels
Previous Article in Special Issue
New Exploration of Emission Abatement Solution for Newbuilding Bulk Carriers
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Ship Trajectory Planning and Optimization via Ensemble Hybrid A* and Multi-Target Point Artificial Potential Field Model

School of Electrical Engineering and Automation, Jiangxi University of Science and Technology, Ganzhou 341000, China
*
Author to whom correspondence should be addressed.
J. Mar. Sci. Eng. 2024, 12(8), 1372; https://doi.org/10.3390/jmse12081372
Submission received: 7 July 2024 / Revised: 6 August 2024 / Accepted: 9 August 2024 / Published: 12 August 2024

Abstract

:
Ship path planning is the core problem of autonomous driving of smart ships and the basis for avoiding obstacles and other ships reasonably. To achieve this goal, this study improved the traditional A* algorithm to propose a new method for ship collision avoidance path planning by combining the multi-target point artificial potential field algorithm (MPAPF). The global planning path was smoothed and segmented into multi-target sequence points with the help of an improved A* algorithm and fewer turning nodes. The improved APF algorithm was used to plan the path of multi-target points locally, and the ship motion constraints were considered to generate a path that was more in line with the ship kinematics. In addition, this method also considered the collision avoidance situation when ships meet, carried out collision avoidance operations according to the International Regulations for Preventing Collisions at Sea (COLREGs), and introduced the collision risk index (CRI) to evaluate the collision risk and obtain a safe and reliable path. Through the simulation of a static environment and ship encounter, the experimental results show that the proposed method not only has good performance in a static environment but can also generate a safe path to avoid collision in more complex encounter scenarios.

1. Introduction

Big data and artificial intelligence have driven the development of smart autonomous ships, which are expected to dominate future maritime transportation. The safety of ship navigation has become the primary concern. Ship navigation accidents can result in significant loss of life and property of both the ship and crew [1]. According to a survey, over 75% of accidents are caused by human decision-making, and the use of autonomous navigation on intelligent ships has partially alleviated losses. One of the primary research directions is to avoid ship collisions, which is one of the urgent problems for intelligent ships. There are three steps in the process of ship collision avoidance (CA): obstacle detection, CA decision-making, and CA action. The detection of obstacles by radar, AIS, and other navigation aids is crucial for ships to make collision avoidance decisions [2]. International regulations for preventing collisions at sea (COLREGs) contain precise advice on how to avoid ship collisions in various encounter scenarios. It is a challenge for ships to avoid collision when considering COLREGs and ship kinematics, particularly in complex encounter scenes.
Many scholars have proposed a variety of path planning algorithms for avoiding ship collisions [3,4]. The effects of these methods vary depending on the driving environment. Meta-heuristic optimization algorithms, such as genetic algorithms, have been proposed by various studies to optimize the shortest time or shortest distance path [5]. Machmudah, A. improved path efficiency by optimizing the UAV turning mechanism; this provided a great reference for ship heading optimization [6]. The simulated annealing algorithm and the multi-objective optimization algorithm have also been applied to ship path planning [7,8].
Graph search is a dynamic path-planning method that is based on environment modeling. This method plans the path by rasterizing the navigation environment image and combining it with the corresponding algorithm. The Dijkstra algorithm and A* algorithm are widely used. The Dijkstra algorithm [9] combines the concepts of breadth search algorithms (BFS) and greedy strategies to calculate the lowest cost path from the source node to the destination during operation. Padhy used the Dijkstra algorithm to solve the route optimization problem and achieved success; the application of this algorithm in route optimization has been the main focus of researchers since then [10]. The A* algorithm [11,12,13] combined with the heuristic function of the Dijkstra algorithm results in the optimal path by calculating the cost of the route to reach the target. Lan proposed a ship path-planning algorithm fusing the A-star and ant colony algorithms, which solved the problems of slow convergence speeds and long search times [14,15]. Singh et al. proposed a new A* algorithm, which takes into collision risk and driving rules, to find an optimal and safest path [16]. He et al. proposed a collision avoidance algorithm that is dynamic and can still be effective in complex multi-ship encounter scenes [17]. Donggyun Kim proposed a Samsung Autonomous Ship (SAS) collision avoidance system that can visualize the best route searched and reflect the relevant parameters of consumers in real time [18]. Hyeong-Tak Lee et al. proposed a new method to obtain the shortest navigation distance in the navigable area by taking automatic identification system data into consideration [19,20,21]. One of its disadvantages is that it perhaps lapses into local minimization so that it cannot obtain the correct results. In addition, there are heuristic algorithms for swarm intelligence, including the ant colony algorithm, particle swarm algorithm (PSO), and grey wolf algorithm. The optimal path is achieved by genetic algorithms by solving the optimal solution using the phenomenon of chromosome crossover and mutation. PSO simulates the foraging behavior of birds in nature and obtains the optimal result through the evolution process of the whole particle swarm from disorder to order in the solving space [22,23]. The PSO algorithm has fast convergence and simple convergence. Despite the application of these methods in ship route planning, there have always been problems with search speed and local optimization. Therefore, various algorithms have been improved and combinations of different algorithms have been developed to solve the defects of a single algorithm.
The artificial potential field algorithm (APF) is a popular algorithm in path planning because of its small amount of calculation, ease of understanding, and flexibility. Lyu and Yin proposed a vector environment information model to obtain a safe shortest path by using the repulsion from different obstacles during navigation [24]. However, this method does not solve the defect whereby the traditional APF method falls into the local optimum. Lazarowska proposed the discrete APF to optimize a ship’s risk-free trajectory, which greatly improves the safety of ship navigation [25]. Farhad proposed a route optimization method based on the electrostatic potential field (EPF), which uses the high potential value generated by the electrostatic field to prevent the vehicle from falling into the local optimum [26]. Therefore, some scholars have proposed a hybrid algorithm combining APF with other algorithms [27], fully utilizing the advantages and disadvantages of different algorithms. Artificial potential field theory was introduced to collision avoidance systems by Mousazadeh and others, resulting in a solution to the optimization problem concerning collision prevention [28]. There has been rapid development of random trees (RRT) [29,30,31] and deep reinforcement learning algorithms [32,33,34,35]. They are also used to obtain better ship trajectories.
In previous studies, rasterization or binarization thresholds are usually used to process electronic charts and environmental images and then intelligent algorithms are used to plan paths on the unitized map. In order to obtain the best results, the previous methods analyze the optimized results repeatedly, which makes it easy to fall into the local cycle and increases the calculation time cost.
In view of the above shortcomings, this paper makes the following contributions:
(1)
In this paper, a new A*path planning algorithm is proposed, which considers the constraints of ship motion, improves the traditional A*algorithm, eliminates redundant nodes, and smoothes the path.
(2)
Considering the phenomenon that the APF algorithm can easily fall into local loops, an artificial potential field multi-target points (MPAPF) approach is proposed. The global path derived by the A* algorithm is divided into multi-target points, and MPAPF is used to optimize each target point locally to obtain an optimal path.
(3)
In route planning, the collision risk factor (CRI) is introduced, and, under the rules proposed by the International Maritime Organization (IMO), the CRI value of each segment is continuously calculated to ensure that a safe, economical, and reliable route is found.
The structure of the rest of this paper is as follows: In the second part, the ship motion planning model is established and ship motion planning is considered. Then, in Section 2.2, the ship path-planning algorithm is introduced, namely, the improved A* algorithm and the multi-objective artificial market algorithm. In the third part, the simulation experiments of ship collision avoidance path planning are carried out in two scenarios of static sea area and ship encounter and compared with the traditional A* algorithm, and the effectiveness and reliability of the method are verified. Finally, the work conducted in this study is summarized and prospects are discussed.

2. Methods

2.1. Ship Motion Model

The motion model of a ship is a very complex, nonlinear problem. Due to the diverse influence of hydrodynamic forces and environments, a ship’s power system is considerably different from conventional linear systems like vehicles and ground robots. It is not possible to disregard the motion characteristics of ships for collision avoidance. We established a ship motion model as shown in Figure 1, with O-XYZ as the inertial coordinate system and o-xyz as the appendage coordinate system (ship motion coordinate system). When describing the motion of ships on water, a six-degree-of-freedom motion is commonly used to describe it, which includes sway, surge, heave, pitch, roll, and yaw. The efficiency of ship trajectory planning was considered in this study by considering three degrees of freedom motions: pitch, roll, and yaw. The definition symbols are shown in Table 1.
In this study, the unified hydrodynamic model was used to establish the motion model of the vehicle, which could be expressed by Equations (1) and (2):
η ˙ = J ( ψ ) v
M v ˙ + C ( v ) v + D ( v ) v = τ + τ e
where v = [ u , v , r ] T represents the vector matrix of heave, pitch, and roll motions of the ship and η = [ x , y , ψ ] T is the position ( x , y ) and attitude matrix of the ship. The driving force matrix τ = [ τ u , τ v , τ r ] T and external disturbance τ e = [ τ e u , τ e v , τ e r ] T . J ( ψ ) is the transformation matrix between the inertial coordinate system and the body coordinate system, M is the inertia matrix, C is a skew-symmetric matrix, and D is a linear damping matrix, and its parameters are defined as in Equations (3)–(6):
J ( ψ ) = cos ψ sin ψ 0 sin ψ cos ψ 0 0 0 1
M = m X u ˙ 0 0 0 m Y v ˙ m X g Y r ˙ 0 m X g Y r ˙ I z N r ˙
C = 0 0 ( m Y v ˙ ) v ( m X g Y r ˙ ) r 0 0 ( m X u ˙ ) u ( m Y v ˙ ) v + ( m X g Y r ˙ ) r ( m X u ˙ ) u 0
D = X u 0 0 0 Y v Y r 0 N V N r
In addition, considering the flexibility of ship movement and navigation efficiency, certain constraints were imposed on the ship’s maneuverability, namely, Equation (7):
u u max , r r max
where u max represents the maximum surge velocity and r max represents the maximum yaw speed of the ship.

2.2. Ship Path Planning Algorithm

The path-planning algorithm proposed in this paper is mainly composed of two parts: using the improved A* algorithm to plan the global path and generate an optimal path. To plan the local path, the multi-target point artificial potential field method (MPAPF) was utilized and the maneuvering motion model was considered. Finally, a safe and efficient path was obtained.

2.2.1. Improved A* Global Path Optimization Algorithm

As a classic and popular heuristic search algorithm, the A* algorithm is widely used to find the shortest path in a unit graph. Before the A* algorithm is implemented, the ENC is converted into a bitmap of cells. The attribute of each cell determines whether there are obstacles, with a = 0 indicating that there are no obstacles and a = 1 indicating that there are obstacles. When the starting and ending points are identified, the A* algorithm will locate the most efficient route by utilizing the heuristic method of finding adjacent zero-value cells and Euclidean distance. Specifically, A* algorithm chooses the path that minimizes these by calculating the cost value F, as shown in Equation (8):
F ( n ) = g ( n ) + h ( n )
where F ( n ) is the cost value of the n th cell, g ( n ) represents the path length from the starting point to the n -th cell, and h ( n ) = ( n i p i ) 2 + ( n j p j ) 2 is the heuristic distance from the n -th cell to the destination point p .
Although the traditional A* algorithm can generate the shortest global path, it does not guarantee vehicle safety or take into account turning costs and path redundancies. Therefore, an improvement was made.
(a) Adding the turning cost ρ to the cost function could reduce the number of turns of the ship, thereby improving the efficiency and safety of the ship, as shown in Equation (9):
F ( n ) = g ( n ) + h ( n ) + ρ
(b) By constraining the search distance and path length, the search range could be narrowed and the search time could be reduced, as shown in Equation (10):
F ( n ) λ l max h ( n ) k d max
where λ and k are scale factors.

2.2.2. Hybrid Improved A* and Multi-Target Point Artificial Potential Field Algorithm

The APF has the characteristics of strong computational power, ease of understanding, and strong robustness in solving the local path-planning problem of ships. This paper proposes a multi-target point artificial potential field algorithm (MPAPF) that is combined with the improved A* algorithm to deal with the phenomenon of A* algorithm’s tendency to fall into the regional air circulation. In addition, the A* algorithm can address the problem of the APF algorithm’s weak global search capability.
When the traditional APF carries out path planning, when the target point and the obstacle are in a straight line, the repulsion force is greater than the target gravity, which will cause the ship to be unable to reach the target point through the obstacle. When the ship sails to a certain area, when the repulsion and gravity are equal, the resultant force is zero, which may cause the algorithm to fall into the local optimal value and cause the ship to stop traveling.
Considering the shortcomings of traditional APF algorithms, the following improvements were made:
(a) The traditional vector calculation method was modified to the potential energy calculation method and the effect boundary value R of the gravitational field function was set. When the relative distance between the ship and the target position G R , the value of the gravitational field was proportional to the k-th power of G ; when G > R , the value of the gravitational field was proportional to G , thus reducing the influence range of the gravitational potential field [36]. The specific equation is shown in Equations (11)–(13):
U t = U a U r
U a = 1 2 α G k , G R R α G , G > R
U r = r ( 1 O ) k
where U a is the gravitational field, U r is the repulsive field, and U t is the total field. G is the distance from the current point to the goal point, O is the distance from the current position to the obstacle, and α and r are the proportional factors of the gravitational potential field and the repulsive potential field, respectively, both of which are greater than zero, and k = 2.5 is the index of the calculated field.
(b) The route achieved by the A* algorithm was divided into multi-target points, which were sub-target points of the APF algorithm, and the ship’s motion model was taken into account. The ship’s speed was nearly zero when it fell into a local minimum. At this time, the sub-target point sequence found the next point as the current target point to continue to run; this ensured that when the program fell into the local optimum, the current point was skipped to find the optimal solution, greatly improving the fluency and rapidity of the algorithm. A flow chart of the ship path-planning method proposed in this paper is shown in Figure 2.

3. Experiments

3.1. Static Sea Environment Path Planning

To verify the effectiveness of the method, this study selected the Bohai Bay and Aegean coral islands areas as experimental planning areas for simulation, respectively. First, the improved A* algorithm was used to obtain the global planning route and then the MPAPF algorithm was used to plan the local route, taking into account the ship motion constraint model, and, finally, a safe and efficient route was obtained.
To grid the satellite image, it was converted into a greyscale image, and each pixel represented a grid. Figure 3 and Figure 4 show the satellite map (a), grey image (b), and image (c) transformed into the unit grid of the offshore waters of China and the Aegean islands area, respectively. Figure 3c has 687 × 630 pixels, the length of each pixel is about 1710 m, and the width is about 1500 m. Figure 4c has 687 × 715 pixels, each pixel is about 144 m in length and 196 m in width. The range of each unit grid was determined by the scale of the satellite map and the number of pixels. Usually, in order to ensure the safety of the planned route, the path algorithm considered more distance between the ship and the shoreline, that is, a path with fewer pixels was selected.
In addition, when planning the path, the black part represented the land (island) and the white part represented the navigation area. It is worth noting that the cell image may have some errors due to the color and resolution of the satellite image, which can impact the final path planning. Before verifying the proposed method, the definition of obstacles was assumed, which meant that the land in the cell image was complete. After completing the preliminary work, the path planning simulation was carried out for the two environments, and the routes are shown in Figure 5 and Figure 6. Among them, the green route and the blue route represent the routes reached by the traditional A* algorithm and the improved A* algorithm, respectively; the red route represents the route optimized by the method in this paper. The route information is shown in Table 2 and Table 3. It is worth noting that IMPAPF * is our proposed method. It can be seen that by improving the A* algorithm, the steering nodes of the route were significantly reduced and the efficiency of navigation was effectively improved.

3.2. Ship Collision Avoidance Decision

According to the actual situation encountered in the process of ship running, the encounter between two ships can be divided into three situations: head-on, crossing, and overtaking. In the process of collision avoidance, the ship conducts collision avoidance operations in accordance with the international maritime collision avoidance rules. Before that, the risk of collision needs to be assessed. In this study, CRI was used to evaluate the risk of vehicle collision, as shown in Equation (14):
C R I = W · U = 0.4 0.367 0.133 0.067 0.033 T × u D C P A u T C P A u D R u θ T u ε
W is the weight vector, a constant matrix. U is the membership matrix, the speed ratio of the target ship and the ship. ε = V T / V O is the jet velocity ratio of the target ship to our ship, and other factors are defined in reference [37]. The value of collision risk was between 0 and 1, and the closer the value was to 1, the higher the collision risk was. Usually, when C R I > 0.7 , it is considered that the risk of collision is higher, and collision avoidance operations should be carried out at this time. When searching the path, the algorithm proposed in this paper masked the nodes with C R I > 0.7 to prevent them from becoming the next node. This made route planning safer, more stable, and more efficient than general methods.
In order to verify the effectiveness of the proposed method, the ship encounter situation was simulated and verified, and three situations, namely, head-on encounter, cross encounter, and overtaking, were considered. The main parameters of the simulation ship are shown in Table 4. Figure 7 shows the collision avoidance operation when a single ship meets. OS stands for the ship and TS stands for the target ship. Without any steering operation by TS, when two ships approached each other, the collision risk rose at this time, and the algorithm performed collision avoidance operations in an emergency. According to the international collision rules, the ship changed its course to starboard to avoid the obstacle ship and drive safely.
Figure 8a shows the safe path planned by this algorithm when multiple ships meet. It can be seen that when the ship met other ships, the ship followed the planned path. When the ship detected the target ship and the CRI with the target ship was high, the ship avoided other ships by changing direction. In addition, after collision avoidance, the ship returned to the planned route. Figure 8b shows the course of our ship. When the ship was running normally, the ship kept a certain course. When meeting with the target ship, the ship’s course changed greatly, and, after collision avoidance, the ship’s course returned to its original direction. Figure 8c shows the rudder angle change of our ship; Figure 9 shows the distance between the ship and the target ship. It can be seen that the relative distance between the ship and the target ship was greater than 1 n mile, which is a safe distance. Therefore, the route planned by the method proposed in this paper was reliable and safe.

4. Conclusions

In this paper, a ship collision avoidance path-planning method IMPAPF * algorithm based on an improved A* algorithm and multi-target point artificial potential field algorithm (MPAPF) was proposed, and the static environment and ship encounter were analyzed and verified. The improved A*algorithm was used to obtain the optimal path and then the multi-target point-target point artificial potential field algorithm was used for local path planning; a ship motion model was introduced to ensure the reliability and safety of the path. In addition, when ships met, in order to prevent the occurrence of collision risk, CRI was used to evaluate the collision risk and avoid collision according to international maritime rules. At the end of this study, the proposed method was simulated, and the results show that the path obtained by the proposed method was safe and effective.
It is worth noting that although the method proposed in this paper can plan ship paths well in a static sea environment and ship encounter scene, this study did not take into account the situation of a ship emergency collision. In future work, how to solve the emergency collision avoidance problem will be incorporated into the planning algorithm. In addition, weather conditions such as ocean currents, wind waves, and tides will have an impact on ship trajectory. Therefore, in follow-up work, the impact of external weather factors on ship motion planning will also be considered.

Author Contributions

Conceptualization, Y.H. and S.Z. (Sishuo Zhao); methodology, Y.H., S.Z. (Sishuo Zhao), and S.Z. (Shuling Zhao); writing—original draft preparation, S.Z. (Sishuo Zhao) and S.Z. (Shuling Zhao); writing—review and editing, S.Z. (Sishuo Zhao) and Y.H.; funding acquisition, Y.H. All authors have read and agreed to the published version of the manuscript.

Funding

The work was jointly supported by the National Natural Science Foundation of China (72061016). Jiangxi Province Key Laboratory of Multidimensional Intelligent Perception and Control, China (No. 2024SSY03161).

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

The data can be accessed by sending an email to the corresponding author.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Yan, X.P.; Wang, S.-W.; Ma, F.; Liu, Y.C.; Wang, J. A novel path planning approach for smart cargo ships based on anisotropic fast marching. Expert Syst. Appl. 2020, 159, 113558. [Google Scholar] [CrossRef]
  2. Sawada, R.; Sato, K.; Majima, T. Automatic ship collision avoidance using deep reinforcement learning with LSTM in continuous action spaces. J. Mar. Sci. Technol. 2021, 26, 509–524. [Google Scholar] [CrossRef]
  3. Öztürk, Ü.; Akdağ, M.; Ayabakan, T. A review of path planning algorithms in maritime autonomous surface ships: Navigation safety perspective. Ocean Eng. 2022, 251, 111010. [Google Scholar] [CrossRef]
  4. Sukumar, N.; Srivastava, A. Exact imposition of boundary conditions with distance functions in physics-informed deep neural networks. Comput. Methods Appl. Mech. Eng. 2022, 389, 114333. [Google Scholar] [CrossRef]
  5. Wang, L.; Zhang, Z.; Zhu, Q.; Ma, S. Ship route planning based on double-cycling genetic algorithm considering ship maneuverability constraint. IEEE Access 2020, 8, 190746–190759. [Google Scholar] [CrossRef]
  6. Machmudah, A.; Shanmugavel, M.; Parman, S.; Manan TS, A.; Dutykh, D.; Beddu, S.; Rajabi, A. Flight trajectories optimization of fixed-wing UAV by bank-turn mechanism. Drones 2022, 6, 69. [Google Scholar] [CrossRef]
  7. Yuan, Q.; Wang, S.; Zhao, J.; Hsieh, T.H.; Sun, Z.; Liu, B. Uncertainty-informed ship voyage optimization approach for exploiting safety, energy saving and low carbon routes. Ocean Eng. 2022, 266, 112887. [Google Scholar] [CrossRef]
  8. Lee, S.M.; Roh, M.I.; Kim, K.S.; Jung, H.; Park, J.J. Method for a simultaneous determination of the path and the speed for ship route planning problems. Ocean Eng. 2018, 157, 301–312. [Google Scholar] [CrossRef]
  9. Sedeño-Noda, A.; Colebrook, M. A biobjective Dijkstra algorithm. Eur. J. Oper. Res. 2019, 276, 106–118. [Google Scholar] [CrossRef]
  10. Padhy, C.P.; Sen, D.; Bhaskaran, P.K. Application of wave model for weather routing of ships in the North Indian Ocean. Nat. Hazards 2008, 44, 373–385. [Google Scholar] [CrossRef]
  11. Oyekanlu, E.A.; Smith, A.C.; Thomas, W.P.; Mulroy, G.; Hitesh, D.; Ramsey, M.; Sun, D. A review of recent advances in automated guided vehicle technologies: Integration challenges and research areas for 5G-based smart manufacturing applications. IEEE Access 2020, 8, 202312–202353. [Google Scholar] [CrossRef]
  12. Grifoll, M.; Borén, C.; Castells-Sanabra, M. A comprehensive ship weather routing system using CMEMS products and A* algorithm. Ocean Eng. 2022, 255, 111427. [Google Scholar] [CrossRef]
  13. Miao, T.; El Amam, E.; Slaets, P.; Pissoort, D. An improved real-time collision-avoidance algorithm based on Hybrid A* in a multi-object-encountering scenario for autonomous surface vessels. Ocean Eng. 2022, 255, 111406. [Google Scholar] [CrossRef]
  14. Lan, X.; Lv, X.; Liu, W.; He, Y.; Zhang, X. Research on robot global path planning based on improved A-star ant colony algorithm. In Proceedings of the 2021 IEEE 5th Advanced Information Technology, Electronic and Automation Control Conference (IAEAC), Chongqing, China, 12–14 March 2021; Volume 5, pp. 613–617. [Google Scholar] [CrossRef]
  15. Zhang, M.; Ren, H.; Zhou, Y. Research on global ship path planning method based on improved ant colony algorithm. IEEE Open J. Intell. Transp. Syst. 2023, 4, 143–152. [Google Scholar] [CrossRef]
  16. 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]
  17. He, Z.; Liu, C.; Chu, X.; Negenborn, R.R.; Wu, Q. Dynamic anti-collision A-star algorithm for multi-ship encounter situations. Appl. Ocean. Res. 2022, 118, 102995. [Google Scholar] [CrossRef]
  18. Kim, D.; Kim, J.S.; Kim, J.H.; Im, N.K. Development of ship collision avoidance system and sea trial test for autonomous ship. Ocean. Eng. 2022, 266, 113120. [Google Scholar] [CrossRef]
  19. Lee, H.T.; Choi, H.M.; Lee, J.S.; Yang, H.; Cho, I.S. Generation of Ship’s passage plan using data-driven shortest path algorithms. IEEE Access 2022, 10, 126217–126231. [Google Scholar] [CrossRef]
  20. Chen, X.; Wei, C.; Yang, Y.; Luo, L.; Biancardo, S.A.; Mei, X. Personnel trajectory extraction from port-like videos under varied rainy interferences. IEEE Trans. Intell. Transp. Syst. 2024, 25, 6567–6579. [Google Scholar] [CrossRef]
  21. Asl, A.N.; Menhaj, M.B.; Sajedin, A. Control of leader–follower formation and path planning of mobile robots using Asexual Reproduction Optimization (ARO). Appl. Soft Comput. 2014, 14, 563–576. [Google Scholar] [CrossRef]
  22. Jovanović, I.; Perčić, M.; BahooToroody, A.; Fan, A.; Vladimir, N. Review of research progress of autonomous and unmanned shipping and identification of future research directions. J. Mar. Eng. Technol. 2024, 23, 82–97. [Google Scholar] [CrossRef]
  23. Wang, X.; Feng, K.; Wang, G.; Wang, Q. Local path optimization method for unmanned ship based on particle swarm acceleration calculation and dynamic optimal control. Appl. Ocean. Res. 2021, 110, 102588. [Google Scholar] [CrossRef]
  24. Lyu, H.; Yin, Y. COLREGS-constrained real-time path planning for autonomous ships using modified artificial potential fields. J. Navig. 2019, 72, 588–608. [Google Scholar] [CrossRef]
  25. Lazarowska, A. A discrete artificial potential field for ship trajectory planning. J. Navig. 2020, 73, 233–251. [Google Scholar] [CrossRef]
  26. Bayat, F.; Najafinia, S.; Aliyari, M. Mobile robots path planning: Electrostatic potential field approach. Expert Syst. Appl. 2018, 100, 68–78. [Google Scholar] [CrossRef]
  27. Gao, J.; Xu, X.; Pu, Q.; Petrovic, P.B.; Rodić, A.; Wang, Z. A Hybrid Path Planning Method Based on Improved A* and CSA-APF Algorithms. IEEE Access 2024, 12, 39139–39151. [Google Scholar] [CrossRef]
  28. Mousazadeh, H.; Jafarbiglu, H.; Abdolmaleki, H.; Omrani, E.; Monhaseri, F.; Abdollahzadeh, M.R.; Makhsoos, A. Developing a navigation, guidance and obstacle avoidance algorithm for an Unmanned Surface Vehicle (USV) by algorithms fusion. Ocean Eng. 2018, 159, 56–65. [Google Scholar] [CrossRef]
  29. Zaccone, R. COLREG-compliant optimal path planning for real-time guidance and control of autonomous ships. J. Mar. Sci. Eng. 2021, 9, 405. [Google Scholar] [CrossRef]
  30. Liu, Z.; Cui, J.; Meng, F.; Xie, H.; Dan, Y.; Li, B. Research on Intelligent Ship Route Planning Based on the Adaptive Step Size Informed-RRT* Algorithm. J. Marine. Sci. Appl. 2024. [Google Scholar] [CrossRef]
  31. Zhao, W.; Wang, H.; Geng, J.; Hu, W.; Zhang, Z.; Zhang, G. Multi-objective weather routing algorithm for ships based on hybrid particle swarm optimization. J. Ocean. Univ. China 2022, 21, 28–38. [Google Scholar] [CrossRef]
  32. Almasan, P.; Suárez-Varela, J.; Rusek, K.; Barlet-Ros, P.; Cabellos-Aparicio, A. Deep reinforcement learning meets graph neural networks: Exploring a routing optimization use case. Comput. Commun. 2022, 196, 184–194. [Google Scholar] [CrossRef]
  33. Chen, X.; Dou, S.; Song, T.; Wu, H.; Sun, Y.; Xian, J. Spatial-Temporal Ship Pollution Distribution Exploitation and Harbor Environmental Impact Analysis via Large-Scale AIS Data. J. Mar. Sci. Eng. 2024, 12, 960. [Google Scholar] [CrossRef]
  34. Sang, H.; You, Y.; Sun, X.; 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, 108709. [Google Scholar] [CrossRef]
  35. Liang, C.; Zhang, X.; Watanabe, Y.; Deng, Y. Autonomous collision avoidance of unmanned surface vehicles based on improved A star and minimum course alteration algorithms. Appl. Ocean. Res. 2021, 113, 102755. [Google Scholar] [CrossRef]
  36. Moradi, M.H.; Brutsche, M.; Wenig, M.; Wagner, U.; Koch, T. Marine route optimization using reinforcement learning approach to reduce fuel consumption and consequently minimize CO2 emissions. Ocean Eng. 2022, 259, 111882. [Google Scholar] [CrossRef]
  37. Seo, C.; Noh, Y.; Abebe, M.; Kang, Y.J.; Park, S.; Kwon, C. Ship collision avoidance route planning using CRI-based A∗ algorithm. Int. J. Nav. Arch. Ocean Eng. 2022, 15, 100551. [Google Scholar] [CrossRef]
Figure 1. Coordinate of ship motion.
Figure 1. Coordinate of ship motion.
Jmse 12 01372 g001
Figure 2. Process of the proposed ship path-planning method.
Figure 2. Process of the proposed ship path-planning method.
Jmse 12 01372 g002
Figure 3. China offshore area. (a) Satellite maps. (b) Greyscale image. (c) Grid cell images.
Figure 3. China offshore area. (a) Satellite maps. (b) Greyscale image. (c) Grid cell images.
Jmse 12 01372 g003
Figure 4. Aegean islands area. (a) Satellite maps. (b) Greyscale image. (c) Grid cell images.
Figure 4. Aegean islands area. (a) Satellite maps. (b) Greyscale image. (c) Grid cell images.
Jmse 12 01372 g004
Figure 5. Route planning of China offshore area.
Figure 5. Route planning of China offshore area.
Jmse 12 01372 g005
Figure 6. Route planning of Aegean islands area.
Figure 6. Route planning of Aegean islands area.
Jmse 12 01372 g006
Figure 7. Encounter situations of two ships.
Figure 7. Encounter situations of two ships.
Jmse 12 01372 g007
Figure 8. Route planning results of multi-ship meeting area. (a) The trajectory of the target ship and the collision avoidance path of our ship when multiple ships meet. (b) The course angle of our ship. (c) The rudder angle change of our ship.
Figure 8. Route planning results of multi-ship meeting area. (a) The trajectory of the target ship and the collision avoidance path of our ship when multiple ships meet. (b) The course angle of our ship. (c) The rudder angle change of our ship.
Jmse 12 01372 g008
Figure 9. Distance between the ship and the target ship.
Figure 9. Distance between the ship and the target ship.
Jmse 12 01372 g009
Table 1. Symbol definitions.
Table 1. Symbol definitions.
FreedomForce and MomentumLinearity/Angular VelocityPosition/Attitude Angle
SurgeXux
SwayYvy
YawNr ψ
Table 2. Route information of China offshore waters.
Table 2. Route information of China offshore waters.
MethodCalculation Time/sSteering NodePath Length/n Mile
Traditional A*427.61153596.4
Improved A*349.2311490.6
IMPAPF*385.9717512.8
Table 3. Route information of Aegean islands area.
Table 3. Route information of Aegean islands area.
MethodCalculation Time/sSteering NodePath Length/n Mile
Traditional A*235.5526773.9
Improved A*133.86759.4
IMPAPF*167.161263.5
Table 4. The main parameters of the simulation ship.
Table 4. The main parameters of the simulation ship.
Names and SymbolsValueUnit
Length116m
Width18m
Draft5.4m
Max rudder angle30°
Speed10knot
Block coefficient0.56-it
Maneuverability index (K)0.31s−1
Maneuverability index (T)62.4s
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

Huang, Y.; Zhao, S.; Zhao, S. Ship Trajectory Planning and Optimization via Ensemble Hybrid A* and Multi-Target Point Artificial Potential Field Model. J. Mar. Sci. Eng. 2024, 12, 1372. https://doi.org/10.3390/jmse12081372

AMA Style

Huang Y, Zhao S, Zhao S. Ship Trajectory Planning and Optimization via Ensemble Hybrid A* and Multi-Target Point Artificial Potential Field Model. Journal of Marine Science and Engineering. 2024; 12(8):1372. https://doi.org/10.3390/jmse12081372

Chicago/Turabian Style

Huang, Yanguo, Sishuo Zhao, and Shuling Zhao. 2024. "Ship Trajectory Planning and Optimization via Ensemble Hybrid A* and Multi-Target Point Artificial Potential Field Model" Journal of Marine Science and Engineering 12, no. 8: 1372. https://doi.org/10.3390/jmse12081372

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