1. Introduction
Unmanned Aerial Vehicles (UAVs), notably employed as indispensable intelligent electronic devices in modern life, are showing continuous growth in the proportion of the global trade market. Civilian drones can be divided into patrol drones, agricultural drones, meteorological drones, exploration drones, and disaster relief drones according to their uses. Based on this, UAVs with higher integration, better computing efficiency, and faster reaction time have been invested immensely in research and development by countries around the world [
1,
2]. However, due to the unpredictability of the disaster area (such as severe weather, disaster areas, etc.), depending solely on radio remote control, is very challenging for UAVs to accomplish tasks such as precise identification, obstacle avoidance flight, and coordinated rescue [
3]. Therefore, it is of great essence to develop algorithms for autonomous path planning of disaster relief UAVs.
Disaster relief UAVs generally fly at altitudes between 25 and 150 m above sea level. Signal interference caused by low-altitude clouds, smoke, and dust is the main natural threat to drones when flying [
4], which means that UAVs should avoid being disrupted by clouds, smoke, and dust. Therefore, the path-planning algorithm deployed on the UAV has to be efficient, safe, and equipped with local dynamic planning capabilities.
Currently, the existing path-planning algorithms can be divided into two categories: the global path-planning algorithm and the local path-planning algorithm. The global path-planning methods include the A* algorithm [
5], the Dijkstra algorithm [
6], the Genetic Algorithm (GA) [
7], and the sampling-based Rapidly-exploring Random Trees (RRT) algorithm [
8]. The drawback of the heuristic algorithm represented by the A* algorithm is that it causes significant performance consumption when the target point is unreachable, which is unsuitable for complex disaster environments. The original version of Dijkstra’s algorithm was only suitable for finding the shortest path between two vertices, later more common variants fixed a vertex as the source node and then found the shortest path from that vertex to all other nodes in the graph, yielding a shortest path tree. This algorithm picks out the smallest distance among the unvisited nodes each time and uses this node to update the distances of other nodes. The GA algorithm can obtain the optimal path in route planning, but it requires multiple iterations to obtain the optimal solution. Its complex algorithm leads to low computational efficiency, poor real-time performance, and the inability to use feedback information from the network in a timely manner.
In disaster areas, the path-planning algorithm needs to prioritize safety and generate the speed of the UAV moving trajectory not just for the optimal path. Therefore, the RRT algorithm with faster execution efficiency is introduced to generate UAV motion paths quickly. Compared with the RRT algorithm, after the sampling point is added to the path tree, the RRT* algorithm draws a circle with the new point as the center, and considers whether there is a better parent node, in other words, which nodes can be connected to make the distance from the starting point to the target point shorter (although those nodes are not the closest points to the sampling point). If a more suitable parent node is selected, it then connects them and removes the original connection, which is called rerouting. Karaman et al. [
9] proposed a progressive optimal path based on the RRT* algorithm to guide the target. Qin et al. [
10] put forward a posture constraint strategy which enables UAVs to fly more smoothly.
The RRT* algorithm takes the Artificial Potential Field (APF) algorithm [
11] and Dynamic Window Algorithm (DWA) [
12] as the typical cases of local path-planning algorithms. The former is widely used in path-smoothing control, while the latter possess relatively high dynamic obstacle avoidance capability. However, the adaptive direction of the existing algorithms is mainly centered around the step size. Most of the optimization work is premised on the characteristics of the algorithms themselves, with less research on algorithm fusion.
In the field of global path planning of UAVs, most of them are static, and the planned path is obtained after the environment is rasterized, which is not a real optimized path, and thus further optimization is still necessitated. Nonetheless, for rescue and disaster relief missions, whether they are reconnaissance or transportation missions, not only must the most basic guarantees be made in terms of path safety, but relatively high requirements are also required for running time. The improved fusion algorithm proposed in this paper possesses an enhanced performance in both dynamic and static obstacle avoidance environments. It is not only satisfied with static obstacle avoidance but also has good safety performance when encountering moving obstacles. Moreover, although the required computing time has been shortened a little, the heading angle has improved a lot, and more importantly, it is suitable for complex and changeable real environments.
From the aforementioned problems, this paper addresses them by improving the RRT* algorithm in the following four ways:
- (a)
Employing adaptive step size, which switches to a small and dynamic step size when approaching obstacles, achieves a step size that changes with path conditions, and improves path smoothness to some extent.
- (b)
Employing adaptive search scope, which gives a dynamic constraint to the search scope, effectively reduces the randomness and blindness of node growth in the search process, speeds up the convergence speed, and improves efficiency.
- (c)
Combining with the APF algorithm. Attraction and repulsion forces are introduced based on expanded random numbers to expand the target point more effectively under the combined force. This algorithm improves operational efficiency, reduces the turning angle and path cost, and has a safe and efficient real-time obstacle avoidance capability.
- (d)
Cutting and optimizing the path. A novel collision detection method is introduced. If the collision detection between and is passed, and there is no collision with the obstacle, the node is banned, the number of turns is reduced, which keeps the path as smooth as possible.
After the improvement of the RRT* algorithm and the integration of the APF algorithm, the convergence speed and path smoothness of the new algorithm APF-IRRT* in both offline static and online dynamic environments are improved, the real-time performance is greatly improved, and the practical implementation is enhanced.
In light of the above discussions, this paper seeks to propose a novel fusion algorithm capable of performing in both dynamic and static obstacle avoidance environments. This algorithm is not only satisfied with static obstacle avoidance, but also has good safety performance when encountering moving obstacles. In this way, the required internal calculation time can be shortened, and its maximum deflection angle can be controlled, whilst improving the rescue speed, and its safety has been greatly improved, which is more suitable for complex and changeable rescue environments.
The remainder of the article is organized as follows:
Section 2 generalizes the path planning problem into a mathematical model;
Section 3 shows the basic principles of RRT, RRT*, and APF algorithms;
Section 4 describes the details of the method proposed in this paper;
Section 5 shows the overall technical route and the acquired data in this paper;
Section 6 presents the detailed results of different experiments, then discusses the results of the test phases; finally, the conclusions are presented in
Section 7.
3. Basic Principles of Algorithm
3.1. Traditional RRT Algorithm
The path planning problem involves finding a collision-free path from the starting point to the target point within the specified area. It can be classified into global path planning and local path planning. The former is the original path planning problem and involves searching for an optimal path throughout the entire space.
The RRT algorithm, proposed in the late 20th century, is particularly noteworthy for its superior performance of speed and flexibility in many scenarios [
14]. However, it also presents the disadvantage of fulling of randomness in its search process, leading to its unstable efficiency.
Furthermore, the lack of target directivity in the iterative process also makes the search paths different and leads to randomness. As shown in
Figure 1, it can be seen that the RRT algorithm struggles to find the exit in the closed terrain with a narrow channel, resulting in excessive computation and time consumption. Although the above problems can be improved by changing the step size or setting the adaptive step size, reducing the step size will lead to a tremendous amount of calculation and a longer calculation time. Additionally, some improved RRT algorithms try to make up for some defects by interpolation correction yet fail to obtain a satisfactory effect.
The RRT algorithm initializes the map with only the root starting point and target point . A random point is then generated according to a search strategy probability, P, which may either take as or scatter within a specific range of . The node closest to the on the map and the starting point of the above process is named . A new node is then generated in the direction of the vector pointing from to , with the step length represented by the distance parameter, step. The value of step is crucial to the algorithm’s accuracy, and careful selection is a top priority.
If there exists a potential collision between
and the parent node
, the path will be abandoned, and a new node will be generated. The loop continues until the distance between
and the
is less than
, where
is used to judge whether it is close enough to the target point or reaches the target point.
Figure 2 shows the schematic diagram of the RRT algorithm.
Obstacles are an array of artificial inputs. The detection of obstacles adopts a hypothetical idea, first selects a certain area, and stipulates that all sampling points falling in this area are invalid and will not be included in the growth tree. In other words, the selected area can be equivalent to a “hole”, and the sampling points falling in the “hole” will not be regarded as and will not participate in the above judgment process. In this way, the generated path will bypass the area, and there will be no intersection at the edge or inside of the area, so the area is equivalently regarded as an obstacle and the obstacles can be detected in real-time.
To ensure the feasibility and controllability of the algorithm, a maximum search count limit COUNT_MAX needs to be set in advance to complete the search within the given number of cycles. Otherwise, it is set to jump out of the cycle to end the task.
Therefore, the RRT algorithm encompasses six basic steps: import map information, generate random points, extend towards the generated point, add collision detection, set the cycle limit, and use the greedy algorithm to find the shortest path.
3.2. The RRT* Algorithm
The RRT* algorithm is an improvement on the traditional RRT algorithm. Instead of immediately starting the next cycle after generating a new node
, it reselects the parent node and reroutes the new node through collision detection. As is shown in
Figure 3, the round icon represents the node, and the label on the node represents the order of node generation.
The improved performance of the RRT* algorithm can be seen by adding weights to the directed weight graph. The innovative step reset and reroute the parent node is demonstrated in
Figure 3b. By finding a path with the least cost from
to the latest node
, the algorithm resets the parent node. The threshold range for reselecting the parent node is a circle with the new node
as the center and the parameter
as the radius.
Any node in the circle is regarded as a potential parent node and compared with the original parent node to see if the path cost is lower. As shown in
Figure 3c, node 3 is chosen as the new parent node for node 7, and the connection between the original node 6 and node 7 is erased. The algorithm then generates a new search tree.
To sum up, the RRT* algorithm improves the way of selecting parent nodes based on the original RRT algorithm. The cost function determines the node with the lowest cost in expanding nodes as the parent node. At the same time, nodes on the existing tree will be reconnected after each iteration to ensure computational complexity and an asymptotic optimal solution.
3.3. The APF Algorithm
Because the working environment of UAVs is highly complex, even with access to global map information, path planning remains challenging. A crucial aspect is moving towards the target position away from the obstacles, which necessitates the construction of a potential field function that incorporates these effects.
Because of the directivity of the UAV to the target point, the target point provides attraction, whereas obstacles elicit repulsion. The potential energy of any point in the map can be obtained by superimposing the attractive and repulsive potential fields. Path planning is accomplished by searching for and moving toward potential energy reduction. The working principle is shown in
Figure 4, where
indicates the repulsion of obstacles to the UAV, and
indicates the attraction of target points to the UAV.
The algorithm stipulates that the UAV will be subjected to the attraction of the target point at any position in the map, and the attraction is inversely proportional to the distance of the target point [
15].
is defined as an attractive potential field function:
where
q is the current position of the UAV,
is the position of the target point,
is the scale coefficient of the attractive potential field, and
,
represents the Euclidean distance between the UAV and the target point. The gradient is expressed in
.
Correspondingly,
is defined as the repulsive potential field function:
where
is the scale coefficient of the potential repulsion field,
represents the distance between UAV and the obstacle, and
(
) is the repulsion field range of the obstacle. If
, then the potential repulsion field
. The gradient is expressed in
.
Therefore, the total potential field function of UAV is the superposition of attractive potential field and repulsive potential field, known as
The total gradient is expressed as
The resultant force is expressed as
4. Algorithm Improvement
The RRT* algorithm distributes numerous extraneous points during global sampling to enhance its search’s randomness, occupying significant memory space and eventually leading to slow convergence and overly convoluted paths. On the other hand, in the artificial potential field method, the complexity, danger, and particularity of the environment may result in an abundance of points with the lowest energy in the map or even positions where the attractive and repulsive forces cancel each other out. This can make the UAV become trapped in local optimization or stagnation. Therefore, to address these issues, this paper proposes an improvement to the RRT* algorithm by combining it with the APF algorithm and integrating the ideas of attraction and repulsion to make the algorithm more sensitive and efficient.
4.1. Adaptive Search Step
Although the RRT* algorithm has a few improvements relative to the traditional RRT algorithm, the algorithm hardly determines the optimal path due to the fixed expansion step size. Therefore, the dynamic adaptive step size is adopted in this paper. The basic principle is: when
approaches obstacles, the small step size is adopted for expansion; in contrast, when it is far away from the obstacle, it can be expanded with a large step size. The dynamic step size can realize that the step size changes with the change of path conditions, which accurately solves the problem of practicality. It also improves the smoothness of the path to a certain extent, which is practical [
16]. Meanwhile, the dynamic step is expressed as
:
where
k is the proportion constant which is used to control the adjustment range of step size,
r and
are the actual and safe critical distance between
and obstacles, respectively. It can be seen from the formula that when the actual distance
r is less than the safe distance
, the step size will be reduced under the control of the proportional coefficient
k, effectively realizing the mutual consideration between obstacle avoidance and smoothness. The latest node
can be represented as follows:
4.2. Adaptive Search Range
In the RRT* algorithm, the sampling mechanism of the algorithm itself has not changed, and the problem of slow convergence still exists. Therefore, the angle-increasing sampling method is introduced based on the RRT algorithm. It is to retain the original random sampling of the whole map, give a constraint to the search scope, and limit the initial search scope to a particular angle space.
Figure 5 shows the basic principle of this method, taking the direction of the resultant force
F of
as the starting axis, counterclockwise as the positive direction, the initial angle
, and the increment
.
The technique involves sampling within the range of around the direction of , followed by collision detection on the connection between the new node and . If the detection fails, the is increased to the current angle , and then the sampling and collision detection are performed again within the range of . This process continues until falls within the range . This method can effectively reduce the randomness and blindness of node growth in the search process, as well as accelerate the convergence speed and improve efficiency.
4.3. Fusion with the APF Algorithm
To better solve the path planning problem of UAVs in emergency rescue and disaster relief, the traction force of target points on UAV and the repulsion force of obstacles in the APF algorithm are integrated into the RRT* algorithm. The essence of the RRT* algorithm is to expand the search tree, filter available nodes, and add them to the search tree. After the introduction of the APF algorithm, the target attraction function and obstacle repulsion function are constructed for each node as a unit when the node is expanded so that the search tree can move towards the target point under the effect of the resultant force.
This approach significantly increases the search’s purpose and target and speeds up the convergence speed [
17]. The function expression of
and
are as follows:
where
indicates the coefficient of attraction and
indicates the coefficient of repulsion.
is simplified by
d to represent the distance between the drone and the obstacles. Equation (2) illustrates that the UAV is within the repulsive force range of the obstacle, that is,
when
, the repulsion force is zero.
The resultant force of the new node is expressed as the vector sum of attractive and repulsive forces:
The generation of new nodes is also the superposition of two directed vectors:
However, in this case, it is often trapped in a local optimum issue for which we can add a disturbance (random walk) or backtrack at the local minimum to jump out of the local minimum.
The node expansion mode after the algorithm fusion is shown in
Figure 6.
4.4. Sectional Cutting Optimization Method
Although the APF-IRRT* algorithm after algorithm fusion has relatively improved in sampling adjustment and convergence speed, the core mode of random sampling nevertheless remains unchanged, which leads to the path still having twists and turns. This is very unfavorable for UAVs in operations. Therefore, to circumvent the UAV from turning to the target point and causing problems such as too fast a speed or too large an angle and to reduce the tortuosity of the path, the original method of traversing from the starting point needs to be improved.
Since the obstacles in this paper are superimposed by circles, for the collision detection of a solid circle, it is only necessary to judge whether the distance between the vertex and the center of the circle is less than the radius. A new rerouting method is introduced after collision detection. Suppose the path goes through
,
, and
. If the collision detection between
and
is passed, and there is no collision with the obstacle, the node
is banned, the number of turns is reduced, and the path is kept as smooth as possible. Secondly, the global path obtained by the fusion algorithm is cut, and the local path after cutting is optimized. In this process, it is necessary to connect the points into a line and calculate the steering angle;
represents the max angle.
7. Conclusions
This paper proposed a new APF-IRRT* fusion algorithm for rescue and disaster relief UAVs. This algorithm firstly improves the RRT* algorithm; it not only reduces the calculation time, but also greatly improves the safety. Secondly, the introduction of the APF algorithm made it not only suitable for ordinary static obstacle environments, but also possesses better obstacle avoidance capabilities in changing dynamic environments to ensure its safety, which has effectively solved the problem of dangerous and complex surroundings of rescue drones. The path planning problem in the environment provides an effective option for the global path planning of the UAV in a specific environment. The algorithm mainly presents the characteristics of simple modeling, with few parameters to be adjusted, not being affected by the shape of obstacles, simple calculation, and easy implementation. Based on the algorithm in this paper, the global optimization path of the robot can be quickly and effectively planned. To ensure computational efficiency and prediction correctness, the target directivity of the extended node was given, which effectively overcomes the inherent blindness of the RRT algorithm. The step-size adaptive and angle-increasing sampling methods were also utilized to limit the sampling range, thus reducing the tortuosity of the generated path and the time consumed.
To further enhance the path’s smoothness, the generated path was optimized by calculating the angle value between the line connecting the new node’s parent node and the original path. The simulation results demonstrate that the fusion APF-IRRT* algorithm dramatically improves the issues of slow convergence speed and tortuous path of the traditional RRT algorithms in the static environment. Meanwhile, the APF-IRRT* takes 63.3 s, ranking second. Despite it taking 9.1 s more than the IRRT* algorithm, the maximum instantaneous steering angle recorded was only 8.95°, an increase of 80.43%, which greatly improved its flight stability and safety. In the dynamic environment, in spite of the fusion algorithm, the UAV was less stable in the static environment, and the change of heading angle also had several cases of turns that were too fast. The maximum turning angle registered was only 23.94°, which was within the acceptable range. The required time was 72.67 s, which was 13.67% shorter than the APF algorithm and 85.03% higher in smoothness.
Despite an enhanced performance and high practicability in static and dynamic environments of the fused APF-IRRT* algorithm, UAVs need more sensitive reaction speeds and smooth paths to maintain high mobility in the disaster environment. Therefore, the next research step is to optimize the mathematical model and algorithm to overcome the bottleneck so that the convergence speed will not change when it is reduced to a certain extent. More importantly, obstacles can be in various forms, while this paper only uses the shape of clouds—which needs to be improved in future research.