Next Article in Journal
Transient Performance of Gas-Engine-Based Power System on Ships: An Overview of Modeling, Optimization, and Applications
Next Article in Special Issue
Research on Obstacle Avoidance Planning for UUV Based on A3C Algorithm
Previous Article in Journal
Daily-Scale Prediction of Arctic Sea Ice Concentration Based on Recurrent Neural Network Models
Previous Article in Special Issue
AUV Collision Avoidance Planning Method Based on Deep Deterministic Policy Gradient
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Maritime Search Path Planning Method of an Unmanned Surface Vehicle Based on an Improved Bug Algorithm

Navigation College, Dalian Maritime University, Dalian 116026, China
*
Author to whom correspondence should be addressed.
J. Mar. Sci. Eng. 2023, 11(12), 2320; https://doi.org/10.3390/jmse11122320
Submission received: 9 November 2023 / Revised: 29 November 2023 / Accepted: 5 December 2023 / Published: 7 December 2023
(This article belongs to the Special Issue AI for Navigation and Path Planning of Marine Vehicles)

Abstract

:
Due to the complicated and changing circumstances of the sea environment, path planning technology is essential for unmanned surface vehicles (USVs) to fulfill search tasks. In most cases, the location of the underwater target is unknown, so it is necessary to completely cover the search area. In this paper, the global static path is planned using a parallel line scan search. When encountering unknown obstacles, the improved Bug algorithm is used for local dynamic path planning according to the sensor detection information. This paper first sets up the safe expansion area to ensure the safety of the USV during the obstacle avoidance process and optimizes the movement direction considering the operation and behavior characteristics of the USV. To meet the requirement of USV steering, the Bezier curve is used to smooth the path points, which greatly improves the smoothness of the path. In this paper, the multi-mode switching strategy of the Bug algorithm based on obstacle boundary width obtained by the sensor is proposed, which ensures no area omissions and meets the requirement of search area coverage during the process of bypassing obstacles. The simulation results show that the improved Bug algorithm can maintain a safe distance along the obstacle boundary to bypass the obstacle. Moreover, the improved Bug algorithm effectively improves the path oscillation phenomenon of traditional Bug and shortens the path length and operating time. Finally, through the global search path planning simulation and comparison experiments, the effectiveness of the proposed method is verified.

1. Introduction

In recent years, emergencies at sea have increased and become more complicated. Sea search and rescue is an indispensable means to ensure the safety of people’s lives and the creation of a good maritime transportation environment. Therefore, the related technologies of maritime search and rescue are increasingly valued. With the characteristics of autonomy, flexibility, intelligence, and information technology, USV provides a new way for the development of sea search work [1]. Due to the complicated and changing sea environment, path planning and obstacle avoidance technology are essential for USV to conduct a search assignment at sea [2,3].
Maritime search can be roughly divided into two scenarios: (1) planning point-to-point paths for multiple specific target points; and (2) search coverage for large search areas. For most cases of maritime search and rescue, the specific location of the drowning person is unknown, so this paper mainly studies the method of search area coverage. The goal of coverage path planning (CPP) is to plan an optimal path that can fulfill the task of area coverage. According to the research of Tan et al. [4], common area coverage algorithms are divided into classical algorithms and heuristic-based algorithms. Features of area coverage methods are shown in Table 1. Classical algorithms include the spanning tree coverage algorithm (STC), artificial potential field (APF), and Bug algorithms, and heuristic algorithms include greedy search and graph search algorithms and bio-inspired algorithms. Among them, STC [5,6,7] and bio-inspired neural networks [8,9] fail to take into account the limitations of motion characteristics and the requirements of area coverage in the turning process of USV. APF and graph search algorithms are usually combined with cow farming and spiral motion to optimize the coverage path, but APF [10,11] cannot meet the requirement of area coverage in the obstacle avoidance process. Graph search algorithms [12,13,14], such as the Dijkstra algorithm and the A-star algorithm, need to obtain global information and are not suitable for dynamic local path planning in USV. The Bug series algorithm is similar to the insect climbing strategy, which does not occur when the distance between the USV and the obstacle exceeds the sensor detection range, resulting in missing area coverage. In addition, the Bug algorithm does not need to obtain global information; it only needs to use sensor information to bypass obstacles.
The key prerequisite for global path planning is to obtain prior environmental information; on the contrary, local path planning only uses sensor information to achieve obstacle avoidance. Considering the actual environment at sea, it is difficult for USV to complete the search task only relying on global path planning, and it will increase the computing time only by local path planning [15]. Therefore, the main idea of sea search path planning proposed by this paper is to first plan the global path according to the static environment information, and when encountering unknown obstacles, the Bug algorithm is used to plan the local dynamic path according to the sensor detection information.
The Bug algorithm was first proposed by Lumelkys and Stepanov [16], who regarded the robot as a mass point and introduced a concept called hit-point. The robot starts to bypass the obstacles at the impact point when there is no barrier between it and the target, then leaves the obstacle at the target point. But the algorithm has some cases, such as facing overlapping obstacles, where the goal is unreachable. Meanwhile, they [16] proposed the Bug1 algorithm. When encountering an obstacle, the robot first explores the border of the obstacle while recording the position of the exit point. When encountering the original hit-point again, it moves to the leave-point and leaves the obstacle. The Bug1 algorithm needs to go around the obstacle, which will probably increase needless path costs. Therefore, the Bug2 algorithm [17] was proposed, which sets a virtual straight line called M-line from the beginning point to the target point. The robot follows the obstacle border and leaves the obstacle when meeting the M-line again, compared with the Bug1 algorithm, which greatly reduces the path cost. But the implementation of these algorithms requires the robot to make physical contact with the obstacle to obtain the hit point.
The sensor enables the robot to sense obstacles at a certain range, thereby avoiding direct collisions with obstacles. Lumelsky and Skewis [18] proposed the VisBug algorithm based on the range sensor, which still follows the M-line strategy of the Bug2 algorithm and bypasses obstacles through the detection of the sensor. Kamon et al. [19] proposed the TangentBug algorithm. At the maximum range of sensing detection, the border of the detected obstacle is expressed by constructing a local tangent graph (LTG). It follows the border of an obstacle while planning the path from the current moment to the goal point, which shortens the path length. Based on the TangentBug algorithm, Xu et al. [20] developed the InsertBug algorithm, which combines the distance sensor data with the security radius and describes and stores paths in the form of a vector by calculating the middle point to re-plan the path and obtain the shortest path. Buniyamin et al. [21] proposed the PointBug algorithm, which introduces trigonometric functions to generate target turning points on the outer perimeter of the obstacle area. By doing so, it shortens the path from the starting point to the target. However, due to the influence of determining acute and obtuse angles, this algorithm requires high positioning accuracy based on trigonometric output.
Furthermore, to improve the efficiency of the algorithm and reduce the path cost, many scholars combine the Bug algorithm with other methods to propose a series of Bug family algorithms. Lee et al. [22] proposed the FuzzyBug algorithm, which is equipped with two sensors. According to the fuzzy membership function, it is determined to follow the left or right border of the obstacle to improve efficiency. Xu [23] proposed the RandomBug algorithm, which is highly correlated with rapidly-exploring random trees. When detecting obstacles, by generating random points at the detection zone of the sensor, it selects the best point and generates a motion vector towards the point, by which to shorten the path length. Zhu et al. [24] proposed the Distance Histogram Bug (DH-Bug), which designed a new pattern and conversion condition so that it could deal with unknown mobile obstacles in a dynamic environment. Jiang et al. [25] put forward a BioBug algorithm based on the principle of neuroethological behavior, using the biological antenna model to describe the interested detected area, thereby reducing the burden of calculation and path length. Athanasios et al. [26] proposed a Ladybug algorithm based on intensified localization that, using the received signal strength indication (RSSI) of the electromagnetic signal, can accurately calculate the label location of the signal, thereby improving the smoothness of the path. Xing et al. [27] ameliorated the Bug algorithm by constructing a stereotype function based on a relative velocity, which used the cumulative changes in the inner and outer angles and reset points while following the wall and redesigned the conditions of state switching to improve the position deviation phenomenon due to the series noise.
Previous research works related to Bug algorithms are shown in Table 2. In summary, the current Bug algorithm family has a wide range of research on the path planning of mobile robots and driverless vehicles. However, it is difficult for USV to directly use these Bug algorithms to finish maritime search path planning.
The main purpose of this paper is to realize the USV search task at sea when the target location is unknown, that is, to cover the search area. Considering the aforementioned research characteristics, this paper proposes a maritime search path planning method for the USV based on an improved Bug algorithm. The innovation of this paper is to adopt double-layer path planning for the search area coverage of USV, and a multi-mode selection strategy for bypassing obstacles is proposed. The main contributions of this paper are summarized as follows:
(1)
To ensure USV safety during the obstacle avoidance process, set up the safe expansion area of the USV and, considering the characteristics of USV operation and behavior, optimize the advance direction of the traditional Bug algorithm.
(2)
In the path planning process, use the Bezier curve to smooth the generated path points. The smooth path is in line with the turning restraint of USV and is easier to control.
(3)
The different bypassing modes are selected for obstacles at different boundaries to meet the requirements of area coverage and reduce path costs.
The structure of this paper is as follows: Section 2 introduces the theoretical knowledge of this paper, including the principles of the USV model, the environment model, and the traditional Bug algorithm. Section 3 introduces the principles of the global path based on parallel line-based scanning and the implementation of the dynamic path based on improving the Bug algorithm. Section 4 analyzes the results of the improved Bug multi-mode simulation compared with the traditional Bug algorithm and verifies the effectiveness of the proposed algorithm. Section 5 sums up the contributions of this paper.

2. Materials and Methods

Before constructing the model of USV, this paper makes the following assumptions:
  • The USV is regarded as a rigid body and possesses a uniform mass distribution.
  • Ignore the influence of the curvature of the earth and regard the sea surface as a plane.
  • Ignore the change in the Z-axis direction; the USV moves in the 2D plane.
  • Do not consider the effect of wind and waves on the sea search of the USV.
  • Ignore the positioning error of the USV; the sensor can accurately sense information about the obstacles.

2.1. USV Motion Planning Model

2.1.1. The Dynamics Model of USV

This paper establishes two coordinate systems for the USV, as shown in Figure 1, which include the hull coordinate system and the global coordinate system. The hull coordinate system is a right-angle coordinate system fixed on the hull, which takes the symmetry point of USV as the origin point of the USV coordinate system and moves with USV. The X-axis direction is set to the sailing direction of USV, the Y-axis direction is the direction of the X-axis clockwise rotation at 90°, and the Z-axis direction is vertical on the horizontal plane. The global coordinate system is an inertial coordinate system fixed on the surface of the earth; its position can be arbitrarily selected. It is stipulated that the X-axis is in the horizontal plane and that its direction can be selected at will, which, once selected, is fixed. The Y-axis direction is the direction of the X-axis clockwise rotation at 90°, and the Z-axis direction is vertical on the horizontal plane.
The motion equation of the USV model [28] can be shown as follows:
{ x = μ cos ψ v sin ψ y = μ sin ψ + v cos ψ ψ = r
where x is the longitudinal displacement of the USV; y is the lateral displacement of the USV; μ is the longitudinal velocity of the USV; ν is the lateral velocity of the USV; ψ is the yaw angle of the USV; r is the yaw angular velocity.

2.1.2. The Model of Environment

For the model of the static environment, we first obtain the electronic sea map information of the search area, and then binarization processing is used to deal with the image of the sea map, as shown in Figure 2. The amount of image data are reduced through the binarization processing, and the two-dimensional matrix of the image is composed of 0 and 1. The black of 0 is the obstacle area, and the black of 1 is the free space area.
For the model of a dynamic environment, we use the sensor to obtain information about the distance and relative position between the USV and targets or obstacles. As shown in Figure 3, the coordinate data of the target or obstacles at the sensor coordinate system is obtained through the sensor, and then the global coordinates are obtained through a series of transformations of coordinates.
The process of obtaining the global coordinates is as follows:
(1)
( x r , 0 ) is the coordinate position of the sensor in the hull coordinate system. During the navigation process of the USV, the position of the sensor coordinate system is fixed to the hull coordinate system, and the targets or obstacles are sensed by the sensor. Assuming ( d , θ 1 ) is the position of the obstacle at the sensor coordinate system, ( x , y ) is the position at the hull coordinate system, the corresponding transformation formula for coordinate systems is as follows:
{ x = d cos θ 1 + x r y = d sin θ 1
(2)
( x u , y u ) is the global position of USV. The obstacle position in the global coordinate system is obtained according to the following transformation formula:
{ x b = x u + x r cos ( α u + π 2 ) + d cos ( α u + π 2 + θ 1 ) y b = y u + x r sin ( α u + π 2 ) + d sin ( α u + π 2 + θ 1 )
where α u is the angle between the sailing direction of the USV and the X-axis direction of the global coordinate system.

2.2. Traditional Bug Algorithm

The Bug algorithm includes two basic behaviors: when not encountering obstacles, move along the line to the target; when encountering obstacles, bypass the obstacles, use a certain judgment strategy to leave the obstacles, and continue to go straight. Through the conversion of two behaviors, the Bug algorithm can adjust the path planning strategy in real-time to reach the end point. The main difference between different Bug algorithms is that their obstacles bypassing strategies and behavioral switching strategies. The following introduces the Bug1 algorithm and Bug2 algorithm, which are the infrastructure algorithms of this paper.

2.2.1. Bug1 Algorithm

The basic principle of the Bug1 algorithm [16] is that when not encountering obstacles, the shortest path is obtained along the line to the target; when encountering obstacles, it first bypasses the entire border of the obstacle while getting the leave-point, which is the closest position to the target point, then leaves obstacles from the leave-point. The schematic diagram of the Bug1 algorithm is shown in Figure 4a. The process is as follows:
(1)
Set the start point and the goal point as q s t a r t and q g o a l .
(2)
When not encountering obstacles, the USV moves along the line to the goal point.
(3)
When encountering obstacles, the position in which the USV hits the obstacle for the first time is called the hit-point q 1 H , then the USV detours the entire border of the obstacle and returns to the hit-point while recording the closest point to the goal point during the process of detouring, which is called the leave-point q 1 L .
(4)
The USV moves to q 1 L , and leaves the obstacle from q 1 L and moves to the target along the line again.

2.2.2. Bug2 Algorithm

The basic idea of the Bug2 algorithm [17] is similar to the Bug1 algorithm but optimizes the part about bypassing obstacles, which sets a virtual straight line called M-Line. When encountering obstacles, the USV follows the border of the obstacle and then leaves the obstacle when it meets the M-line on the other side again. The schematic diagram of the Bug2 algorithm is shown in Figure 4b. The process is as follows:
(1)
Set q s t a r t and q g o a l , the line connecting q s t a r t with q g o a l is called M-line, which does not change with the movement of the USV.
(2)
When not encountering obstacles, the USV moves along the line to the goal point.
(3)
When encountering obstacles, the position where the USV meets the M-line closer to the goal point is called the leave-point q 1 L .
(4)
The USV moves to q 1 L and leaves the obstacle from q 1 L and moves to the target along the line again.

3. Search Path Planning

This paper uses parallel line scanning search, when obstacles are encountered in the search process, Bug algorithm is used to bypass obstacles. The flow chart of sea search path planning for the USV is shown in Figure 5.

3.1. Global Path Planning Based on Parallel Line Scanning Search Methods

According to the “National Maritime Search and Rescue Manual” [29], considering the maneuverability and detectivity of USVs, the main search method is visual search, including fan-shaped search, expansion square search, trail line search, parallel line search, and cross line search. When the accurate position of the search target cannot be known, it is usually necessary to evenly cover the large search area, where parallel line scanning is the most effective method. The parallel line search first selects a point at the area boundary as the starting point; the distance between the first search route and the long side of the search is half of the route spacing; then it keeps a route spacing for the parallel search.
Based on the parallel line scanning search, the global path should make the search direction of USV consistent or opposite to the direction of search area width, which can complete area coverage with the least number of turns. We set the spacing width between the two parallel lines to be the width of the inner square of the detection range, called D, which is also the scanning width of the USV along the parallel line, as shown in Figure 6.

3.2. Dynamic Path Planning Based on Improved Bug Algorithm

The traditional Bug algorithm is not suitable for the search path planning of USV. In the following part, the implementation principle and method of the improved Bug algorithm are introduced in detail.

3.2.1. Improved Bug Algorithm Based on the Characteristics of USV

(1)
Set the safety expansion area of the USV
Considering the complex and changeable nature of the actual navigation environment, the USV cannot simply be regarded as a mass point. To ensure the safety of the USV during the process of bypassing obstacles, we set a safe expansion area for the USV to ensure that the distance between the USV and obstacle d ( X , X o ) is always greater than the safety distance D s a f e , as shown in Figure 7.
(2)
Optimize the movement direction of the USV
The traditional Bug algorithm does not limit the movement directions in the process of following the border of an obstacle; the robot can easily perform complex actions such as braking and turning in place, but the USV generally does not choose astern operation during sailing [30]. Therefore, considering the manipulation characteristics of the USV, this paper optimizes the forward direction of the algorithm during bypassing obstacles and removes the astern direction, as shown in Figure 8.

3.2.2. Multi-Modes Selection Strategy for Bypassing Obstacles

To meet the requirement of covering the search area when the USV bypasses obstacles, this paper proposes the Multi-modes selection strategy of bypassing obstacles and adopts different bypassing modes for obstacles with different border widths. The USV detects the border lengths L y _ r i g h t and L y _ l e f t obstacles on both sides of the Y-axis of the hull coordinate system through the sensor, which are abbreviated as L r and L l , as shown in Figure 9.
As shown in Figure 9a, the lengths of the obstacle border L y _ r i g h t > L y _ l e f t and L y _ r i g h t > D/2, in this case, the USV can meet the requirement of area coverage by choosing to bypass the obstacle on the left; as shown in Figure 9b, the lengths of the obstacle border L y _ r i g h t < L y _ l e f t and L y _ l e f t > D/2, in this case, the USV can meet the requirement of area coverage by choosing to bypass the obstacle on the right; as shown in Figure 9c, L y _ r i g h t < D/2 and L y _ l e f t < D/2, in this case, the USV needs to bypass the obstacle for a week to meet search area coverage.
By judging the relationship between the width of the obstacle border and the scanning width of the USV along the parallel line, the USV takes different modes to bypass obstacles. The process of multi-mode selection strategies for bypassing obstacles is as follows:
(1)
Set the planned parallel route as M-Line, and M-Line does not change as the USV moves.
(2)
When not encountering obstacles, the USV moves in the straight line along the M-line.
(3)
When encountering obstacles, by judging the relationship between L y _ r i g h t , L y _ l e f t and D/2, the USV adopts different modes to bypass obstacles.
Mode1: L y _ r i g h t > L y _ l e f t and L y _ r i g h t > D/2
The USV selects to turn left to bypass the obstacle and leaves the obstacle when it meets M-Line again.
Mode2: L y _ r i g h t < L y _ l e f t and L y _ l e f t > D/2
The USV selects to turn on the right to bypass the obstacle and leaves the obstacle when it meets M-Line again.
Mode3: L y _ r i g h t < D/2 and L y _ l e f t < D/2
The USV bypasses the obstacle and then returns to the starting point while recording the length of the path before and after meeting M-Line. Compared with the length of the two sections, the USV sails along the shorter path and leaves the obstacle when it meets M-Line again.
(4)
The USV leaves the obstacle and resumes the original planned parallel line path.
The flowchart of the multi-mode Bug algorithm is shown in Figure 10. The pseudo-code for the improved Bug algorithm is shown in Algorithm 1.
Algorithm 1: The improved Bug algorithm of USV
Jmse 11 02320 i001

3.3. Smooth the Path Points

The smoothness of the path is a principal element influencing the sailing of the USV; the feasible path suitable for the sailing of the USV must meet the continuous changes in orientation and curvature [31]. Therefore, it is necessary to use the smoothing algorithm to fit the discrete path points and generate a smooth path that meets the constraints of the manipulation characteristics of USV. The common path smoothing methods include graph-based curve generation methods and function-based curve generation methods. The graph-based curve generation methods are composed of straight lines, arcs, and circles, including the Dubins curve [32] and Reeds-Shepp curve [33], but the problem of curvature discontinuity is faced when a circular arc combines with two straight lines. The function-based curve generation methods mainly include Clothoids [34], Bezier [35], and B-spline [36]. Among them, path smoothing based on the Bezier curve has many advantages, such as simple calculation and continuous curvature, which is an appropriate method to smooth the path points for USV.
In the actual sailing process, the path of the USV is composed of a series of steering points. Considering the constraints of USV, the path should try to maintain the continuity of changes in the turning angle and the sailing direction. This paper uses the N-times Bezier curve to smooth the path points. The smoothed path makes the control of USV substantially guaranteed and meets the actual maneuverability. When the degree of the Bezier curve is N, which is shown in Equation (4) [35].
B ( k ; N ) = i = 0 N P i J N , k ( k )
where k is the intrinsic parameter, k [ 0 , 1 ] ; P i is control point, i [ 0 , N ] ; J N , k ( k ) is an N-basis polynomial of Bernstein.
The N-basis polynomial of Bernstein and the binomial coefficient are given by Equations (5) and (6).
J N , i ( k ) = ( N i ) k i ( 1 k ) N i
( N i ) = N ! i ! ( N i ) !

4. Simulation and Analysis

Some indicators, such as path length, smoothness, and safety, play an important role in the path planning of USV. Next, this paper analyzes the simulation of the improved algorithm from four angles: path length, smoothness, running time, and safety.

4.1. Improved Bug Algorithm Multi-Modes Simulation and Performance Comparison

The strategic basis of multi-modes is to select different bypass modes by judging the relationship between Ly-Right, Ly-Left, and D/2, which are differences in the way of bypassing obstacles and the judgment standard of leaving obstacles. Since Mode 1 and Mode 2 bypass obstacles in the same way, only Mode 1 and Mode 3 are described below. The simulation and analysis of the improved Bug algorithm multi-modes appear as follows:

4.1.1. Bypassing Obstacles in Mode 1

Set the starting point coordinates (31, 177), the end point coordinates (31, 30), and the radius of the safe expansion area of the USV as two units of length. The path length, bypassing length, and running time of the traditional Bug algorithm, the Bug algorithm after expansion, and the improved Bug algorithm are shown in Table 3.
Table 3 shows that the path length obtained by the improved Bug algorithm is reduced by 18.7% compared with the traditional Bug algorithm, and the running time is reduced by 11.1%. The path length obtained by the improved Bug algorithm is greatly shortened, and the time spent bypassing obstacles is greatly shortened. The USV can safely bypass the obstacle on Mode 1. The paths generated by the three Bug algorithms are shown in Figure 11. The improved Bug algorithm maintains a safe distance from the obstacle to bypass the obstacle along the boundary of the obstacle. The path bypassing the obstacles is shown in Figure 12. The path generated by the improved Bug algorithm effectively improves the path oscillation phenomenon of the traditional Bug algorithm.
The variance and standard deviation are common quantitative indicators describing data differences and fluctuations. The smaller the variance and the standard deviation, the smaller the data fluctuations, so the variance and the standard deviation of angles between the road points and the USV heading angles can be used to evaluate the path smoothness. The variance and standard deviation are given by Equations (7) and (8) [37].
S 2 = i = 1 N ( X μ ) 2 N
S = i = 1 N ( X μ ) 2 N
where, S2 is the overall variance; X is variate; μ is the overall average; N is the overall number of examples.
The evaluation indicators of the path smoothness are shown in Table 4. Table 4 shows the variance and the standard deviation of the angles between the road points. The heading angles of USV after path smoothing by the Bezier curve are less than before path smoothing, so the obstacle avoidance process is smoother. The path after smoothing by the Bezier curve conforms to the corner angle restriction of USV, as shown in Figure 13.
Figure 14 and Figure 15 show that the corner angles of the path points obtained by the improved Bug algorithm are within the [90, 180] range, and the average corner angles before and after smoothing are 163.13° and 178.65°, respectively. The corner angles of the path points after smoothing conform to the corner angle restriction of the USV, and the heading angles of the USV after smoothing change continuously, which is in line with the movement characteristics of the USV.

4.1.2. Bypassing Obstacle in Mode 3

Set the starting point coordinates (185, 143), the end point coordinates (185, 298), and the radius of the safe expansion area of the USV as two units of length. The path length and running time of the traditional Bug algorithm, the Bug algorithm after expansion, and the improved Bug algorithm are shown in Table 5.
Table 5 shows that the path length obtained by the improved Bug algorithm is reduced by 11.1% compared with the traditional Bug algorithm, and the running time is reduced by 13.0%. The path length obtained by the improved Bug algorithm is greatly shortened, and the time of bypassing obstacle a is greatly shortened, so the USV can safely bypass the obstacles on Mode 3. The paths generated by the three Bug algorithms are shown in Figure 16. The improved Bug algorithm bypasses the obstacle along the boundary and maintains a safe distance from the obstacle. Figure 17 shows the path that bypasses the obstacles. The path generated by the improved Bug algorithm effectively improves the path oscillation phenomenon of the traditional Bug algorithm.
The evaluation indicators of the path smoothness are shown in Table 6. Table 6 shows that the variance and the standard deviation of angles between the road points and the heading angles of USV after path smoothing by the Bezier curve are less than before path smoothing, so the obstacle avoidance process is smoother. The path after smoothing by the Bezier curve conforms to the corner angle restriction of USV, as shown in Figure 18.
Figure 19 and Figure 20 show that the corner angles of the path points obtained by the improved Bug algorithm are within the [90, 180] range, and the average corner angles before and after smoothing are 148.27° and 177.98°, respectively. The corner angles of the path points after smoothing conform to the corner angle restriction of the USV, and the heading angles of the USV after smoothing change continuously, which is in line with the movement characteristics of the USV.

4.2. Global Path Planning for USV

To verify the applicability of the maritime search path planning method of USV based on the improved Bug algorithm, this paper selects the seas of Dalian in China for the simulation. Select the sea area of Dalian as 121.526766° E~121.542361° E, 38.833196° N~38.821056° N. The USV simulation experimental parameters are settled concerning Zhilong No.1 USV, as shown in Figure 21. The specific parameters are shown in Table 7.
The path planning of the sea area simulation is shown in Figure 22, and the overall path planned by the maritime search path planning method in this paper is successful. There is no problem with big corner angles and path oscillation on the planning path, which meets the movement characteristics of USV and meets the requirements of area coverage.

4.3. Comparison Experiment

The improved Bug has been tested using Matlab simulations for convex and concave environments and has been compared with other area coverage methods, including APF and RRT. We have also used big O to represent the complexity of the proposed algorithm and compared the complexity with APF and RRT [4], as shown in Table 8. The complexity analysis of the improved Bug algorithm is shown in Appendix A.
The parameters are set as follows: the safe distance of the USV is two units of length, and the detection distance of the USV is eighty units of length. Area coverage is the standard to evaluate whether the search task is completed, and coverage efficiency is to measure the coverage efficiency of the algorithm in the given area based on area coverage. Therefore, considering the applicability of the algorithm in different scenarios, area coverage is the primary reference standard for selecting an algorithm suitable for marine search.
For the problem of search path planning at sea, the area coverage guarantees whether people overboard can be rescued. The artificial potential field method has strong obstacle avoidance ability, but the path coverage depends on the potential field design and parameter setting when it is applied to the area coverage. The artificial potential field method cannot guarantee the distance between obstacles in the obstacle avoidance process, making it prone to missing areas and failing to achieve complete coverage. At the same time, RRT can be explored over a large range, but its area length and path coverage are mainly affected by the distribution of sampling points and the generation strategy, and the distance between obstacles cannot be guaranteed to be within the detection range. The simulation results show that both APF and RRT are not only applicable to the USV sea search scenarios.
As can be seen from Figure 23, the improved Bug algorithm finds a path from the start point to the end point by moving along the contour boundary of the obstacle. In this paper, the Bezier curve is introduced for path smoothing to solve the problem of oscillation at the boundary of obstacles. The area length of the Bug algorithm mainly depends on the shape and distribution of obstacles, but it can ensure complete coverage of the area, which is fully proved by simulation and comparison experiments.

5. Conclusions

Aiming at the problem of maritime searching for USV in complex environments, this paper proposes a search path planning method for USV based on an improved Bug algorithm. The Bug algorithm is improved based on the maneuverability of the USV by setting the safety expansion area and optimizing the forward direction. To meet the requirement of covering the search area when USV circumnavigates obstacles, this paper proposes a multi-mode selection strategy for bypassing obstacles. By judging the relationship between obstacle boundary length and USV path scanning width, different modes are adopted for obstacles with different boundary widths. Finally, the simulation shows that the improved Bug algorithm greatly shortens the path length and the running time, and the path obtained by the improved Bug algorithm effectively improves. After smoothing by the Bezier curve, the path conforms to the restriction of corner angles and the movement characteristics of the USV. This simulation of search path planning verifies that the proposed algorithm can effectively and accurately plan the search path.

Author Contributions

Conceptualization, Y.Y., X.W. and Q.J.; Formal analysis, X.W. and Y.Y.; Funding acquisition, Y.Y. and Q.J.; Investigation, X.W. and Y.Y.; Methodology, X.W., Y.Y. and Q.J.; Project administration, X.W.; Software, X.W.; Supervision, Y.Y.; Validation, X.W. and Y.Y.; Writing the original draft, X.W.; Writing—review and editing, X.W. and Y.Y. All authors have read and agreed to the published version of the manuscript.

Funding

This work is supported by the Ship Maneuvering Simulation in Yunnan Inland Navigation, grant number 851333J; 2022 Liaoning Provincial Science and Technology Plan (Key) Project: R&D and Application of Autonomous Navigation System for Smart Ships in Complex Waters, grant number 2022JH1/10800096; National Key R&D Program of China, grant number 2022YFB4301402; the Fundamental Research Funds for the Central Universities, grant number 3132023139.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Data are contained within the article.

Acknowledgments

The author would like to thank the reviewers for their comments on improving the quality of this paper.

Conflicts of Interest

The authors declare no conflict of interest.

Appendix A

The pseudo-code for the improved bug algorithm is as follows: To explain the algorithm, we need the following definitions.
G stands for goal point. S W F is a variable that determines if the wall-following is right-sided ( S W F = 1) or left-sided ( S W F = −1). R s e n stand for local sensor measurements. x g l o b a l stands for the global position estimate of the Bug Algorithm. d ( H , G ) p r e v stands for the previous distance of the hit-point to the goal point, and d ( x g l o b a l , G ) stands for the current distance to the goal point. L h p stand for a list of previously encountered hit points. v is the control output for the forward velocity of the robot and c v is the fixed velocity constant. ω is the control output for the heading of the USV and c ω is a fixed rate constant to control the speed of the USVs turns. P is a set of path costs. L y _ r i g h t and L y _ l e f t stand for the USV detecting the border lengths of obstacles on both sides of the Y-axis of the hull coordinate system through the sensor. Wall _ F o l l w i n g ( c v , c ω , S W F , R s e n ) is set as [38].
Using O-notation, we can often describe the running time of the improved Bug algorithm merely by inspecting the algorithm’s overall structure. We use a tree structure to make this clearer, as shown in Figure A1. The tree structure of Step 3 is shown in Figure A2. For the worst case, the input loops N times, and each time needs to enter a different state by judgment, so the time complexity C is O ( n ) . For the best case, the input loops one time, so the time complexity C is O ( 1 ) .
Figure A1. The tree structure of the improved Bug algorithm.
Figure A1. The tree structure of the improved Bug algorithm.
Jmse 11 02320 g0a1
Figure A2. The tree structure of Step 3.
Figure A2. The tree structure of Step 3.
Jmse 11 02320 g0a2

References

  1. Campbell, S.; Naeem, W.; Irwin, G.W. A Review on Improving the Autonomy of Unmanned Surface Vehicles through Intelligent Collision Avoidance Manoeuvres. Annu. Rev. Control 2012, 36, 267–283. [Google Scholar] [CrossRef]
  2. Jin, J.; Zhang, J.; Liu, D.; Shi, J.; Wang, D.; Li, F. Vision-Based Target Tracking for Unmanned Surface Vehicle Considering Its Motion Features. IEEE Access 2020, 8, 132655–132664. [Google Scholar] [CrossRef]
  3. Park, J. Improved Collision Avoidance Method for Autonomous Surface Vessels Based on Model Predictive Control Using Particle Swarm Optimization. IJFIS 2021, 21, 378–390. [Google Scholar] [CrossRef]
  4. Tan, C.S.; Mohd-Mokhtar, R.; Arshad, M.R. A Comprehensive Review of Coverage Path Planning in Robotics Using Classical and Heuristic Algorithms. IEEE Access 2021, 9, 119310–119342. [Google Scholar] [CrossRef]
  5. Luo, H.; Lin, H.; Zhu, T.; Kang, Z. Complete Coverage Path Planning of UUV for Marine Mine Countermeasure Using Grid Division and Spanning Tree. In Proceedings of the 2019 Chinese Control And Decision Conference (CCDC), Nanchang, China, 3–5 June 2019; pp. 5016–5021. [Google Scholar]
  6. Gao, G.-Q.; Xin, B. A-STC: Auction-Based Spanning Tree Coverage Algorithm Formotion Planning of Cooperative Robots. Front. Inf. Technol. Electron. Eng. 2019, 20, 18–31. [Google Scholar] [CrossRef]
  7. Ranjitha, T.D.; Guruprasad, K.R. Pseudo Spanning Tree-Based Complete and Competitive Robot Coverage Using Virtual Nodes. IFAC-PapersOnLine 2016, 49, 195–200. [Google Scholar] [CrossRef]
  8. Luo, C.; Yang, S.X. A Bioinspired Neural Network for Real-Time Concurrent Map Building and Complete Coverage Robot Navigation in Unknown Environments. IEEE Trans. Neural Netw. 2008, 19, 1279–1298. [Google Scholar] [CrossRef]
  9. Cao, X.; Zhu, D.; Yang, S.X. Multi-AUV Target Search Based on Bioinspired Neurodynamics Model in 3-D Underwater Environments. IEEE Trans. Neural Netw. Learn. Syst. 2016, 27, 2364–2374. [Google Scholar] [CrossRef]
  10. Rostami, S.M.H.; Sangaiah, A.K.; Wang, J.; Liu, X. Obstacle Avoidance of Mobile Robots Using Modified Artificial Potential Field Algorithm. J. Wirel. Commun. Netw. 2019, 2019, 70. [Google Scholar] [CrossRef]
  11. Lin, X.; Wang, Z.-Q.; Chen, X.-Y. Path Planning with Improved Artificial Potential Field Method Based on Decision Tree. In Proceedings of the 2020 27th Saint Petersburg International Conference on Integrated Navigation Systems (ICINS), Saint Petersburg, Russia, 25–27 May 2020; pp. 1–5. [Google Scholar]
  12. Viet, H.H.; Dang, V.-H.; Laskar, M.N.U.; Chung, T. BA*: An Online Complete Coverage Algorithm for Cleaning Robots. Appl. Intell. 2013, 39, 217–235. [Google Scholar] [CrossRef]
  13. Choi, S.; Lee, S.; Viet, H.H.; Chung, T. B-Theta*: An Efficient Online Coverage Algorithm for Autonomous Cleaning Robots. J. Intell. Robot. Syst. 2017, 87, 265–290. [Google Scholar] [CrossRef]
  14. Dogru, S.; Marques, L. A*-Based Solution to the Coverage Path Planning Problem. In Proceedings of the ROBOT 2017: Third Iberian Robotics Conference, Porto, Portugal, 20–22 November 2019; Ollero, A., Sanfeliu, A., Montano, L., Lau, N., Cardeira, C., Eds.; Springer International Publishing: Cham, Switzerland, 2018; pp. 240–248. [Google Scholar]
  15. Chen, Y.; Bai, G.; Zhan, Y.; Hu, X.; Liu, J. Path Planning and Obstacle Avoiding of the USV Based on Improved ACO-APF Hybrid Algorithm With Adaptive Early-Warning. IEEE Access 2021, 9, 40728–40742. [Google Scholar] [CrossRef]
  16. Lumelsky, V.; Stepanov, A. Dynamic Path Planning for a Mobile Automaton with Limited Information on the Environment. IEEE Trans. Automat. Contr. 1986, 31, 1058–1063. [Google Scholar] [CrossRef]
  17. Lumelsky, V.; Stepanov, A. Path-Planning Strategies for a Point Mobile Automaton Moving amidst Unknown Obstacles of Arbitrary Shape. Algorithmica 1987, 2, 403–430. [Google Scholar] [CrossRef]
  18. Lumelsky, V.; Skewis, T. A Paradigm for Incorporating Vision in the Robot Navigation Function. In Proceedings of the 1988 IEEE International Conference on Robotics and Automation, Philadelphia, PA, USA, 24–29 April 1988; pp. 734–739. [Google Scholar]
  19. Kamon, I.; Rivlin, E.; Rimon, E. A New Range-Sensor Based Globally Convergent Navigation Algorithm for Mobile Robots. In Proceedings of the IEEE International Conference on Robotics and Automation, Minneapolis, MN, USA, 22–28 April 1996; Volume 1, pp. 429–435. [Google Scholar]
  20. Xu, Q.-L.; Tang, G.-Y. Vectorization Path Planning for Autonomous Mobile Agent in Unknown Environment. Neural Comput. Appl. 2013, 23, 2129–2135. [Google Scholar] [CrossRef]
  21. Buniyamin, N.; Wan Ngah, W.A.J.; Mohamad, Z. PointsBug versus TangentBug Algorithm, a Performance Comparison in Unknown Static Environment. In Proceedings of the 2014 IEEE Sensors Applications Symposium (SAS), Queenstown, New Zealand, 18–20 February 2014; pp. 278–282. [Google Scholar]
  22. Lee, S.; Adams, T.M.; Ryoo, B. A Fuzzy Navigation System for Mobile Construction Robots. Autom. Constr. 1997, 6, 97–107. [Google Scholar] [CrossRef]
  23. Xu, Q.-L. RandomBug: Novel Path Planning Algorithm in Unknown Environment. Open Electr. Electron. Eng. J. 2014, 8, 252–257. [Google Scholar] [CrossRef]
  24. Zhu, Y.; Zhang, T.; Song, J.; Li, X. A New Bug-type Navigation Algorithm for Mobile Robots in Unknown Environments Containing Moving Obstacles. Ind. Robot Int. J. 2012, 39, 27–39. [Google Scholar] [CrossRef]
  25. Jiang, J.; Tu, D.; Xu, S.; Zhao, Q. Cognitive Response Navigation Algorithm for Mobile Robots Using Biological Antennas. Robotica 2014, 32, 743–756. [Google Scholar] [CrossRef]
  26. Lentzas, A.; Vrakas, D. LadyBug. An Intensity Based Localization Bug Algorithm. In Proceedings of the 2020 25th IEEE International Conference on Emerging Technologies and Factory Automation (ETFA), Vienna, Austria, 8–11 September 2020; pp. 682–689. [Google Scholar]
  27. Xing, Q.; Xu, S.; Wang, H.; Wang, J.; Zhao, W.; Xu, H. Path Planning of a Mobile Robot Using an Improved Mixed-Method of Potential Field and Wall Following. Int. J. Adv. Robot. Syst. 2023, 20, 172988062311691. [Google Scholar] [CrossRef]
  28. Sonnenburg, C.R.; Woolsey, C.A. Modeling, Identification, and Control of an Unmanned Surface Vehicle: Modeling, ID, and Control of a USV. J. Field Robot. 2013, 30, 371–398. [Google Scholar] [CrossRef]
  29. China Maritime Search and Rescue Center; Tianjin Maritime Search and Rescue Center; Dalian Maritime University. National Maritime Search and Rescue Manual; Dalian Maritime University Press: Dalian, China, 2011. [Google Scholar]
  30. Bertaska, I.R.; Shah, B.; Von Ellenrieder, K.; Švec, P.; Klinger, W.; Sinisterra, A.J.; Dhanak, M.; Gupta, S.K. Experimental Evaluation of Automatically-Generated Behaviors for USV Operations. Ocean Eng. 2015, 106, 496–514. [Google Scholar] [CrossRef]
  31. Yang, K.; Sukkarieh, S. An Analytical Continuous-Curvature Path-Smoothing Algorithm. IEEE Trans. Robot. 2010, 26, 561–568. [Google Scholar] [CrossRef]
  32. Jacobs, P.; Canny, J. Planning Smooth Paths for Mobile Robots. In Proceedings of the 1989 International Conference on Robotics and Automation, Scottsdale, AZ, USA, 14–19 May 1989; pp. 2–7. [Google Scholar]
  33. Sabelhaus, D.; Röben, F.; Zu Helligen, L.P.M.; Schulze Lammers, P. Using Continuous-Curvature Paths to Generate Feasible Headland Turn Manoeuvres. Biosyst. Eng. 2013, 116, 399–409. [Google Scholar] [CrossRef]
  34. Chen, Y.; Cai, Y.; Zheng, J.; Thalmann, D. Accurate and Efficient Approximation of Clothoids Using Bézier Curves for Path Planning. IEEE Trans. Robot. 2017, 33, 1242–1247. [Google Scholar] [CrossRef]
  35. Kawabata, K.; Ma, L.; Xue, J.; Zhu, C.; Zheng, N. A Path Generation for Automated Vehicle Based on Bezier Curve and Via-Points. Robot. Auton. Syst. 2015, 74, 243–252. [Google Scholar] [CrossRef]
  36. Maekawa, T.; Noda, T.; Tamura, S.; Ozaki, T.; Machida, K. Curvature Continuous Path Generation for Autonomous Vehicle Using B-Spline Curves. Comput. Aided Des. 2010, 42, 350–359. [Google Scholar] [CrossRef]
  37. Puig, D.; Garcia, M.A.; Wu, L. A New Global Optimization Strategy for Coordinated Multi-Robot Exploration: Development and Comparative Evaluation. Robot. Auton. Syst. 2011, 59, 635–653. [Google Scholar] [CrossRef]
  38. McGuire, K.N.; De Croon, G.C.H.E.; Tuyls, K. A Comparative Study of Bug Algorithms for Robot Navigation. Robot. Auton. Syst. 2019, 121, 103261. [Google Scholar] [CrossRef]
Figure 1. USV coordinate system.
Figure 1. USV coordinate system.
Jmse 11 02320 g001
Figure 2. The model of the static environment. (a) the sea map; (b) the model of the environment after binarization processing.
Figure 2. The model of the static environment. (a) the sea map; (b) the model of the environment after binarization processing.
Jmse 11 02320 g002
Figure 3. Transformations of coordinates.
Figure 3. Transformations of coordinates.
Jmse 11 02320 g003
Figure 4. Bug algorithm schematic diagram. (a) Bug1 algorithm; (b) Bug2 algorithm.
Figure 4. Bug algorithm schematic diagram. (a) Bug1 algorithm; (b) Bug2 algorithm.
Jmse 11 02320 g004
Figure 5. The flow chart of sea search path planning for the USV.
Figure 5. The flow chart of sea search path planning for the USV.
Jmse 11 02320 g005
Figure 6. Set the spacing width between the two parallel lines.
Figure 6. Set the spacing width between the two parallel lines.
Jmse 11 02320 g006
Figure 7. Set up the safety expansion area of the USV.
Figure 7. Set up the safety expansion area of the USV.
Jmse 11 02320 g007
Figure 8. Optimize the movement direction of the USV. (a) the traditional Bug algorithm; (b) the improved Bug algorithm. Grey areas stand for unexplored areas; blue areas stand for detected areas; arrows stand for the movement directions.
Figure 8. Optimize the movement direction of the USV. (a) the traditional Bug algorithm; (b) the improved Bug algorithm. Grey areas stand for unexplored areas; blue areas stand for detected areas; arrows stand for the movement directions.
Jmse 11 02320 g008
Figure 9. The different cases of detecting the border of the obstacle. (a) L r > L l and L r > D/2; (b) L r < L l and L l > D/2; (c) L r < D/2 and L l < D/2.
Figure 9. The different cases of detecting the border of the obstacle. (a) L r > L l and L r > D/2; (b) L r < L l and L l > D/2; (c) L r < D/2 and L l < D/2.
Jmse 11 02320 g009
Figure 10. The flowchart of the obstacle avoidance algorithm of USV is based on the multi-mode Bug algorithm.
Figure 10. The flowchart of the obstacle avoidance algorithm of USV is based on the multi-mode Bug algorithm.
Jmse 11 02320 g010
Figure 11. The path is generated by the Bug algorithm. (a) the traditional Bug algorithm; (b) the Bug algorithm after expansion; (c) the improved Bug algorithm.
Figure 11. The path is generated by the Bug algorithm. (a) the traditional Bug algorithm; (b) the Bug algorithm after expansion; (c) the improved Bug algorithm.
Jmse 11 02320 g011
Figure 12. The path bypasses the obstacle generated by the Bug algorithm in mode 1.
Figure 12. The path bypasses the obstacle generated by the Bug algorithm in mode 1.
Jmse 11 02320 g012
Figure 13. The path after smoothing by the Bezier curve.
Figure 13. The path after smoothing by the Bezier curve.
Jmse 11 02320 g013
Figure 14. The angles between the path points.
Figure 14. The angles between the path points.
Jmse 11 02320 g014
Figure 15. The heading angles of USV relative to the Y-axis in mode 1.
Figure 15. The heading angles of USV relative to the Y-axis in mode 1.
Jmse 11 02320 g015
Figure 16. The path generated by the Bug algorithm. (a) the traditional Bug algorithm; (b) the Bug algorithm after expansion; (c) the improved Bug algorithm.
Figure 16. The path generated by the Bug algorithm. (a) the traditional Bug algorithm; (b) the Bug algorithm after expansion; (c) the improved Bug algorithm.
Jmse 11 02320 g016
Figure 17. The path bypasses the obstacle generated by the Bug algorithm in mode 3.
Figure 17. The path bypasses the obstacle generated by the Bug algorithm in mode 3.
Jmse 11 02320 g017
Figure 18. The path after the smoothness of the Bezier curve.
Figure 18. The path after the smoothness of the Bezier curve.
Jmse 11 02320 g018
Figure 19. The angles between path point.
Figure 19. The angles between path point.
Jmse 11 02320 g019
Figure 20. The heading angles of USV relative to the Y-axis in mode 3.
Figure 20. The heading angles of USV relative to the Y-axis in mode 3.
Jmse 11 02320 g020
Figure 21. Zhilong No.1 USV.
Figure 21. Zhilong No.1 USV.
Jmse 11 02320 g021
Figure 22. The actual sea area simulation path planning.
Figure 22. The actual sea area simulation path planning.
Jmse 11 02320 g022
Figure 23. Paths for 3 planners improved Bug, APF, and RRT. (a) environment 1; (b) environment 2.
Figure 23. Paths for 3 planners improved Bug, APF, and RRT. (a) environment 1; (b) environment 2.
Jmse 11 02320 g023
Table 1. Features of area coverage methods.
Table 1. Features of area coverage methods.
MethodClassEnvironmentAdvantageDisadvantage
Spanning tree coverage Classical
algorithm
GlobalHigh path coverage, simple structureNo considering node energy, cannot deal with dynamic change
Artificial
potential field
Classical
algorithm
LocalSimple principle, fast calculation speedUnable to control the distance to obstacles, easy to fall into local optimum
Bug
algorithms
Classical
algorithm
LocalEasy to implement, able to control the distance to obstaclesMaybe create unnecessary costs
Graph search algorithmsHeuristic-based
algorithms
GlobalBy calculating path cost, easy to find optimal path Excessive computing cost, not suitable for large areas
Bio-inspired
algorithms
Heuristic-based
algorithms
GlobalGood adaptability and parallelismEasy to fall into a dead zone
Table 2. Previous research work related to Bug algorithms.
Table 2. Previous research work related to Bug algorithms.
PaperBug AlgorithmClassificationObjectBypass Pattern
Lumelkys et al. [16]Bug1Contact BugRobotsCompletely bypass obstacle
Lumelkys et al. [17]Bug2Contact BugRobotsUse M-line + wall following
Lumelsky et al. [18]VisBugBug with sensorRobotsRange sensor + Use M-Line + Wall following
Kamon et al. [19]TangentBugBug with sensorMobile robotsRange sensor (0 − unlimited) + wall following + heuristic function
Xu et al. [20]InsertBugBug with sensorAutonomous mobile agentsRange sensor + vectorization path description + intermediate point
Buniyamin et al. [21]PointBugBug with sensorMobile robotsRange sensor + sudden point + trigonometric function
Lee et al. [22]FuzzyBugSpecial BugMobile construction robotsFuzzy logic controller (FLC) + tangent algorithm
Xu [23]RandomBugSpecial BugAutonomous mobile agentsRange sensor with safety radius + random intermediate points + vectors form
Zhu et al. [24]DH-BugSpecial BugHumanoid robotsDistance Histogram (DH) + three motion modes
Jiang et al. [25]BioBugSpecial BugMobile robotsBiological antenna model + cognitive response navigation
Athanasios et al. [26]LadybugSpecial BugRobotsLocal sensing, localization scheme + distance sensors + RSSI
Table 3. Performance comparison table of Bug algorithms in mode 1.
Table 3. Performance comparison table of Bug algorithms in mode 1.
Hit PointsPath Length
(Per Unit Length)
Bypassing Length
(Per Unit Length)
Running Time
(ms)
the traditional Bug algorithm(31, 159), (31, 52)206.1543161.154324.973
the Bug algorithm after expansion (31, 162), (31, 49)208.3970170.397025.274
the improved Bug algorithm(31, 162), (31, 49)167.5685130.568522.198
Table 4. The evaluation indicators of the path of smoothness of Bug algorithms in mode 1.
Table 4. The evaluation indicators of the path of smoothness of Bug algorithms in mode 1.
Standard Deviation of Points Angle (°)Variance of Points Angle (°^2)Standard Deviation of Course Angle (°)Variance of Course Angle (°^2)
before smoothing22.7714518.537631.89551017.3214
after smoothing1.70582.909912.8192164.3311
Table 5. Performance comparison table of Bug algorithms in mode 3.
Table 5. Performance comparison table of Bug algorithms in mode 3.
Hit PointsPath Length
(Per Unit Length)
Bypassing Length
(Per Unit Length)
Running Time
(ms)
the traditional Bug algorithm(185, 155), (185, 275)591.8284552.414245.256
the Bug algorithm after expansion (185, 155), (185, 275)607.0000571.000045.718
the improved Bug algorithm(185, 155), (185, 275)525.8600489.860039.392
Table 6. The evaluation indicators of the path of smoothness of Bug algorithms in mode 3.
Table 6. The evaluation indicators of the path of smoothness of Bug algorithms in mode 3.
Standard Deviation of Points Angle (°)Variance of Points Angle (°^2)Standard Deviation of Course Angle (°)Variance of Course Angle (°^2)
before smoothing30.3274919.751755.53193083.7897
after smoothing1.78203.175645.28552050.7763
Table 7. Zhilong No.1 USV parameters and simulation experiment parameters.
Table 7. Zhilong No.1 USV parameters and simulation experiment parameters.
Zhilong No.1 USV ParametersSimulation Experiment Parameters
size (length, width): 1.75 m, 0.5 mradar detection range: 200 m
radar detection range: 200 mthe scanning width of the USV: 283 m
Table 8. The computational complexities of each type of algorithm.
Table 8. The computational complexities of each type of algorithm.
AlgorithmTime Complexity ( C )
The improved Bug O ( 1 ) C O ( n )
APF O ( log n ) C O ( n )
RRT O ( n log n ) C O ( n 2 )
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

Wang, X.; Yin, Y.; Jing, Q. Maritime Search Path Planning Method of an Unmanned Surface Vehicle Based on an Improved Bug Algorithm. J. Mar. Sci. Eng. 2023, 11, 2320. https://doi.org/10.3390/jmse11122320

AMA Style

Wang X, Yin Y, Jing Q. Maritime Search Path Planning Method of an Unmanned Surface Vehicle Based on an Improved Bug Algorithm. Journal of Marine Science and Engineering. 2023; 11(12):2320. https://doi.org/10.3390/jmse11122320

Chicago/Turabian Style

Wang, Xiuling, Yong Yin, and Qianfeng Jing. 2023. "Maritime Search Path Planning Method of an Unmanned Surface Vehicle Based on an Improved Bug Algorithm" Journal of Marine Science and Engineering 11, no. 12: 2320. https://doi.org/10.3390/jmse11122320

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