Next Article in Journal
Optimising General Configuration of Wing-Sailed Autonomous Sailing Monohulls Using Bayesian Optimisation and Knowledge Transfer
Previous Article in Journal
Fracture Prediction of Steel-Plated Structures under Low-Velocity Impact
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Motion Planning of UAV for Port Inspection Based on Extended RRT* Algorithm

1
Logistics Engineering College, Shanghai Maritime University, Shanghai 201306, China
2
Naval Academy, Brest Naval, Lanveoc-Poulmic, BP 600, 29240 Brest Naval, France
3
School of Mechatronic Engineering, Guangdong Polytechnic Normal University, Guangzhou 510665, China
*
Author to whom correspondence should be addressed.
J. Mar. Sci. Eng. 2023, 11(4), 702; https://doi.org/10.3390/jmse11040702
Submission received: 12 February 2023 / Revised: 16 March 2023 / Accepted: 21 March 2023 / Published: 24 March 2023

Abstract

:
A suitable trajectory in a port inspection mission is important for unmanned aerial vehicles (UAVs). Motion planning can help UAVs quickly generate an optimal trajectory that meets the constraints. The motion planning of UAVs is achieved in this paper as follows: firstly, a collision detection (CD) function is applied that evaluates whether the bias_RRT* (rapidly exploring random tree) algorithm needs to be called. Secondly, an isosceles triangle optimization function optimizes the path. Next, a trajectory is generated based on the minimum snap trajectory method. Lastly, the bias_RRT* algorithm and the improved bias_RRT* algorithm are used in the two experimental scenes for path planning comparison, and trajectory planning is carried out. The results show that, in the improved method, the path length and calculation time are shortened, and the trajectory cost and trajectory deviation are also significantly reduced. Overall, it appears that a camera-equipped UAV under the proposed approach can accomplish monitoring tasks more effectively and safety in port environment.

1. Introduction

In the context of the rapid growth of international trade in maritime environments, it is crucial to ensure the orderly operation of ports. As an important transportation infrastructure, the port is necessary for regular inspection and maintenance [1]. The inspection task of civil infrastructure inspection (ports, bridges, ships, wind turbines, and airplanes.) is considered to be very important, because the lack of any details will affect the performance and integrity of the structure [2]. These structures generally have the following characteristics: manual inspections of hard-to-reach areas and inspections of various types of faults and exception. Therefore, conventional structural inspections are things that consume time and resources or, even worse, can cause inspectors to be in an unsafe environment. Therefore, it is necessary to perform inspection of the structure as efficiently and accurately as possible [3]. The continued development and production of unmanned aerial vehicles (UAVs) with increasingly advanced levels of autonomy have the potential to significantly reduce the occurrence of human error and greatly improve the safety, speed, and accuracy of inspections [4].
In recent years, an increasing number of studies have investigated the use of autonomous UAVs to inspect various structures such as wind turbines [5], high-rise structures [6], and large-scale photovoltaic farms [7]. In this paper, we target the inspection of a port, which is an infrastructure with a large area. One of the crucial factors for the automated inspection of structures using UAVs is the strategy employed to conduct a rapid and safe inspection. Given an a priori map and orderly detection waypoints, the UAV needs to take into account the sensor limitations and motion constraints of the drone to generate an optimized detection trajectory to detect the region of interest.
In this study, we present a method combining a path planning algorithm with a trajectory planning algorithm for detecting ports using a UAV. At the outset, our approach assumes the availability of an a priori map, which is represented using a grid map; meanwhile, a series of orderly detection points are given by manual detection experience. The main principle behind our approach is to generate a better collision-free path between multiple waypoints. We first apply a collision detection (CD) function that evaluates whether the bias_RRT* (rapidly exploring random tree) algorithm needs to be called. If not, such points are connected by a straight line. Compared with other path planning methods, this step greatly reduces the call times of the path planning algorithm in the link of the calling algorithm. The advantage of this method is that it can reduce the time and cost of path calculation, generate collision-free paths more quickly, and improve the efficiency of path planning. Secondly trajectories are optimized according to a minimum snap approach and by an application of inequality constraints. Unlike other methods, the minimum snapshot method takes into account the acceleration, angular acceleration, and continuity of the higher derivative of the trajectory, so that a trajectory with high continuity can be generated.
The main contributions are as follows: (1) the CD function can effectively reduce the number of calls to the path planning algorithm, thus reducing the time to generate a collision-free path; (2) before trajectory optimization, the collision-free path is optimized by the triangular function, which reduces the deviation of the trajectory from the original collision-free path.
The subsequent sections of this paper are structured as follows: Section 2 provides a concise overview of the related literature; Section 3 describes the UAV path planning problem, while Section 4 develops the RRT* algorithm optimization; Section 5 introduces the trajectory optimization method; Section 6 reports on the simulation and experiments; lastly, Section 7 discusses the research results of this paper, while Section 8 summarizes the whole paper and puts forward some prospects for further work.

2. Related Work

Generally, the purpose of trajectory optimization is to generate an optimal trajectory that satisfies the constraints. In the detection task, we assume that the environment and objects are known, and then give the waypoints in the detection task; therefore, the trajectory optimization is designed to generate a no-collision trajectory that passes through all the waypoints. Previous related studies categorized UAV motion planning into two approaches: path planning and trajectory planning. The purpose of path planning is to quickly generate a collision-free path without considering motion constraints. The purpose of trajectory planning is to generate a no-collision trajectory that satisfies the motion constraints based on the generated path.

2.1. Path Planning

Numerous path planning algorithms have been proposed in a variety of recent studies based on intelligent algorithms [8], artificial potential field methods [9], sampling-based methods [10], or the A* algorithm [11]. However, the path planning algorithm based on an intelligent algorithm needs extensive parameter adjustment, which falls easily into the local optimal solution. The artificial potential field method is easily disturbed by environmental noise, and the performance of the algorithm depends on the artificial potential function. The A* algorithm is sensitive to environmental modeling and selection of a heuristic function, which requires reasonable setting and adjustment, potentially failing to find a feasible path.
According to the environment and dynamic constraints of a UAV, different sampling methods are applied to generate a successful path. The goal of the coverage path planning (CPP) algorithm is to cover all areas of interest with minimal overlap [12]. The rapidly exploring random tree (RRT) algorithm has been proposed to solve the problem of nonholonomic constraints in high-dimensional environments [13]. Its main advantage is that it can quickly generate a solution by randomly sampling the state space, which is especially appropriate for a high-dimensional problem. However, due to the randomness of the sampling, the generated path is suboptimal. To get the optimal path, the RRT* algorithm proposed by Karaman and Frazoll connects all nodes in a certain range at each iteration [14]. By comparison, only the lowest cost node is reserved as the parent node. In this way, with the increase in sampling nodes, the generated path gradually becomes optimal. However, the generation of the optimal path is still computationally expensive, which has a great impact on real-time performance. Actually, in a real environment, it is important to get a solution quickly rather than to get an optimized but slow solution. The Anytime RRT* algorithm proposes a framework that first generates a rapid solution and then optimizes it in a limited computational time frame [15]. A few methods have been proposed to improve the convergence rate of the RRT* algorithm. The RRT-Connect algorithm is used to generate a path with a simple greedy heuristic [16]. Through bias sampling in the exploration space, the convergence speed of RRT* is accelerated. The RRT*-Smart algorithm firstly generates an initial path, and then applies intelligent sampling to optimize the path [17]. A potential field function is used to guide the RRT* algorithm toward the optimal solution [18]. However, the parameters of the gravity function and the repulsive function are preset; thus, this method does not adaptively change according to some changing behaviors. The Informed RRT* algorithm firstly generates an initial path; next, the length of the initial path is used to construct a region, and then the approximate rate sampling is carried out in this region, which can reduce the rate of sampling and obtain a better path solution [19]. However, when faced with complex environments, its computational complexity may be very high; hence, it needs to be optimized and accelerated. The Sampling-SEE algorithm uses the path cost and the location information of path points; then, through uniform sampling and bias sampling, it can achieve fast convergence to the optimal solution [20]. Its implementation requires sampling space division and path optimization. The Fast RRT* (F-RRT*) algorithm creates nodes based on triangle inequality, which can be combined with a sampling strategy to obtain a lower-cost initial solution. Meanwhile, its convergence rate is faster, which can form a smoother path [21,22]. However, if the triangle inequality on which it is based is not satisfied, the algorithm needs to be further improved. Compared with RRT*, the Quick RRT* (Q-RRT*) algorithm can converge to the optimal solution at a faster speed [23]. It can also be combined with a sampling strategy or graph pruning algorithm to get the Improved Q-RRT* algorithm [24]. However, when the UAV constraint cost does not satisfy the triangle inequality, the new sample information in the algorithm cannot propagate well in the tree. Considering the dynamic characteristics of UAVs and the complexity of the real three-dimensional environment, real-time path planning of UAVs has been realized by parallel implementation on a standard multicore central processing unit (CPU) [25]. Based on intelligent sampling and target distance, the Goal Distance-Based RRT* (GDRRT*) algorithm solves the problem that RRT* converges slowly to the target. On this basis, a particle swarm optimization algorithm and a bidirectional long/short-term memory (BiLSTM)-based architecture are used to improve the GDRRT* algorithm to obtain the BiLSTM/particle swarm optimization (PSO)/GDRRT* (BiLSTM-PSO-GDRRT*) algorithm, which provides a fast path planning method for real-time UAV applications [26]. However, this does not guarantee a shorter path.

2.2. Trajectory Planning

However, as most of these path planning algorithms generate nonlinear paths, the sudden and significant changes in acceleration that occur when a UAV makes a turn can greatly reduce its efficiency and result in unnecessary energy consumption. Constraint control can guide the UAV to the desired position while ensuring that constraints are met [27]. Although the steer function of RRT* can also generate trajectories with dynamic constraints, the computational time is not optimal [28]. Consequently, after generating waypoints, trajectory optimization is also required to generate smooth trajectories. Several nonlinear optimization methods are available for trajectory optimization, which can be employed to produce locally optimal paths [29]. Nonetheless, it should be noted that these techniques can be computationally intensive, and their successful application may rely on the availability of accurate analytical representations of environmental constraints for efficient computation of cost gradients concerning obstacles. For UAVs with extensive degrees of freedom, the minimum snap trajectory is a highly appropriate option, as it directly influences the fourth derivative of the trajectory, which in turn determines the motor command and attitude acceleration of the UAV [30]. The use of a minimum snap trajectory guarantees the precision of sensor measurements on board while preventing abrupt or excessive control inputs. Nonetheless, the optimization technique mentioned above cannot handle large-scale, multisegment, high-order polynomial trajectories due to the limitations imposed by the parameter matrix in quadratic programming [31]. Unconstrained quadratic programming (UQP) is derived using a substitution technique, and the optimization of time distribution is accomplished through a gradient descent approach. The joint polynomial trajectory optimization method can effectively address the challenges associated with a relatively high number of segment trajectories without introducing computational complexity. However, the resulting trajectory may deviate from the originally planned straight-line path [32]. In the case of dense obstacles, many iterations are needed to generate collision-free trajectories, which is time-intensive. To quickly generate a safe trajectory, a graph search algorithm can be used to generate a piece-wise linear skeleton and, on this basis, derive an efficient convex decomposition method that builds the safe flight corridor (SFC) [33]. The SFC provides a set of linear inequality constraints in quadratic programming, and a safe and smooth trajectory solution can be generated quickly. However, there is the problem of how to constrain the whole trajectory and its derivatives effectively in the feasible space with hard constraints.

3. UAV Path Planning Problem Description

3.1. Environment Modeling

A port roughly consists of the seaside, shore side, and land side, as shown in Figure 1. Ships are docked at the seaside while quay cranes are mainly arranged on the shore to load and unload goods. The land side, also known as the storage yard, is used for the temporary storage of goods.
Let us introduce the port environment considered above as a 3D simulation map. The length, width, and height of the map boundary are 820 m, 2820 m, and 120 m, respectively. The yard is generally divided into four subareas: the container area, dangerous container area, empty container yard area, and port inspection area, as shown in Figure 2.

3.2. Multiple-Point Motion Planning

A UAV is a six-freedom-degree platform; hence, its states need to be described in a three-dimensional environment. In a given three-dimensional environment, let X denote a bordered map environment, X R     3 , including free space X f r e e and an obstacle space X o b s . The starting node x s t a r t and the target node x g o a l are located in the free space X f r e e . The purpose of path planning is to generate a collision-free path from the starting node to the target node. In order to make sure a UAV will follow a secure path that takes into account the dynamic constraints of the environment, trajectory optimization needs to be performed.
Firstly, according to the environment tasks to perform and the UAV camera parameters, multiple monitoring points are artificially given, and then path planning is performed. Path planning between multiple points can be commonly transformed into multiple path planning tasks to solve. The principle behind these approaches is that, since path points are obtained, in addition to satisfying UAV power constraints, the trajectory needs to be as close as possible to the original inspection route to ensure the quality of the inspection task to perform.

4. RRT* Algorithm Optimization

The RRT* algorithm is computationally costly when searching for an optimal solution; in narrow areas, this is even worse. In order to optimize the application of the RRT* algorithm for path planning, we introduce a bias sampling strategy to generate a path in acceptable computational time assuming that the additional cost of the optimization process will be still acceptable.

4.1. Bias_RRT* Algorithm

Let us introduce the principles of the bias_RRT* algorithm. In Algorithm 1, Line 1 initializes the state of the path, while Line 3 generates a random node to set the direction at each iteration. Line 4 searches for the nearest node to the random node. The new node is generated by the size of the step u in Line 5. Overall, Lines 1–5 are used to generate the new node x n e w , this being similar to the RRT* algorithm. The main difference is that the bias_RRT* algorithm uses a target node as a random node to decide the direction of the iteration according to a given probability, which can improve the convergence rate of the RRT* algorithm. To ensure the characteristic of random sampling, the probability is generally given by interval values of 0.001–0.1. The iteration process of the bias_RRT* algorithm is illustrated in Figure 3. Algorithm 1, Line 7 shows how to find the nodes with a distance lower than r to x n e w . Lines 9–13 show that how to choose the node, such as x n e a r 2 , with the least cost as a parent node from x n e a r e s t to x n e w . Lines 14–17 show how to delete the edge from x n e a r 4 to x n e a r 5 , and then generate the new edge from x n e w to x n e a r 5 , which can achieve local optimization. Therefore, as long as there are enough sampling nodes, the bias_RRT* algorithm can ensure that the generated path is optimal. However, in limited planning time, the path is not optimal; hence, postprocessing is applied to reoptimize the path.
Algorithm 1. Bias_RRT* algorithm
1. V { x s t a r t } ; E
2. f o r   i = 1 : n
3.   x r a n d b i a s _ g o a l _ s a m p l e   ( )
4.   x n e a r e s t N e a r e s t ( V , x r a n d )
5.   x n e w S t e e r   ( x n e a r e s t , x r a n d , u )
6.   i f   n o C o l l i s i o n   ( x n e a r e s t , x n e w )
7.     X n e a r = N e a r   ( V , x n e w , r )
8.     V V x n e w
9.     x min x n e a r e s t ;   c min Cos t ( x n e a r e s t ) + c ( L i n e ( x n e a r e s t , x n e w ) )
10.     f o r e a c h   x n e a r X n e a r   d o
11.       i f   n o C o l l i s i o n   ( x n e a r , x n e w ) & & Cos t ( x n e a r ) + c ( L i n e ( x n e a r , x n e w ) ) < c min
12.         x min x n e a r ; c min Cos t ( x n e a r ) + c ( L i n e ( x n e a r , x n e w ) )
13.         E E { x min , x n e w }
14.     f o r e a c h   x n e a r X n e a r   d o
15.       i f   n o C o l l i s i o n ( x n e w , x n e a r ) & & Cos t ( x n e w ) + c ( L i n e ( x n e w , x n e a r ) ) < Cos t ( x n e a r )
16.         x p a r e n t P a r e n t ( x n e a r )
17.         E ( E \ { ( x p a r e n t , x n e a r ) } ) { ( x n e w , x n e a r ) }
18. r e t u r n   G = ( V , E )

4.2. Improved Bias_RRT* Algorithm

When applying detection path planning, not all adjacent detected points have obstacles to reach them. The flow chart of the detection path planning algorithm is shown in Figure 4. When the detection path point is given, whether there is an obstacle between two adjacent points should be evaluated. If there are obstacles, the improved RRT* algorithm is applied for path planning to get the collision-free path. Alternatively, if there are no obstacles, a straight line between the two points gives the collision-free path, thus saving computational time for the overall path planning task.
The CD function is presented to verify that a collision has occurred between the two adjacent detection points x a and x b , thus determining whether the bias_RRT* algorithm needs to be called.
C D x a , x b = i = 1 N H p i ,
where N represents the uniform selection of N points on line x a x b , and H p i represents the collision risk of any point p i :
H p i = 1 j = 1 n 1 h j p i ,
where n represents the number of obstacle points in the environment, and h j p i represents the influence of any obstacle point on point p i :
h j p i = 1 2 π σ 2 e d 2 2 σ 2 ,
where d represents the Euclidean distance between the obstacle point and p i point in the environment.
When optimizing the path under the proposed method, the trajectory is likely to diverge from the planned path; thus, the probability of the trajectory encountering obstacles is likely to increase. Bigger Euler angles denote a greater distance between the trajectory and the planned path. Accordingly, this increases the probability of hitting obstacles. We treat every three adjacent points in the path points as A, B, and C to show the principle of the proposed optimization function in Figure 5. The two points D and E represent the new path points through which the trajectory deviation is optimized.
First, the Euler angle φ between A B and B C is obtained as follows:
φ = 180 arccos B A B C B A × B C .
Then, an isosceles triangle Δ D B E is constructed, with the length of its base denoted by d . The length of the leg of the isosceles triangle r is as follows:
r = d 4 sin ( 180 φ 2 ) ,
where the value of d is one-fifth of the step u of the bias_RRT* algorithm. According to Equations (1) and (2), one can get the coordinates of the two points D and E :
D = ( B x + ( B A B A ) x × r , B y + ( B A B A ) y × r , B z + ( B A B A ) z × r ) E = ( B x + ( B C B C ) x × r , B y + ( B C B C ) y × r , B z + ( B C B C ) z × r ) .
It has been found in previous work that a smaller distance between two adjacent points in free space decreases the likelihood of hitting an obstacle [17]. Therefore, for different Euler angles, the value of d is always the same, which guarantees that new path segments are in free space. A schematic diagram of isosceles triangle optimization is shown in Figure 6. For the given path points, such as 1-2-3-4-1 in the leftmost diagram of Figure 6, the optimization function can be used to obtain 1-2-3-4-5-6-7-8-1 path points in the middle picture of Figure 6. Then, taking the midpoint of each path segment, the 1-2-3-4-5-6-7-8-1 path points in the rightmost diagram of Figure 6 can be obtained.

5. Optimized Path for Trajectory Planning

5.1. Trajectory Generation

Let us contemplate the issue of navigating through m waypoints at designated times. In between each waypoint, there is a safe corridor that the UAV must stay within. A trivial trajectory that satisfies these constraints is one that is interpolated between waypoints using straight lines. Nonetheless, this trajectory is suboptimal as it exhibits infinite curvature at the waypoint, necessitating the UAV to halt at each waypoint.
Our proposed method generates an optimized trajectory that smoothly transitions through the waypoints at the designated times while remaining within the safe corridors. It is convenient to write them as piece-wise polynomial functions of order n over m time intervals. For a quadrotor UAV, the i - th trajectory segment between two adjacent path points is denoted by P ( t ) . The trajectory segment’s polynomial function P ( t ) can be expressed as follows:
P ( t ) = i = 0 n p i 1 t i t 1 t < t 2 i = 0 n p i 2 t i t 2 t < t 3 i = 0 n p i m t i t m 1 t < t m ,
where p i j   ( i = 0 , 1 , , n ; j = 1 , 2 , , m ) is a coefficient of the polynomial trajectory. The reason for the choice of this basis is that we are searching for trajectories that minimize the polynomial function. The optimization program to solve this problem while minimizing the integral of the k derivative of position squared is as follows:
J = min   t 0 t m | | d k P ( t ) d t k | | 2 d t .
Our approach generates trajectories that aim to minimize the integral of the square of the snap’s norm (the second derivative of acceleration, k = 4 ).

5.2. Trajectory Optimization Constraints

There are two common constraints in trajectory optimization. One is to ensure that the location of each path point is the same as the trajectory point, and the other is that each intermediate node is continuous according to the k - o r d e r derivative. The common constraint diagram of trajectory optimization is shown in Figure 7. The red points in the figure represent the given detection points, and the black points represent the path points generated by the algorithm to avoid obstacles. Further details are expounded in the subsequent sections.

5.2.1. Waypoint Constraints

Let us consider that the UAV needs to pass through the waypoints from the start position to target position. Enforcing waypoint constraints involves setting equality constraints on relevant control points to ensure their compliance, expressed as follows:
P ( t i ) = W p ( i ) ( i = 1 , 2 , , m ) ,
where W p ( i ) represents the i th waypoint, and W p ( 1 ) , W p m represent the start and goal point respectively.

5.2.2. Continuity Constraints

At the connection point between two sections ( 0 Φ k 1 ), the trajectory must exhibit continuity in all ϕ th derivatives. Enforcing continuity constraints involves setting equality constraints between corresponding control points of two consecutive curves. For the trajectory segment between j th and ( j + 1 ) th pieces, the formula is as follows:
P t i t i + 1 ( ϕ ) ( t i + 1 ) =   P t i + 1 t i + 2 ( ϕ ) ( t i + 1 ) ( i = 1 , 2 , , m 2 , ϕ = 0 , 1 , 2 , 3 ) .

5.2.3. Camera Constraints

The target that UAV needs to detect is also an obstacle in the environment. Under the premise of ensuring the completion of the task and safety, there is a certain distance between the camera and the detection target. The expression is as follows:
d min s d max d min _ safe s d max _ s a f e ,
where s is the distance between UAV and the detected target. d min and d max are the minimum and maximum distances that the camera can capture, respectively. d min _ s a f e and d max _ s a f e represent the minimum and maximum distance under the premise of ensuring safety, and these two values depend on the environment. At the same time, in the flight process of UAV, the target area can be detected, and the distance between the UAV and target area should not be less than a certain value. The size of the detection region determines the minimum distance between UAV and the detection region, as shown in Figure 8.
L c h = 2 s tan ( w c h / 2 ) L d h L c v = 2 s tan ( w c v / 2 ) L d v ,
where L d h and L d v represent the horizontal and vertical lengths of the detection region. w c h and w c v represent the horizontal and vertical field angles of the camera. L c h and L c v represent the horizontal and vertical field lengths of the camera.
After s is obtained by the above two formulas, this is transformed into the constraint that the trajectory can deviate from the original straight-line path, expressed as follows:
( P ( t ) W p ( i ) ) ( W p ( i + 1 ) W p ( i ) ) W p ( i + 1 ) W p ( i ) f r ,
f r = s d point _ detection ,
where d point _ detection is the distance from a given detection point to the detection area.

6. Simulation

In order to apply the detection task, we give a series of monitoring points, which are the path points that the UAV must pass through. The selection of the monitoring points should fulfill an appropriate distance to the detection target. The simulation experimental parameters are shown in Table 1. The improved algorithm is experimented according to two task scenarios. In the following simulation results, the white line represents the path generated by the algorithm, while the blue line represents the desired trajectory of UAV, the red line represents the actual trajectory of UAV, and the yellow line represents the errors between the actual and desired trajectory. All simulation experiments were performed using MATLAB on a laptop with a 2.20 GHz Intel i7 CPU. The specific parameters in the experiment are shown in Table 1.

6.1. Scenario 1: Full Coverage Task Detection of the Port

In this scenario, we give a series of detection points, which are located above the upper plane of containers, and there is no collision between two adjacent points. The goal of this mission is to generate the path that can discover the emergencies and potential dangers in the port. The detection paths generated by the algorithms are shown in Figure 9. The computational time and path length of the bias_RRT* and improved bias_ RRT* algorithms are shown in Table 2.
The bias_RRT* algorithm generates a path from the starting node to the goal node after 3477.44 s while the path length is 195,378.25 m. The improved bias_RRT* algorithm generates a path from the starting node to the target node after 60.60 s while the path length is 194,917.57 m. Compared with Figure 9a, the improved path length in Figure 9b is reduced by 461 m, accounting for 0.2%. The more obvious difference is that the improved path generation time is 98% less than before, due to the lack of a possible collision between intermediate nodes.

6.2. Scenario 2: Inspection Task of Containers in the Port

In this scenario, the detection point is located at the end of the container array. Compared with scenario 1, the detection point is lower; hence, there is a possibility of collision between two adjacent detection points. For that scenario, the UAV should detect the status of containers in the yard. The detection paths generated by the algorithms are shown in Figure 10. The comparison of the computational times and trajectory length of the generated path are shown in Table 3.
The bias_RRT* algorithm generates a path from the starting node to the goal node after 1111.109 s while the path length is 36,448.24 m. The improved bias_RRT* algorithm generates a path from the starting node to the target node after 902.90 s while the path length is 34,360.35 m. The computational time to generate the path after the improvement is reduced by 18% compared with that before the improvement. The adjacent detection points are not all collision-free; thus, the impact on the optimization and computational time is not as favorable as in scenario 1, but it still has advantages over the previous method. The length of the improved path is reduced by 2087.89 m, accounting for 5.73%.
In scenario 2, we take the scene and path in the black dotted box as an example to illustrate the trajectory generated before and after optimization. In Figure 11, the blue line is the generation trajectory, and the black line is the path. Figure 11a is the effect diagram of the previous method, and Figure 11b is the effect diagram of the proposed method.
The length of the trajectory generated by the previous method is 7548.9 m, as shown in Figure 11a. The trajectory length resulting from the proposed method is 5627.3 m, as shown in Figure 11b. It can be seen from the figure that the deviation degree of the trajectory generated by the improved method is smaller than that before; a quantitative analysis was carried out, and the results are shown in Figure 12.
One can note that the quality of the generated trajectory improves as the generated trajectory points approach the straight-line path. It can be seen from Table 4 that the deviation between the trajectory generated by the proposed method and the original line is smaller than that of the original method. The comparisons between the bias_RRT* algorithm and the proposed method are shown in Table 5.
Overall, the results indicate that not only is the trajectory generated by this method optimized in terms of its length, but the average deviation is also reduced by 43.80%, and the cost function value is also reduced by 2659.6, accounting for 13.74%.

6.3. Trajectory Tracking Control Analysis

From the position and speed, let us analyze the relations between the desired trajectory generated by the proposed method and the actual trajectory generated by the UAV. There are a few errors between the actual trajectory and the desired trajectory. This is represented by the position and speed of three axes at each step. The relations of the desired trajectory and the actual trajectory are shown in Figure 13. Where x, y, and z represent axes in all three directions, and sec represents time in seconds.
The desired trajectory and the actual trajectory are shown in Figure 13a. Because the desired trajectory and the actual trajectory are not completely identical, Figure 13b,c show the error differences between the desired trajectory and the actual trajectory over time. The maximum error of position is about 2 × 10 2 mm, while the maximum error of velocity is about 5 × 10 3 mm/s. This finally shows that the UAV can effectively track the generated trajectory.

7. Discussion

In this paper, a motion planning method for UAV port inspection based on an optimized bias_RRT* algorithm is proposed, which aims to obtain UAV path planning under the condition of improved calculation time and ballistic length. The principles of the whole approach are fourfold. Firstly, the collision-free detection function is used as the basis to determine whether to call the bias_RRT* algorithm, to save calculation time. Secondly, the collision-free path is obtained by the geometric function and optimized. Then, the UAV camera constraint is added to the minimum stop trajectory to carry out trajectory planning. Lastly, the optimized collision-free path and trackable flight path of the UAV are generated. In the simulation experiment, we compare the methods before and after the improvement. According to the experimental results, the improved method has a higher optimization coefficient in terms of path generation time and trajectory deviation distance. The shortened path generation time means that the UAV can perform the inspection task more quickly, and the shortened deviation distance means that the risk of UAV collision is greatly reduced. Firstly, in terms of path generation, the path generation time before the improvement is 3477.44 s and 1111.11 s, while the path generation time after the improvement is 60.60 s and 902.90 s. Moreover, the path lengths before the improvement are 195,378.25 m and 36,448.24 m, while the improved path lengths are 194,917.57 m and 34,360.35 m, respectively. The experimental results show that the improved path generation time is 98% and 18% shorter than that before the improvement, and the improved path length is 0.2% and 5.73% shorter than that before the improvement. Secondly, in terms of trajectory optimization in local scenes, the path length before improvement is 4664.4 m, the path length after improvement is 4576.8 m, the track length before improvement is 7548.9 m, the track length after improvement is 5627.3 m, and the average deviation distance of the track before improvement is 17.19 m. The average deviation distance of the improved trajectory is 9.66 m, the cost function value before the improvement is 19,358.4, and the cost function value after the improvement is 16,698.8. The experimental results show that the improved path length is shortened by 1.88%, the improved track length is shortened by 25.46%, and the average deviation distance of the improved track is reduced by 43.80% compared with that before the improvement. The cost function value after improvement is 13.74% lower than that before improvement. Lastly, in terms of trajectory tracking control, the maximum position error between the expected trajectory and the actual trajectory is about 2 × 10 2 mm, and the maximum velocity error is about 5 × 10 3 mm/s, which indicates that the optimized trajectory can be well tracked by the UAV. The quantitative analysis of the above experimental data shows that the motion planning method in this paper can quickly generate the optimal trajectory, satisfying the tasks of UAV port inspection and tracking.

8. Conclusions

This research developed in this paper introduced an optimized bias_RRT* algorithm whose objective is to derive UAV path planning with improved computational time and trajectory length. The principles of the whole approach are fourfold. Firstly, a collision-free detection function is used as the basis to judge whether to call bias_RRT* algorithm or not in order to save computational time. Secondly, the collision-free path is obtained and optimized by the application of a geometrical function. Next, UAV camera constraints are added to the minimum stop trajectory for trajectory planning. Lastly, an optimized UAV collision-free path and a traceable flight trajectory are generated.
In summary, the global port inspection path provided in this paper has the advantages of global feasibility of path planning, avoidance of obstacles, precision of path planning, optimization of path planning, and improvement of path planning efficiency, and it is suitable for complex environments requiring global planning. In the condition of the given map and detection points, our approach can provide a good global detection path as reference. In practice, it is necessary for UAVs to have the ability to deal with dynamic problems. In the future work, we can consider using the camera and inertial sensors to capture information about the surrounding environment and its location, and then use local planning algorithms to solve the problem. Meanwhile, in order to take into account endurance limitations of quadrotor UAVs, cooperation between multiple UAVs will be explored in a sort of collaborative modelling and simulation framework. These are future research directions worth exploring.

Author Contributions

Conceptualization, Z.H.; software, Z.H.; resources, Z.H.; writing—original draft preparation, Z.H.; writing—review and editing, P.L. and C.C.; visualization, Z.H.; supervision, G.T.; funding acquisition, P.Z. All authors have read and agreed to the published version of the manuscript.

Funding

This research was supported in part by the National Natural Science Foundation of China (NO. 51905557).

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

The data presented in this study are available on request from the corresponding author. The data are not publicly available due to privacy.

Acknowledgments

The authors would like to thank funding body for the grant.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Al Abkal, S.; Talas, R.; Shaw, S. The application of unmanned aerial vehicles in managing port security in Kuwait. In Proceedings of the Logistics Research Network Conference, Southampton Solent University, Southampton, UK, 6–8 September 2017. [Google Scholar]
  2. Shakhatreh, H.; Sawalmeh, A.H.; Al-Fuqaha, A.; Dou, Z.; Almaita, E.; Khalil, I.; Othman, N.S.; Khreishah, A.; Guizani, M. Unmanned Aerial Vehicles (UAVs): A Survey on Civil Applications and Key Research Challenges. IEEE Access 2019, 7, 48572–48634. [Google Scholar] [CrossRef]
  3. Tang, G.; Hou, Z.; Claramunt, C.; Hu, X. UAV Trajectory Planning in a Port Environment. J. Mar. Sci. Eng. 2020, 8, 592. [Google Scholar] [CrossRef]
  4. Montambault, S.; Beaudry, J.; Toussaint, K.; Pouliot, N. On the application of VTOL UAVs to the inspection of power utility assets. In Proceedings of the 2010 1st International Conference on Applied Robotics for the Power Industry, Montreal, QC, Canada, 5–7 October 2010; pp. 1–7. [Google Scholar]
  5. Schäfer, B.E.; Picchi, D.; Engelhardt, T.; Abel, D. Multicopter unmanned aerial vehicle for automated inspection of wind turbines. In Proceedings of the 2016 24th Mediterranean Conference on Control and Automation (MED), Athens, Greece, 21–24 June 2016; pp. 244–249. [Google Scholar]
  6. Jung, S.; Song, S.; Youn, P.; Myung, H. Multi-layer coverage path planner for autonomous structural inspection of high-rise structures. In Proceedings of the 2018 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Madrid, Spain, 1–5 October 2018; pp. 1–9. [Google Scholar]
  7. Luo, X.; Li, X.; Yang, Q.; Wu, F.; Zhang, D.; Yan, W.; Xi, Z. Optimal path planning for UAV based inspection system of large-scale photovoltaic farm. In Proceedings of the 2017 Chinese Automation Congress (CAC), Jinan, China, 20–22 October 2017; pp. 4495–4500. [Google Scholar]
  8. Garcia, M.A.P.; Montiel, O.; Castillo, O.; Sepúlveda, R.; Melin, P. Path planning for autonomous mobile robot navigation with ant colony optimization and fuzzy cost function evaluation. Appl. Soft Comput. 2009, 9, 1102–1110. [Google Scholar] [CrossRef]
  9. Vadakkepat, P.; Tan, K.C.; Ming-Liang, W. Evolutionary artificial potential fields and their application in real time robot path planning. In Proceedings of the 2000 Congress on Evolutionary Computation. CEC00 (Cat. No. 00TH8512), La Jolla, CA, USA, 16–19 July 2000; pp. 256–263. [Google Scholar]
  10. Elbanhawi, M.; Simic, M. Sampling-Based Robot Motion Planning: A Review. IEEE Access 2014, 2, 56–77. [Google Scholar] [CrossRef]
  11. Duchoň, F.; Babinec, A.; Kajan, M.; Beňo, P.; Florek, M.; Fico, T.; Jurišica, L. Path Planning with Modified a Star Algorithm for a Mobile Robot. Procedia Eng. 2014, 96, 59–69. [Google Scholar] [CrossRef] [Green Version]
  12. Fevgas, G.; Lagkas, T.; Argyriou, V.; Sarigiannidis, P. Coverage Path Planning Methods Focusing on Energy Efficient and Cooperative Strategies for Unmanned Aerial Vehicles. Sensors 2022, 22, 1235. [Google Scholar] [CrossRef] [PubMed]
  13. LaValle, S.M. Rapidly-Exploring Random Trees: A New Tool for Path Planning; Tech. Rep. TR 98-11; Department of Computer Science—Iowa State University: Ames, IA, USA, 1998. [Google Scholar]
  14. Karaman, S.; Frazzoli, E. Sampling-based algorithms for optimal motion planning. Int. J. Robot. Res. 2011, 30, 846–894. [Google Scholar] [CrossRef] [Green Version]
  15. Karaman, S.; Walter, M.R.; Perez, A.; Frazzoli, E.; Teller, S. Anytime motion planning using the RRT. In Proceedings of the 2011 IEEE International Conference on Robotics and Automation, Shanghai, China, 9–13 May 2011; pp. 1478–1483. [Google Scholar]
  16. Kuffner, J.J.; LaValle, S.M. RRT-connect: An efficient approach to single-query path planning. In Proceedings of the 2000 ICRA. Millennium Conference, IEEE International Conference on Robotics and Automation, Symposia Proceedings (Cat. No. 00CH37065), San Francisco, CA, USA, 24–28 April 2000; pp. 995–1001. [Google Scholar]
  17. Islam, F.; Nasir, J.; Malik, U.; Ayaz, Y.; Hasan, O. RRT*-smart: Rapid convergence implementation of RRT* towards optimal solution. In Proceedings of the 2012 IEEE International Conference on Mechatronics and Automation, Chengdu, China, 5–8 August 2012; pp. 1651–1656. [Google Scholar]
  18. Tahir, Z.; Qureshi, A.H.; Ayaz, Y.; Nawaz, R. Potentially guided bidirectionalized RRT* for fast optimal path planning in cluttered environments. Robot. Auton. Syst. 2018, 108, 13–27. [Google Scholar] [CrossRef] [Green Version]
  19. Gammell, J.D.; Srinivasa, S.S.; Barfoot, T.D. Informed RRT: Optimal sampling-based path planning focused via direct sampling of an admissible ellipsoidal heuristic. In Proceedings of the 2014 IEEE/RSJ International Conference on Intelligent Robots and Systems, Chicago, IL, USA, 14–18 September 2014; pp. 2997–3004. [Google Scholar]
  20. Wang, Z.; Li, Y.; Zhang, H.; Liu, C.; Chen, Q. Sampling-Based Optimal Motion Planning with Smart Exploration and Exploitation. IEEE/ASME Trans. Mechatron. 2020, 25, 2376–2386. [Google Scholar] [CrossRef]
  21. Liao, B.; Wan, F.; Hua, Y.; Ma, R.; Zhu, S.; Qing, X. F-RRT*: An improved path planning algorithm with improved initial solution and convergence rate. Expert Syst. Appl. 2021, 184, 115457. [Google Scholar] [CrossRef]
  22. Qiu, X.; Li, Y.; Jin, R.; Zhao, Z.; Li, J.; Lu, D.; Ma, L.; Chen, J. Improved F-RRT* Algorithm for Flight-Path Optimization in Hazardous Weather. Int. J. Aerosp. Eng. 2022, 2022, 1166968. [Google Scholar] [CrossRef]
  23. Jeong, I.-B.; Lee, S.-J.; Kim, J.-H. Quick-RRT*: Triangular inequality-based implementation of RRT* with improved initial solution and convergence rate. Expert Syst. Appl. 2019, 123, 82–90. [Google Scholar] [CrossRef]
  24. Zhuge, C.; Wang, Q.; Liu, J.; Yao, L. An Improved Q-RRT* Algorithm Based on Virtual Light. Comput. Syst. Sci. Eng. 2021, 39, 107–119. [Google Scholar] [CrossRef]
  25. Roberge, V.; Tarbouchi, M.; Labonte, G. Comparison of Parallel Genetic Algorithm and Particle Swarm Optimization for Real-Time UAV Path Planning. IEEE Trans. Ind. Inform. 2013, 9, 132–141. [Google Scholar] [CrossRef]
  26. Aslan, M.F.; Durdu, A.; Sabanci, K. Goal distance-based UAV path planning approach, path optimization and learning-based path estimation: GDRRT*, PSO-GDRRT* and BiLSTM-PSO-GDRRT*. Appl. Soft Comput. 2023, 137, 110156. [Google Scholar] [CrossRef]
  27. Hermand, E.; Nguyen, T.W.; Hosseinzadeh, M.; Garone, E. Constrained Control of UAVs in Geofencing Applications. In Proceedings of the 2018 26th Mediterranean Conference on Control and Automation (MED), Zadar, Croatia, 19–22 June 2018; pp. 217–222. [Google Scholar]
  28. Sertac, K.; Emilio, F. Optimal kinodynamic motion planning using incremental sampling-based methods. In Proceedings of the 49th IEEE Conference on Decision and Control (CDC), Atlanta, GA, USA, 15–17 December 2010; p. 7681. [Google Scholar]
  29. Rösmann, C.; Hoffmann, F.; Bertram, T. Kinodynamic trajectory optimization and control for car-like robots. In Proceedings of the 2017 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Vancouver, BC, Canada, 24–28 September 2017; pp. 5681–5686. [Google Scholar]
  30. Cutler, M.; How, J. Actuator constrained trajectory generation and control for variable-pitch quadrotors. In Proceedings of the AIAA Guidance, Navigation, and Control Conference, Grapevine, TX, USA, 9–13 January 2012; p. 4777. [Google Scholar]
  31. Mellinger, D.; Kumar, V. Minimum snap trajectory generation and control for quadrotors. In Proceedings of the 2011 IEEE International Conference on Robotics and Automation, Shanghai, China, 9–13 May 2011; pp. 2520–2525. [Google Scholar]
  32. Richter, C.; Bry, A.; Roy, N. Polynomial Trajectory Planning for Aggressive Quadrotor Flight in Dense Indoor Environments. In Robotics Research: The 16th International Symposium ISRR; Springer: Berlin/Heidelberg, Germany, 2016; pp. 649–666. [Google Scholar]
  33. Liu, S.; Watterson, M.; Mohta, K.; Sun, K.; Bhattacharya, S.; Taylor, C.J.; Kumar, V. Planning dynamically feasible trajectories for quadrotors using safe flight corridors in 3-d complex environments. IEEE Robot. Autom. Lett. 2017, 2, 1688–1695. [Google Scholar] [CrossRef]
Figure 1. Phase IV wharf of Yangshan Port.
Figure 1. Phase IV wharf of Yangshan Port.
Jmse 11 00702 g001
Figure 2. Simulation environment for phase IV wharf of Yangshan Port. In the middle of the figure, the areas with red and green stripes represent the container areas, while the areas inside the black wire frame on the left denote the dangerous container areas. In the upper part, the red and blue rectangular areas are the empty container yard area, and the yellow area is the port inspection area.
Figure 2. Simulation environment for phase IV wharf of Yangshan Port. In the middle of the figure, the areas with red and green stripes represent the container areas, while the areas inside the black wire frame on the left denote the dangerous container areas. In the upper part, the red and blue rectangular areas are the empty container yard area, and the yellow area is the port inspection area.
Jmse 11 00702 g002
Figure 3. Iteration process of the bias_RRT* algorithm.
Figure 3. Iteration process of the bias_RRT* algorithm.
Jmse 11 00702 g003
Figure 4. Flow chart of UAV trajectory optimization.
Figure 4. Flow chart of UAV trajectory optimization.
Jmse 11 00702 g004
Figure 5. Principle and optimization effect of isosceles triangle function. (a) Schematic diagram of optimizing path length effect. (b) Schematic diagram of optimizing trajectory deviation effect.
Figure 5. Principle and optimization effect of isosceles triangle function. (a) Schematic diagram of optimizing path length effect. (b) Schematic diagram of optimizing trajectory deviation effect.
Jmse 11 00702 g005
Figure 6. Schematic diagram of isosceles triangle optimization.
Figure 6. Schematic diagram of isosceles triangle optimization.
Jmse 11 00702 g006
Figure 7. Schematic diagram of constraints in trajectory optimization.
Figure 7. Schematic diagram of constraints in trajectory optimization.
Jmse 11 00702 g007
Figure 8. Schematic diagram of UAV detection region.
Figure 8. Schematic diagram of UAV detection region.
Jmse 11 00702 g008
Figure 9. Detection paths generated by the algorithms in Scenario 1. (a) Path generated by the bias_RRT* algorithm. (b) Path generated by the improved bias_RRT* algorithm.
Figure 9. Detection paths generated by the algorithms in Scenario 1. (a) Path generated by the bias_RRT* algorithm. (b) Path generated by the improved bias_RRT* algorithm.
Jmse 11 00702 g009
Figure 10. Detection paths generated by the algorithms in Scenario 2. (a) Path generated by the bias_RRT* algorithm. (b) Path generated by the improved bias_RRT* algorithm.
Figure 10. Detection paths generated by the algorithms in Scenario 2. (a) Path generated by the bias_RRT* algorithm. (b) Path generated by the improved bias_RRT* algorithm.
Jmse 11 00702 g010
Figure 11. Trajectory optimization comparison in local environment. (a) Trajectory generated by the previous based on bias_RRT* algorithm. (b) Trajectory generated by the proposed method based on improved bias_RRT* algorithm.
Figure 11. Trajectory optimization comparison in local environment. (a) Trajectory generated by the previous based on bias_RRT* algorithm. (b) Trajectory generated by the proposed method based on improved bias_RRT* algorithm.
Jmse 11 00702 g011
Figure 12. Deviation distance between the path and the trajectory. (a) Deviation distance generated by the previous methods. (b) Deviation distance generated by the proposed methods.
Figure 12. Deviation distance between the path and the trajectory. (a) Deviation distance generated by the previous methods. (b) Deviation distance generated by the proposed methods.
Jmse 11 00702 g012
Figure 13. Relations between the desired trajectory and actual trajectory. (a) Comparison of desired trajectory and actual trajectory. (b) Position error. (c) Velocity error.
Figure 13. Relations between the desired trajectory and actual trajectory. (a) Comparison of desired trajectory and actual trajectory. (b) Position error. (c) Velocity error.
Jmse 11 00702 g013
Table 1. Simulation experiment parameters.
Table 1. Simulation experiment parameters.
SymbolParameter
bias_RRT* algorithmEPS = 3 m
p = 0.001
r = 3 m
dd = r/3
UAV bottom camera w ch = w cv = 64 °
d min = 0.7
d max = 20
UAV front camera w ch = w cv = 90 °
d min = 1
d max = 15
Laptop setupIntel i7 CPU
2.20 GHz
Table 2. Bias_RRT* algorithm comparison to improved bias_RRT* algorithm in Scenario 1.
Table 2. Bias_RRT* algorithm comparison to improved bias_RRT* algorithm in Scenario 1.
Time (s)Length of Path (m)
Bias_RRT* algorithm3477.44195,378.25
Improved bias_RRT* algorithm60.60194,917.57
Table 3. Bias_RRT* algorithm comparison to the improved bias_RRT* algorithm in Scenario 2.
Table 3. Bias_RRT* algorithm comparison to the improved bias_RRT* algorithm in Scenario 2.
Time (s)Length of Path (m)
Bias_RRT* algorithm1111.1136,448.24
Improved bias_RRT* algorithm902.9034,360.35
Table 4. Proportion of distribution range of deviation distance.
Table 4. Proportion of distribution range of deviation distance.
Distance Distribution Range (m)0–55–1010–1515–20Above 20
Previous methods31.51%20.73%13.70%7.85%26.22%
Proposed methods50.09%16.75%12.45%6.91%13.80%
Table 5. Comparisons between previous method and the proposed method.
Table 5. Comparisons between previous method and the proposed method.
Path Length (m)Trajectory Length (m) δ d F / m J
Previous methods4664.47548.917.1919,358.4
Proposed methods4576.85627.39.6616,698.8
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

Tang, G.; Liu, P.; Hou, Z.; Claramunt, C.; Zhou, P. Motion Planning of UAV for Port Inspection Based on Extended RRT* Algorithm. J. Mar. Sci. Eng. 2023, 11, 702. https://doi.org/10.3390/jmse11040702

AMA Style

Tang G, Liu P, Hou Z, Claramunt C, Zhou P. Motion Planning of UAV for Port Inspection Based on Extended RRT* Algorithm. Journal of Marine Science and Engineering. 2023; 11(4):702. https://doi.org/10.3390/jmse11040702

Chicago/Turabian Style

Tang, Gang, Pengfei Liu, Zhipeng Hou, Christophe Claramunt, and Peipei Zhou. 2023. "Motion Planning of UAV for Port Inspection Based on Extended RRT* Algorithm" Journal of Marine Science and Engineering 11, no. 4: 702. https://doi.org/10.3390/jmse11040702

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