Next Article in Journal
Aerodynamic Hinge Moment Characteristics of Pitch-Regulated Mechanism for Mars Rotorcraft: Investigation and Experiments
Previous Article in Journal
Neural Network and Extended State Observer-Based Model Predictive Control for Smooth Braking at Preset Points in Autonomous Vehicles
Previous Article in Special Issue
Probabilistic Chain-Enhanced Parallel Genetic Algorithm for UAV Reconnaissance Task Assignment
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Research on Multi-UAV Cooperative Dynamic Path Planning Algorithm Based on Conflict Search

1
College of Automation Engineering, Nanjing University of Aeronautics and Astronautics, Nanjing 210016, China
2
School of Automation, Northwestern Polytechnical University, Xi’an 710129, China
*
Author to whom correspondence should be addressed.
Submission received: 13 May 2024 / Revised: 5 June 2024 / Accepted: 17 June 2024 / Published: 20 June 2024

Abstract

:
Considering of the dynamic cooperative path planning problem of multiple UAVs in complex environments, this paper further considers the flight constraints, space coordination, and fast re-planning of UAVs after detecting sudden obstacles on the basis of conflict-based search algorithm (CBS). A sparse CBS-D* algorithm is proposed as a cooperative dynamic path planning algorithm for UAVs in sudden threats. The algorithm adopts the two-layer planning idea. At the low layer, a sparse D* algorithm, which can realize the 3D dynamic path planning of UAVs, is proposed by combining the dynamic constraints of UAVs with the D* algorithm. At the high layer, heuristic information is introduced into the cost function to improve the search efficiency, and a dynamic response mechanism is designed to realize rapid re-planning in the face of sudden threats. The simulation results show that the proposed algorithm can deal with the UAV cooperative dynamic path planning problem in a complex environment more quickly and effectively.

1. Introduction

The unmanned aerial vehicle (UAV) cluster is widely used in various complex tasks. However, various threats in complex environments make it difficult for drone swarms to accomplish their tasks efficiently. Therefore, the dynamic path planning algorithm of a drone swarm in complex environment is the basis of multi-UAV task completion. The goal of multi-aircraft cooperative dynamic path planning is to find a set of conflict-free optimal paths that meet flight constraints and quickly replan the optimal paths when encountering sudden threats.
Current path planning algorithms can be divided into traditional algorithms and intelligent algorithms [1]. Traditional algorithms include the A* algorithm [2], artificial potential field method [3], fast expanding random tree [4], and corresponding improved algorithms. This kind of traditional algorithm has simple mathematical principles, fast operation speed, and good stability. For example, the A* algorithm can quickly find the global optimal path that meets the requirements by using the heuristic information. The literature [5] proposed a multi-objective point path planning algorithm based on global static programming. First, the A* algorithm was optimized for bidirectional smoothing, and the distance of each path was calculated. Secondly, according to the distance, the ant colony algorithm was used to sort multiple targets and plan the global optimal path. In addition, for a dynamic environment, the D* algorithm retains the information of initial planning on the basis of the A* algorithm, thus improving the speed of re-planning. In the literature [6], UAV attitude angle information was integrated into the D* algorithm to solve the problem of re-planning the penetration path of a single UAV. In the literature [7], a strategy of deleting redundant nodes was developed to improve the solving efficiency of rapidly expanding random trees and to realize dynamic obstacle and collision avoidance algorithms for multiple UAVs. The literature [8] proposed a cooperative path planning algorithm for multiple UAVs based on co-evolutionary optimization and combined the optimal individual selection strategy and mixed selection strategy to effectively solve the cooperative path planning problem of multiple UAVs in complex environments. A path planning algorithm was proposed for underwater vehicles based on an improved rapidly expanding random tree [9]. The artificial potential field (APF) algorithm was introduced into the heuristic function of bidirectional RRT to improve the scaling efficiency as a global path. The literature [10] proposed a hybrid path planning algorithm to solve the navigation problem of mobile robots in the presence of unpredictable obstacles. However, traditional algorithms have many limitations in solving multi-machine path planning problems; for example, it is difficult to give effective solutions when the objective functions and constraints are too complex, and it is easy to fall into local optimization, which is not suitable for large-scale problems [11]. Specifically, for example, the A* algorithm is too inefficient when the search space is too large, and it is often applied to the path planning of a single UAV. Intelligent algorithms mainly include the genetic algorithm [12], particle swarm algorithm [13], swarm algorithm [14], and reinforcement learning algorithm [15]. Compared with traditional algorithms, intelligent algorithms are more adaptable and robust and can better deal with path planning problems in uncertain environments [16]. A genetic multi-robot path planning (GMPP) algorithm was proposed in reference [17]. In order to solve the problem of collision during work, GMPP introduces a central planner to realize crash-free driving between multiple robots through two mechanisms of collision detection and collision elimination. The literature [18] considered the space and time constraints between multiple UAVs, established a multi-constrained target optimization model, and then solved the multi-UAVs path planning problem by using an improved gray wolf algorithm. Deep learning was combined with the genetic algorithm to improve the problem of slow convergence of the genetic algorithm in multi-UAV path planning in a 3D environment [19]. However, intelligent algorithms often have high computational complexity, high hardware requirements, and poor convergence when dealing with multi-machine dynamic path planning in complex environments.
The multi-UAV cooperative path planning problem is essentially a kind of multi-agent path planning problem with special constraints. The conflict-based search algorithm is an optimal two-layer, multi-agent path planning algorithm [20], which has been widely applied in storage robot systems [21]. The core idea is to decompose the multi-agent path planning problem into a large number of restricted, single-agent path planning problems. The algorithm is divided into two layers. The lower layer plans the path for each agent independently and then discusses the solution of the conflict by generating new nodes through a binary tree in the upper layer. Each node of the binary tree represents a solution to the conflict; that is, one of the conflicting agents avoids the path point where the conflict occurs. In this way, CBS discusses both solutions to each conflict, ensuring the completeness of the algorithm. In addition, optimality is guaranteed by adopting the best first-search algorithm at the highest layer. On the basis of not destroying the optimal completeness of CBS, researchers have put forward various improved methods of acceleration algorithms. Aiming at multi-agent path planning in dynamic environment, the literature [22] replaced the CBS low-layer A* algorithm with a D*-lite algorithm, proposing an incremental multi-agent path planning algorithm. The literature [23] proposed an enhanced CBS algorithm (ECBS) that replaced the best first-search algorithm in the high and low layers of CBS with focus search. Based on ECBS, Li et al. [24] further replaced focus search with explicit estimation search and proposed a new bounded suboptimal variant of CBS called explicit estimation CBS (EECBS). Considering of the space and time conflicts of multiple UAVs in complex environments, the literature [25] proposed a multi-conflict-based cooperative path planning algorithm for multiple UAVs—a multi-conflict-based search algorithm. The synergistic conflict between UAVs was solved, and the path searching efficiency was improved.
However, the current planning space of CBS and its improved algorithm is mainly a grid environment, and there is no precedent for its application in complex three-dimensional environments. Therefore, this paper encounters many problems to be solved when implementing multi-aircraft cooperative dynamic path planning in complex environments through CBS. The main problems are as follows: (1) The flight constraints of UAS need to be comprehensively considered; (2) the conflict between UAV paths lacks definition; and (3) the traditional reprogramming algorithm is difficult to apply to the reprogramming problem in a 3D environment.
The main contributions of our work are as follows:
(1)
The flight coordination constraints and conflicts of multiple UAVs in the three-dimensional space environment are comprehensively analyzed, and a CBS-based framework for a multi-UAV cooperative dynamic path planning algorithm is constructed;
(2)
A sparse D* algorithm for UAV dynamic path planning in complex environments is proposed, which reduces the time of path search in case of sudden threats;
(3)
The search efficiency is improved by heuristic information, and a dynamic response mechanism is designed to realize the dynamic path planning of multiple UAVs facing sudden threats.
The arrangement of this paper is as follows: In Section 1, the multi-constrained objective optimization model of multi-UAV cooperative path planning is established, and the flight constraints and cooperative constraints in the model are analyzed. In Section 2, a sparse CBS-D*-based multi-UAV dynamic path planning algorithm is designed, and the implementation ideas and measures are given. In Section 3, we evaluate the performance of the proposed algorithm through simulation experiments; finally, the final conclusion of this paper is given in Section 4.

2. Problem Description

Multi-UAV dynamic path planning aims to find a set of safe, flyable, and conflict-free paths for the UAV group according to the mission requirements of the UAV cluster, comprehensively considering the threat constraints of the flight environment, such as terrain and air defense units, as well as the flight performance constraints and the constraints within the cluster. In addition, when the UAV group encounters sudden obstacles, the initial planning information can be used to quickly re-plan a group of safe flying paths for the UAV group. Therefore, the multi-machine cooperative path planning problem can be regarded as a constrained optimization problem, which can be described as follows:
min   J ( P / E )     s . t . { g ( P ) 0 h ( P ) = 0
where E is the environment during path planning; g ( P ) and h ( P ) is the inequality constraint and equality constraint that comprehensively consider the flight constraint of UAVs, battlefield environment, and intra-cluster constraint; P is a path set that satisfies the constraint of this problem, which can be expressed as P = {p1, p2, ···, pN}; Pi is the path of the i th UAV; N is the number of UAVs; and J ( P / E ) is the total path cost of the path set P in the current environment E . The following introduces the threat constraint, flight constraint, and intra-cluster constraint in the environment.

2.1. Environmental Threat Analysis

The threat of UAV in flight mainly comes from five aspects: mountains in the terrain, air defense radars, surface-to-air missiles, air defense artillery, and no-fly zone. In this paper, the digital elevation map that records the real terrain data is used to construct the battlefield environment. Then, on the basis of the existing terrain, the radar model with terrain-shielding blind area and the hit probability model of surface-to-air missile and anti-aircraft artillery are further constructed. Finally, the no-fly zone is represented in the form of a quadrangular column. The result is a complex environment, as shown in Figure 1.

2.2. Flight Constraint Analysis

An important problem in multi-UAV path planning is to consider the flight constraints due to the physical characteristics of the aircraft, such as flight speed, altitude, and overload. The setting of constraints is the key to whether the path at the final planning is flyable.
This paper mainly considers the following five kinds of UAV flight constraints to represent the UAV motion process:
(1)
Minimum turning radius constraint r: Due to the constraints of maneuvering conditions, the turning radius of the UAV needs to be greater than the minimum turning radius;
(2)
Minimum path segment length constraint dS: The minimum path segment length is the minimum distance that the UAV must fly before changing its flight attitude during flight. In path planning, the unit step size of the planned path can be set to be greater than the minimum path segment length so as to meet the minimum path segment length constraint;
(3)
Maximum path slope angle constraint θ: Because the UAV is constrained by engine performance and flight safety, the ascending and diving angles of the path in the vertical direction are also restricted, so the planned flight path of the UAV must meet the maximum path slope angle constraint within the unit path step size;
(4)
Minimum ground clearance constraint z: In order to ensure the safe flight of the UAV and avoid collision with the ground or low-altitude obstacles, the minimum ground clearance constraint needs to be set to make the flight height of the UAV greater than the minimum ground clearance and ensure flight safety;
(5)
Average speed constraint v: Considering the control optimization of the speed system, the flight speed of the UAV can be adjusted quickly. Therefore, the average speed of each UAV passing through different path segments is set to be the same in this paper; that is, it takes the same time to pass through different path segments.

2.3. Cooperative Constraint and Conflict Analysis

The path planning of multiple UAVs not only meets the single flight constraints but also needs to meet the cooperative constraints between multiple aircraft, which means there can be no spatial conflict between multiple machines. Combined with the average velocity constraints assumed above, this paper divides spatial conflicts into the following two categories.
Point conflict: Point conflict is shown in Figure 2. The points in the figure are path points. When two aircraft are at the same path point at the same time, or the distance between two points at the same time is less than the safe distance, point conflict occurs.
Edge conflict: As shown in Figure 3, the edge is an edge formed by connecting two path points before and after. When the distance between the points on the edge formed by the path points before and after two aircraft at the same time is less than the safe distance, the edge conflict occurs.
Spatial cooperative conflict can be expressed as ( a i , a j , t , D s a f e ) , which means that the distance between the UAV a j and the UAV ai is less than the safe distance in the path point at the moment t. The space restriction can be expressed as the waypoint ( a i , v i , t ) , where v i is the waypoint of ai at the time of conflict, which means that the drone is prohibited from being at the waypoint vi at time t.

3. Design of Multi-UAV Dynamic Path Planning Algorithm Based on CBS-D*

In this section, a new sparse CBS-D* algorithm is proposed, which can effectively solve the dynamic path planning problem of multiple UAVs in a complex 3D environment. The algorithm in this paper is based on CBS and replaces the A* algorithm with the sparse D* algorithm at the lowest layer. At the highest layer, heuristic information is introduced, and the dynamic response mechanism is utilized. Finally, multi-machine path planning for a sudden threat in a 3D environment is realized. The lowest-layer and the highest-layer algorithms are described below.

3.1. Low-Layer Planning Design Based on Improved Sparse D* Algorithm

CBS uses the A* algorithm as a low-layer algorithm. However, the A* algorithm cannot take advantage of the information previously searched. CBS-D*-lite changes the low-layer algorithm from A* to D*-lite to implement iterative search. However, the D*-lite algorithm is a kind of path planning algorithm that is mainly applied in a raster environment and is not suitable for a three-dimensional, complex environment. In order to realize constrained UAV path planning in a 3D environment, an improved sparse D* algorithm was designed for the low layer. Different from the traditional D*, the sparse D* algorithm considers the dynamic constraints such as the minimum turning radius, the maximum climb height, and maximum dive height of UAV when expanding nodes and obtains a real and feasible expansion point. This can not only improve the feasibility of the search path but also limit the number of expansion points and improve the search efficiency.
(1)
Waypoint search method design
When the algorithm searches the path, a path search tree composed of path points is formed with the starting point as the root node. First, the node with the least cost in the search tree is selected as the current path point, and then, the successor path point is calculated according to the flight constraints of the UAV. The waypoints extend horizontally, as shown in Figure 4.
In Figure 4, d S is the unit step length of the waypoint, and r min is the minimum turning radius of the UAV. The coordinates of the next-generation extended waypoint ( S n n + 1 , S n n + 2 , S n n + 3 ) can be calculated by the following formula:
d ψ = d S / R min
c = R min 2 ( 1 cos ( d ψ ) )
S n n + 3 = S n + [ c cos ( ψ 0.5 d ψ ) c sin ( ψ 0.5 d ψ ) d ψ ]
S n n + 2 = S n + [ d S cos ( ψ ) d S sin ( ψ ) 0 ]
S n n + 1 = S n + [ c · cos ( ψ + 0.5 d ψ ) c · sin ( ψ + 0.5 d ψ ) d ψ ]
Then, based on the maximum path slope angle, the maximum climb height and maximum dive height of the aircraft can be calculated, and the subsequent path points of the upper and lower layers can be calculated. We continue to select the least costly waypoint for the next round of waypoint search. In the end, a path search tree is formed from the starting point to the destination point.
(2)
Path research
Path research is based on the accessed path-point information that is not affected in the initial path planning process. Incremental re-planning is realized through local correction, which can improve the efficiency of the path planning algorithm and reduce the calculation amount. During re-planning, the algorithm inherits the previous planned path search tree from the high layer. After inheriting the search tree, the algorithm will delete the waypoints affected by the burst threat and its subsequent sub-waypoints. The deletion process is shown in Figure 5. When the UAV is flying along the initial planned path, and it detects a sudden obstacle in front of it at the path point S, it only needs to re-plan the route from the black node area to the current location of the UAV node S, and the black path point found based on the initial planning is still available.
The aim of the low-layer search is to find the path that satisfies the constraints given by the high layer and, finally, find the path that satisfies the conflict-free requirement. By treating constraints as sudden obstacles to prune the previously preserved path search tree, iterative search can be realized at the low layer.

3.2. High-Layer Planning and Design Based on Search Algorithm

The high-layer search is performed on a restricted tree. A limit tree is a binary tree in which each node contains a limit set, a path set, a current cost, and the low-layer search tree set. The global feasible solution occurs only when there is no conflict between any set of paths in the path set. If a conflict (ai, aj, t, Dsafe) occurs in the path set, two limits ( a i , v i , t ) and ( a j , v i , t ) are generated. For each of these two restrictions, the current tree node generates two successor tree nodes and adds the corresponding restriction to its set of restrictions. In addition, the search tree of the previous planning for each UAV is retained in the tree node, and then, the initial information of the search tree is used for low-layer rapid re-planning. On this basis, this paper further introduces the cooperative violation into the cost function and designs the dynamic response mechanism.
(1)
Cost function design
In order to reduce the search space and the time to find the optimal solution, the cooperative violation is designed to be added into the cost function as the heuristic information. Compared with the original cost function, the improved cost function can better guide the algorithm to search in the direction with fewer conflicts and reduce the search space. For a UAV group composed of N UAVs, conflict detection can be carried out on the path pairwise corresponding to N UAVs, and the cooperative violation quantity can be constructed by the sum of the number of path set conflicts as follows:
v i o = i = 1 N 1 j = i + 1 N n i j
where v i o represents the spatial cooperative violation value of the UAV group cooperative track, and n i j represents the number of conflicts caused by the collision detection between the i th UAV track and the j th UAV track.
The final total cost function is shown in Equation (8):
C = i = 1 n l i + ω v · v i o
where l i is the length of the path of the i th drone, and ω v is the penalty factor.
(2)
Dynamic response mechanism design
Considering of the problem of dynamic cooperative path planning for emergent threats, this paper designs a dynamic response mechanism to accelerate the process of dynamic cooperative path re-planning. The dynamic response mechanism process is shown in Figure 6.
When a sudden threat occurs, the path that is not affected by the sudden threat will be used as the initial path in the re-plan, and the path that is affected by the sudden threat will be re-constructed by the low-layer sparse D* algorithm. The cooperative path to be searched by UAVs that do not encounter sudden threats is not much different from the static cooperative path originally planned and often only needs to be adjusted in some parts. Therefore, by inheriting the original path, the number of conflicts between paths can be reduced, the convergence speed can be accelerated, and the path re-planning against sudden threats can be realized.

3.3. Design of Dynamic Cooperative Path Planning Algorithm

Considering of the dynamic environment with emergent threats, this paper adopts the framework of pre-planning and then dynamic planning to solve the UAV dynamic cooperative path planning problem. By introducing a static cooperative path as the initializing path of the information construction algorithm in a dynamic environment, the efficiency of path planning is improved. The block diagram of UAV dynamic cooperative path planning is shown in Figure 7.
Firstly, static cooperative path planning is carried out to plan the constrained cooperative path for each UAV. Then, each UAV flies to the target point with the cooperative path as the reference. Firstly, the path of the UAV is judged regarding whether it is affected by sudden obstacles during initialization. If it is affected, the path is planned again through the sparse D* algorithm; if it is not affected, the path in the static environment is used as the initial path. After the initialization is completed, the conflict-free cooperative path satisfying the requirements is solved again. The drones then continue to fly towards the target point using the re-planned cooperative path as a reference while continuing to monitor the environment until they reach the target point. The pseudo-code of UAV dynamic cooperative path planning is shown in Table 1.

4. Simulation Analysis

4.1. Simulation Condition Design

Based on the battlefield environment space model established in Section 2, this section uses the same task scenario to simulate the static path, dynamic path, and algorithm effectiveness. The flight constraint parameter settings of the UAVs are shown in Table 2.

4.2. Improved Sparse D* Algorithm Validity Verification Analysis

In this paper, an improved sparse D* algorithm is used at a low layer to solve the UAV path planning problem and accelerate the re-planning search efficiency in a 3D environment.
In order to verify the effectiveness of the algorithm, this paper simulates the single-machine path re-planning under the appeal simulation scenario. The simulation results are shown in Figure 8.
As can be seen from Figure 8a, during the initial planning, the algorithm generates a path search tree. Then, as shown in Figure 8b, after the UAV encounters sudden threats, the sparse D* algorithm will inherit the initial path search tree and then trim it as the initial information during re-planning. Finally, the search tree after the final re-planning is shown in Figure 8c. As shown in Table 3, when encountering sudden threats, the expanded new node tree of the improved sparse D* algorithm in this paper reduces by 21.93% compared with reusing the sparse A* algorithm.

4.3. Sparse CBS-D* Algorithm Validity Verification Analysis

  • Simulation verification 1. Cooperative path planning for five UAVs
In order to fully verify the effectiveness of the designed sparse CBS-D* algorithm, this paper designs the task scenario shown in Table 4. The effectiveness of the sparse CBS-D* algorithm is verified by a cooperative path planning scenario in which five UAVs arrive at the same designated location from different locations.
The simulation results are shown in Figure 9, and the shortest distance between any UAV paths is shown in Figure 10.
Figure 9a shows the global static path planned by the UAV group before the sudden obstacle appeared, and the UAV group avoided the obstacle successfully. Figure 9b shows that at the 9th time unit, a sudden cylindrical obstacle with a height of 120 and a radius of 50 appeared at the 5th path point of the 3rd UAV, blocking the path of multiple UAVs. Figure 9c shows the cooperative path re-planned by the UAV group for the sudden obstacle, which allowed avoiding the sudden obstacle successfully. Figure 10 shows that the algorithm ensures that the shortest distance between UAV paths is greater than the specified safe distance during initial planning and re-planning.
In addition, in order to further verify the superiority of the algorithm, a naive sparse CBS algorithm was proposed as a comparison. The sparse CBS algorithm adopts a sparse A* algorithm at the low layer, and when encountering sudden obstacles, the sparse CBS algorithm is re-used for new planning. As shown in Table 5, compared with the common sparse CBS, the heuristic information and dynamic response mechanism introduced at the high layer can make use of the information more efficiently in the previous planning and greatly reduce the number of conflicts to be dealt with in the planning. The low-layer sparse D* algorithm can speed up the path search process and reduce the time of conflict processing.
  • Simulation verification 2. Cooperative path planning for ten UAVs
The environmental space of 500 km ∗ 500 km ∗ 6 km in a certain area was selected as the setting area of the battlefield, and the terrain was constructed with digital elevation information. The horizontal direction unit 1 represents 500 m, and the vertical direction unit 1 represents 50 m. Five threats were designed, which include environmental threats: two radar threats, two air defense fire threats, air defense missile threats, and no-fly zones. The parameters of each threat are shown in Table 6. The specific coordinates of the starting point and target point of each UAV are shown in Table 7. The red dot is the starting point of each UAV, and the blue dot is the target point of each UAV. The simulation results are shown in Figure 11.
In Figure 11, Figure 11a,b show the global static path planned by the UAV group before the sudden obstacle appeared, and the UAV group successfully avoided the obstacle set. Figure 11c,d show that a sudden cylindrical obstacle with a height of 120 and a radius of 60 appeared at the 20th path point of the 5th UAV at the 10th time unit. Figure 11e,f show that coordinated path re-planned for the UAV group to deal with the sudden obstacle, which avoided the sudden obstacle successfully. In addition, the D*-lite algorithm obtained the path search tree from the target point to the start point in the global static path planning by searching from the target point to the start point. When the UAV encounters sudden threats while flying along the originally planned path, the path search tree is pruned and then re-planned. The static path that is not affected by sudden obstacles is taken as the initial path of the UAV in the CBS algorithm initialization, which improves the planning efficiency and speed of dynamic path planning.

5. Conclusions

A sparse CBS-D* algorithm is proposed to deal with the dynamic cooperative path planning of multiple UAVs in complex environments. On the basis of the traditional CBS algorithm, combined with the idea of iterative search, the high and low layers of the algorithm were improved. At the lower layer, this study designed a sparse D* algorithm based on UAV dynamics constraints to realize iterative path planning for a single UAV. At the high layer, heuristic information was introduced into the cost function, and a dynamic response mechanism was designed to realize dynamic reprogramming after encountering sudden obstacles. The comparison of simulation results shows that the proposed method can realize multi-UAV cooperative dynamic path planning of sudden threats based on the previous planning information, improve the algorithm search efficiency, and accelerate the algorithm convergence speed.
Considering UAV cooperative path planning in dynamic environments, this paper mainly focuses on spatial cooperation, but in fact, the task also has certain requirements for the time cooperation of UAV. Therefore, based on the research in this paper, we can further consider the time coordination among UAVs and study UAVs cooperative path planning in four-dimensional space.

Author Contributions

Conceptualization, Z.W. and H.G.; data curation, Z.W.; formal analysis, Z.W.; funding acquisition, X.L.; investigation, Z.W. and H.G.; methodology, Z.W.; project administration, Z.W.; resources, Z.W. and M.N.; software, Z.W.; supervision, Z.W., H.G. and X.L.; validation, Z.W.; visualization, Z.W.; writing—original draft, Z.W., M.N. and X.L.; writing—review and editing, Z.W. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Data are contained within the article.

Acknowledgments

Gratitude is extended to the Shaanxi Province Key Laboratory of Flight Control and Simulation Technology.

Conflicts of Interest

The authors declare that they have no known competing financial interests or personal relationships that could have appeared to influence the work reported in this paper.

References

  1. Suh, J.; Gong, J.; Oh, S. Fast sampling-based cost-aware path planning with nonmyopic extensions using cross entropy. IEEE Trans. Robot. 2017, 33, 1313–1326. [Google Scholar] [CrossRef]
  2. Wang, R.; Wei, W.; Yang, M.; Liu, W. Task allocation of multiple UAVs considering cooperative route planning. Acta Aeronaut. Astronaut. Sin. 2020, 41, 724234. [Google Scholar]
  3. Ma’Arif, A.; Rahmaniar, W.; Vera, M.A.M.; Nuryono, A.A.; Majdoubi, R.; Çakan, A. Artificial potential field algorithm for obstacle avoidance in uav quadrotor for dynamic environment. In Proceedings of the 2021 IEEE International Conference on Communication, Networks and Satellite (COMNETSAT), Purwokerto, Indonesia, 17–18 July 2021; pp. 184–189. [Google Scholar]
  4. Lee, H.; Lee, D.; Shim, D.H. Receding horizon-based RRT* algorithm for a UAV real-time path planner. In Proceedings of the AIAA Information Systems-AIAA Infotech@ Aerospace, Grapevine, TX, USA, 9–13 January 2017; p. 0676. [Google Scholar]
  5. Guo, J.; Huo, X.; Guo, S.; Xu, J. A Path Planning Method for the Spherical Amphibious Robot Based on Improved A-star Algorithm. In Proceedings of the 2021 IEEE International Conference on Mechatronics and Automation (ICMA), Takamatsu, Japan, 8–11 August 2021; pp. 1274–1279. [Google Scholar] [CrossRef]
  6. Zhang, Z.; Wu, J.; Dai, J.; He, C. A novel real-time penetration path planning algorithm for stealth UAV in 3D complex dynamic environment. IEEE Access 2020, 8, 122757–122771. [Google Scholar] [CrossRef]
  7. Zu, W.; Fan, G.; Gao, Y.; Ma, Y.; Zhang, H.; Zeng, H. Multi-UAVs Cooperative Path Planning Method based on Improved RRT Algorithm. In Proceedings of the 2018 IEEE International Conference on Mechatronics and Automation (ICMA), Changchun, China, 5–8 August 2018; pp. 1563–1567. [Google Scholar] [CrossRef]
  8. Wu, Y.; Nie, M.; Ma, X.; Guo, Y.; Liu, X. Co-Evolutionary Algorithm-Based Multi-Unmanned Aerial Vehicle Cooperative Path Planning. Drones 2023, 7, 606. [Google Scholar] [CrossRef]
  9. Zhu, J.; Zhao, S.; Zhao, R. Path Planning for Autonomous Underwater Vehicle Based on Artificial Potential Field and Modified RRT. In Proceedings of the 2021 International Conference on Computer, Control and Robotics (ICCCR), Shanghai, China, 8–10 January 2021; pp. 21–25. [Google Scholar] [CrossRef]
  10. Han, L.; Wu, X.; Sun, X. Hybrid path planning algorithm for mobile robot based on A* algorithm fused with DWA. In Proceedings of the 2023 IEEE 3rd International Conference on Information Technology, Big Data and Artificial Intelligence (ICIBA), Chongqing, China, 26–28 May 2023; pp. 1465–1469. [Google Scholar] [CrossRef]
  11. Zhang, H.; Gan, X.; Mao, Y.; Yang, C.; Xie, X. Review of UAV Obstacle Avoidance Algorithms. Aero Weapon. 2021, 28, 53–63. [Google Scholar]
  12. Zhou, Z.; Luo, D.; Shao, J.; Xu, Y.; You, Y. Immune genetic algorithm based multi-UAV cooperative target search with event-triggered mechanism. Phys. Commun. 2020, 41, 101103. [Google Scholar] [CrossRef]
  13. He, W.; Qi, X.; Liu, L. A novel hybrid particle swarm optimization for multi-UAV cooperate path planning. Appl. Intell. 2021, 51, 7350–7364. [Google Scholar] [CrossRef]
  14. Liang, J.-H.; Lee, C.-H. Efficient collision-free path-planning of multiple mobile robots system using efficient artificial bee colony algorithm. Adv. Eng. Softw. 2015, 79, 47–56. [Google Scholar] [CrossRef]
  15. Qu, C.; Gai, W.; Zhong, M.; Zhang, J. A novel reinforcement learning based grey wolf optimizer algorithm for unmanned aerial vehicles (UAVs) path planning. Appl. Soft Comput. 2020, 89, 106099. [Google Scholar] [CrossRef]
  16. Yan, J.; Zhang, Q.; Hu, X. Review of Path Planning Techniques Based on Reinforcement Learning. Comput. Eng. 2021, 47, 16–25. [Google Scholar]
  17. Fan, M.; He, J.; Ding, S.; Ding, Y.; Li, M.; Jiang, L. Research and Implementation of Multi-robot Path Planning Based on Genetic Algorithm. In Proceedings of the 2021 5th International Conference on Automation, Control and Robots (ICACR), Nanning, China, 25–27 September 2021; pp. 140–144. [Google Scholar] [CrossRef]
  18. Xu, C.; Xu, M.; Yin, C. Optimized multi-UAV cooperative path planning under the complex confrontation environment. Comput. Commun. 2020, 162, 196–203. [Google Scholar] [CrossRef]
  19. Pan, Y.; Yang, Y.; Li, W. A Deep Learning Trained by Genetic Algorithm to Improve the Efficiency of Path Planning for Data Collection With Multi-UAV. IEEE Access 2021, 9, 7994–8005. [Google Scholar] [CrossRef]
  20. Guni, S.; Roni, S.; Ariel, F.; Sturtevant, N.R. Conflict-based search for optimal multi-agent pathfinding. Artif. Intell. 2015, 219, 40–66. [Google Scholar]
  21. Li, J.; Tinka, A.; Kiesel, S.; Durham, J.W.; Kumar, T.K.S.; Koenig, S. Lifelong Multi-Agent Path Finding in Large-Scale Warehouses. In Proceedings of the AAMAS 2020, Online, 9–13 May 2020; pp. 1898–1900. [Google Scholar]
  22. Fatih, S.; Faruk, P. Incremental multi-agent path finding. Future Gener. Comput. Syst. 2021, 116, 220–233. [Google Scholar] [CrossRef]
  23. Barer, M.; Sharon, G.; Stern, R.; Felner, A. Suboptimal Variants of the Conflict-Based Search Algorithm for the Multi-Agent Pathfinding Problem. In Proceedings of the Annual Symposium on Combinatorial Search (SoCS), Prague, Czech Republic, 15–17 August 2014; pp. 19–27. [Google Scholar]
  24. Li, J.; Wheeler, R.; Sven, K. Eecbs: A bounded-suboptimal search for multi-agent path finding. In Proceedings of the AAAI Conference on Artificial Intelligence (AAAI), Virtually, 2–9 February 2021. [Google Scholar]
  25. Liu, X.; Su, Y.; Wu, Y.; Guo, Y. Multi-Conflict-Based Optimal Algorithm for Multi-UAV Cooperative Path Planning. Drones 2023, 7, 217. [Google Scholar] [CrossRef]
Figure 1. Battlefield environment.
Figure 1. Battlefield environment.
Drones 08 00274 g001
Figure 2. Schematic diagram of point conflict.
Figure 2. Schematic diagram of point conflict.
Drones 08 00274 g002
Figure 3. Schematic diagram of edge conflict.
Figure 3. Schematic diagram of edge conflict.
Drones 08 00274 g003
Figure 4. Expansion diagram of horizontal path point.
Figure 4. Expansion diagram of horizontal path point.
Drones 08 00274 g004
Figure 5. Schematic diagram of path re-plan.
Figure 5. Schematic diagram of path re-plan.
Drones 08 00274 g005
Figure 6. Process diagram of dynamic response mechanism.
Figure 6. Process diagram of dynamic response mechanism.
Drones 08 00274 g006
Figure 7. Block diagram of UAV dynamic cooperative path planning.
Figure 7. Block diagram of UAV dynamic cooperative path planning.
Drones 08 00274 g007
Figure 8. Diagram of path search tree. (a) Initial path search tree; (b) pruned path search tree; (c) reconstructed search tree.
Figure 8. Diagram of path search tree. (a) Initial path search tree; (b) pruned path search tree; (c) reconstructed search tree.
Drones 08 00274 g008
Figure 9. Simulation diagram of multi-machine dynamic cooperative penetration. (a) Flying normally; (b) encountering a sudden obstacle; (c) re-planning the cooperative path.
Figure 9. Simulation diagram of multi-machine dynamic cooperative penetration. (a) Flying normally; (b) encountering a sudden obstacle; (c) re-planning the cooperative path.
Drones 08 00274 g009aDrones 08 00274 g009b
Figure 10. The shortest distance between all UAV paths.
Figure 10. The shortest distance between all UAV paths.
Drones 08 00274 g010
Figure 11. Simulation diagram of ten drones dynamic cooperative penetration. (a) Flying normally, top view; (b) flying normally, 3D view; (c) encountering a sudden obstacle, top view; (d) encountering a sudden obstacle, 3D view; (e) re-planning the cooperative path, top view; (f) re-planning the cooperative path, 3D view.
Figure 11. Simulation diagram of ten drones dynamic cooperative penetration. (a) Flying normally, top view; (b) flying normally, 3D view; (c) encountering a sudden obstacle, top view; (d) encountering a sudden obstacle, 3D view; (e) re-planning the cooperative path, top view; (f) re-planning the cooperative path, 3D view.
Drones 08 00274 g011
Table 1. Pseudo code of UAV dynamic cooperative path planning.
Table 1. Pseudo code of UAV dynamic cooperative path planning.
Input: Drone swarm D , Starting points set S , Target point T, Battlefield environment space E
Begin
// Static cooperative path planning
I n i t i a l _ p a t h s = I n i t i a l _ w i t h _ D * ( D , S , T , E ) ; // generate the shortest path by D*Lit
P a t h s = C B S D * ( D , S , T , E , I n i t i a l _ p a t h s ) ;
// find a conflict-free path for the CBS algorithm of D* algorithm in low layer
While P o s ( D ) ! = P o s ( T ) // before the drone reaches the target point
   U p d a t e _ P o s ( D , P a t h ) ; // drones fly along the cooperative path
   F l a g = E n v _ det e c t i o n ( ) ; // Continuously monitor the battlefield environment
  If F l a g = T r u e // a sudden threat occurs on the cooperative path
    u s e f u l _ p a t h s = f i n d _ u s e f u l _ p a t h ( P a t h s ) ; // Find a path that is not affected by threats
   Initial_paths = Initial_with_D*(D,S,T,E,useful_paths); // reinitialize
   Paths = CBSD*(D,S,T,E,Initial_paths) ; // a conflict-free path is found
  End
End
End
Table 2. Flight constraint parameter settings.
Table 2. Flight constraint parameter settings.
Flight ConstraintParameter Value (Unit: 0.5 km)
Safe distance 15
Minimum path segment length 50
Minimum turning radius50
Minimum ground clearance5
Table 3. Statistics table for the number of new expanded nodes.
Table 3. Statistics table for the number of new expanded nodes.
AlgorithmThe Number of New Expanded Nodes
Sparse A* algorithm2485
Sparse D* algorithm1940
Table 4. Setting of the task scenario parameter.
Table 4. Setting of the task scenario parameter.
TypeParameter Value
Starting point coordinatesUAV 0: [50 200 60]
UAV 1: [200 100 70]
UAV 2: [500 50 110]
UAV 3: [700 100 80]
UAV 4: [900 50 100]
Target point coordinates[700 900 80]
Safe distance (unit: 0.5 km)20
Table 5. The number of conflicts and the time taken by different algorithms.
Table 5. The number of conflicts and the time taken by different algorithms.
AlgorithmThe Number of Conflicts during Initial PlanningInitial Planning Time (Unit: s)The Number of Conflicts during Re-PlanningRe-Planning Time (Unit: s)
Sparse CBS159.896.1
Sparse CBS-D*103.920.9
Table 6. Threat related parameters.
Table 6. Threat related parameters.
Threat TypePosition CoordinateThreat Radius (Unit: 0.5 km)
Radar 0[300,400,20]160
Radar 1[700,600,25]140
Air defense missile[400,750,20]120
Air defense fire 0[600,180,25]60
Air defense fire 1[750,320,20]60
No-fly zonep1 = [520,320]; p2 = [620,340];
p3 = [600,430]; p4 = [520,430].
Table 7. Specific starting and target coordinates for each drone.
Table 7. Specific starting and target coordinates for each drone.
Drone NumberStarting Points CoordinateTarget Points Coordinate
UAV 0[860,50,60][40,950,85]
UAV 1[820,50,60][80,950,85]
UAV 2[780,50,60][120,950,85]
UAV 3[740,50,60][160,950,85]
UAV 4[700,50,60][200,950,85]
UAV 5[660,50,60][240,950,85]
UAV 6[620,50,60][280,950,85]
UAV 7[580,50,60][320,950,85]
UAV 8[540,50,60][360,950,85]
UAV 9[500,50,60][400,950,85]
UAV 10[860,50,60][40,950,85]
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, Z.; Gong, H.; Nie, M.; Liu, X. Research on Multi-UAV Cooperative Dynamic Path Planning Algorithm Based on Conflict Search. Drones 2024, 8, 274. https://0-doi-org.brum.beds.ac.uk/10.3390/drones8060274

AMA Style

Wang Z, Gong H, Nie M, Liu X. Research on Multi-UAV Cooperative Dynamic Path Planning Algorithm Based on Conflict Search. Drones. 2024; 8(6):274. https://0-doi-org.brum.beds.ac.uk/10.3390/drones8060274

Chicago/Turabian Style

Wang, Zhigang, Huajun Gong, Mingtao Nie, and Xiaoxiong Liu. 2024. "Research on Multi-UAV Cooperative Dynamic Path Planning Algorithm Based on Conflict Search" Drones 8, no. 6: 274. https://0-doi-org.brum.beds.ac.uk/10.3390/drones8060274

Article Metrics

Back to TopTop