Advances in UAV Path Planning: A Comprehensive Review of Methods, Challenges, and Future Directions
Abstract
1. Introduction
1.1. Background
1.1.1. Advancements in UAV Technology Development
1.1.2. The Significance and Challenges of UAV Path Planning
1.2. Motivation
2. Fundamentals and Categorization of UAV Path Planning
2.1. Problem Definition
- , , , … are weight coefficients for the respective objectives.
- represents the path length:
- denotes the energy consumption cost:
- is a cost function associated with collision risk or obstacle avoidance (e.g., penalizing the path when enters an unsafe region ).
Constraints in UAV Path Planning
- Environmental constraints: As a crucial restrictive factor within the UAV flight environment, environmental constraints cover a wide and complex range of elements. Static obstacles, such as terrain and landforms in natural geographical environments, and buildings in populated areas, are key components of this constraint. Dynamic obstacles, whose positions and motion states continuously change, include other UAVs, birds, and moving vehicles. In recent years, flight areas defined by management regulations and safety requirements have also become part of environmental constraints. These include no-fly zones [49] and restricted-fly zones, such as ecological protection areas [50].
- Physical constraints: Physical constraints [51] arise from the UAV’s inherent characteristics and performance limitations, directly defining the feasible range of its flight path. The UAV’s hardware configurations, such as the power system and propulsion device [52], determine key performance metrics like flight speed and endurance range. Furthermore, due to structural design considerations aimed at ensuring flight stability, some UAVs have specific restrictive conditions during maneuvers, such as minimum turning radius and maximum turning angle [53]. Additionally, there are constraints related to the UAV’s flight capabilities, including maximum acceleration and maximum flight altitude [54].
- Task constraints: Task constraints are directly associated with the specific missions assigned to UAVs. These typically include factors such as the priority of flight objectives and task time. The priority constraint becomes particularly relevant in practical applications where it is crucial to prioritize the swift execution of high-priority tasks during path planning [55]. To meet the time-sensitive nature of these tasks, other objectives, such as minimizing energy consumption and reducing flight distance, may need to be compromised to some extent.
- Energy reservation constraints: Energy consumption during UAV flight is influenced by multiple factors, including flight speed, altitude changes, flight attitude adjustments, and air resistance [56,57,58,59], all of which have a particularly significant impact. For instance, ref. [60] presents an effective energy-aware path planning method that efficiently navigates through uncertain and time-varying wind fields, designing a path that leverages the energy provided by these wind conditions.
2.2. Categorization of UAV Path Planning Approaches
2.2.1. Algorithmic Principle-Based Classification
- Deterministic algorithms: Deterministic algorithms follow fixed rules and steps, producing consistent results for the same input, making them predictable and stable. They are suitable for scenarios requiring high accuracy in path planning. Representative methods include graph search algorithms and optimization algorithms. In graph search algorithms, the Dijkstra algorithm finds the shortest path in a weighted graph using a greedy strategy and priority queue [61]. The A* algorithm combines breadth-first search with Dijkstra, using an evaluation function to prioritize nodes [62]. Linear programming, as an optimization algorithm, transforms the path planning problem into a mathematical model to maximize or minimize a linear objective under constraints.
- Random sampling algorithms: Random sampling algorithms construct a search framework by randomly sampling the space, making them effective for high-dimensional or complex environments [63]. A typical example is the RRT algorithm [64], which grows a tree from the start point by adding new nodes toward random points if they are collision-free. Variants like RRT* [65] optimize the path with a rewiring mechanism, while RRT-Connect [66] uses bidirectional search for improved efficiency in large spaces.
- Biologically inspired algorithms: Bio-inspired algorithms mimic natural behaviors to solve path planning problems. Examples include genetic algorithms, which simulate heredity and natural selection to evolve solutions [67]; PSO, which models the group foraging behavior of birds or fish [68,69]; and ACO, which mimics ant pheromone-based pathfinding [70].
- Hybrid algorithms: Hybrid algorithms combine different methods to overcome individual limitations, achieving better efficiency and quality in path planning. For instance, a hybrid of PSO and genetic algorithms improves 3D UAV path planning [71]. RRT-based hybrid methods enhance time efficiency [72], while RT-Dijkstra integrates RRT with deterministic planning for cluttered environments [73].
2.2.2. Environment-Based Classification
- Static environment path planning: Static environment path planning generates collision-free paths in settings with stationary obstacles, assuming fixed positions and geometries. It computes an optimal path from a start to a target location and is widely used in indoor robotic navigation [74], warehouse logistics [75], and autonomous mobility systems [76]. Its key advantage is computational efficiency, as the derived path requires no real-time updates due to the static nature of the environment.
- Dynamic environment path planning: Dynamic environment path planning handles scenarios with moving obstacles, requiring continuous real-time adaptation to ensure collision-free navigation. Applications include autonomous vehicles avoiding other vehicles, pedestrians, or road obstructions [77]. Unlike static planning, it integrates both static and dynamic obstacle considerations, relying on real-time sensor data, predictive modeling, and adaptive decision making [78]. This approach is computationally more complex due to the need for continuous trajectory updates.
- Three-dimensional environment path planning: Three-dimensional environment path planning is essential for navigating vehicles or drones in volumetric spaces, incorporating dimensions like altitude and heading. It is critical for UAV navigation [76], spacecraft trajectory optimization [79], and navigating complex terrains like mountains or urban areas [80]. The complexity arises from modeling volumetric spaces, collision detection [81], and processing large-scale 3D data, requiring robust and scalable algorithms.
2.2.3. Task-Based Classification
- Single-UAV path planning: Single-UAV path planning focuses on determining an optimal route for a UAV from a specified starting point to a designated target. In practical applications, this includes scenarios such as planning the UAV’s trajectory from a distribution center to a customer’s location for express delivery [82] or defining the flight path from a take-off point to a mapping area for field surveys [83,84]. The mission objectives of single-UAV path planning are diverse. One primary goal is to minimize the flight distance, thereby reducing travel time and optimizing energy consumption to extend flight endurance, which is particularly critical for long-duration missions. Additionally, path planning must account for risk factors such as adverse weather conditions, ensuring that the selected route minimizes potential hazards and enhances flight safety.
- Multi-UAV collaborative path planning: Multi-UAV collaborative path planning involves coordinating multiple UAVs to efficiently complete tasks within a shared environment [85]. This process addresses several challenges, including task allocation—ensuring that each UAV is assigned appropriate duties—and path coordination to prevent conflicts or collisions. Additionally, the approach focuses on overall optimization to enhance task efficiency and system reliability. Such collaborative planning is particularly critical in complex scenarios, including search and rescue operations [86] and environmental monitoring [87], where the collective performance of multiple UAVs significantly influences mission success.
2.3. Evaluation Metrics
3. Classical Path Planning Algorithms
3.1. Graph-Based Algorithms
- The Dijkstra algorithm is a single-source shortest-path method based on weighted graphs. It iteratively updates the shortest distances from the source node to all other nodes until the target is reached, ensuring a globally optimal solution in static environments [88]. This algorithm performs exceptionally well in grid-based maps and road networks, making it suitable for applications such as airport patrol [89] and indoor navigation [90]. However, its high computational complexity and limited scalability in large or dynamic environments present significant challenges.
- The A* algorithm enhances Dijkstra’s approach by incorporating a heuristic function that estimates the cost from any node to the goal. By combining the actual cost and the heuristic estimate, A* significantly accelerates the search for the optimal path. This algorithm is widely applied in static environments where both optimality and efficiency are required. However, in high-dimensional spaces or dynamic settings, designing an effective heuristic function becomes challenging, potentially limiting performance. Variants such as Theta* [91] have been proposed to address issues like path smoothness in grid-based implementations.
- The D* algorithm is a dynamic path planning algorithm designed to adapt to environmental changes by incrementally updating the planned path. Once an initial path is established, D* leverages previously computed information to efficiently replan when obstacles or other environmental modifications are detected. The core principle involves adjusting the priority of nodes based on their cost and distance to the target while maintaining a priority queue. When the environment changes, only the affected nodes require recalculation, avoiding the need to recompute the entire path [92]. While D* excels in dynamic scenarios, frequent environmental changes can significantly increase computational overhead.
3.2. Optimization Methods
- Linear programming (LP) formulates the path planning problem as an optimization task governed by linear constraints and an objective function. By utilizing established LP solvers, this approach efficiently computes globally optimal solutions in environments characterized by simple constraints and static conditions. However, its effectiveness diminishes in scenarios with complex, nonlinear constraints or dynamic environments, where its assumptions and computational efficiency become limiting factors.
- Nonlinear programming (NLP) methods address path planning problems with complex constraints, such as dynamic obstacles and curved trajectories, that linear models cannot adequately represent. By incorporating nonlinear objective functions and constraints, NLP enables the generation of paths that more accurately capture the physical and operational requirements of the task. This approach is particularly advantageous in scenarios such as UAV formation control and continuous motion planning for robots. However, its practical application is often hindered by high computational complexity and susceptibility to local optima, posing significant challenges in real-time and large-scale environments.
3.3. Random Sampling Algorithms
- The Rapidly Exploring Random Trees (RRT) algorithm incrementally constructs a search tree to explore the configuration space by randomly sampling nodes and connecting them to the nearest neighbors in the existing tree, as shown in Figure 5a,b. Mathematically, the process can be described as follows: a random configuration is sampled from the free space , the nearest node in the current tree T is identified based on a distance metric , and a new node is generated by extending from toward by a fixed step size e, such that . If the path from to lies entirely within , the new node is added to the tree. A key advantage of RRT is its probabilistic completeness, meaning that as the number of iterations k approaches infinity, the probability of finding a solution converges to one [93]. The choice of the extension step size e is critical, as it affects both the exploration efficiency and path quality. For instance, setting e to 5% of the diagonal length of the environment has been shown to achieve a success rate of 96% in path planning for a 3D robotic arm [94]. Unlike traditional search algorithms that often suffer from the curse of dimensionality in high-dimensional spaces, RRT effectively mitigates this issue through its random sampling mechanism, resulting in superior search efficiency. However, the algorithm has notable limitations: the stochastic nature of the search tree often leads to suboptimal paths, and it cannot guarantee a globally optimal solution. To address these issues, various improved algorithms have been proposed, as summarized in Table 3. Despite its limitations, the RRT algorithm remains a cornerstone of motion planning, offering a powerful and efficient approach for exploring large and complex configuration spaces.
- The Probabilistic Roadmap (PRM) algorithm constructs a collision-free path in high-dimensional configuration spaces by building a graph (roadmap) of sampled configurations and then searching for paths within this structure, as shown in Figure 5c,d. Mathematically, the process can be described in two phases: during the learning phase, random configurations are sampled from the free space, and edges are created by connecting to its neighboring nodes within a specified radius r, where a connection is valid only if the direct path between the nodes lies entirely within . In the query phase, graph search algorithms such as A* or Dijkstra are employed to find the shortest path between the start and goal nodes on the constructed roadmap. A key strength of PRM is its probabilistic completeness: as the number of samples n increases, the probability of finding a solution (if one exists) approaches one [95]. The algorithm’s performance is heavily influenced by parameters like the sampling density n and connection radius r. For example, in a six-degrees-of-freedom (DOF) robotic arm scenario, using samples and achieves a 92% success rate in cluttered environments [96]. PRM is particularly effective in high-dimensional spaces due to its decoupling of roadmap construction from path queries, enabling the reuse of the roadmap for multiple planning tasks, which contrasts with incremental methods like RRT that rebuild the tree for each query. However, PRM’s preprocessing phase can be computationally expensive in complex environments, especially in the presence of narrow passages, as uniform sampling may fail to capture these critical regions. Moreover, the quality of the roadmap depends on the sampling strategy, and the algorithm does not guarantee optimal paths. Variants such as Lazy PRM [97] and PRM* [63] address these issues by optimizing sampling and connection strategies, improving path quality and computational efficiency. Despite its limitations, PRM remains a versatile and powerful tool for motion planning, particularly in scenarios that require repeated queries in static environments.
Algorithm | Improvement | Advantages | Reference |
---|---|---|---|
RRT* | Based on RRT; path optimization is introduced to ensure asymptotic optimization | Asymptotic optimality; better path quality | [65] |
RT-RRT* | Adds tree maintenance and rewiring mechanisms | Efficient path generation; adaptable | [98] |
Informed RRT* | Using a heuristic function to limit the search space | Less unnecessary exploration; faster | [99] |
RRT*-smart | Uses intelligent sampling methods, incremental optimization, and heuristic guidance | Efficient path quality; strong adaptability | [100] |
Bi-RRT* | The combination of retrospective thought and greedy search strategy; path optimization strategy and path smoothing strategy | High algorithm efficiency; high path quality | [101] |
RRT-Connect | Improves the search speed by means of bidirectional tree | Bidirectional search; fast response | [66] |
RRT-blossem | Using biased sampling. Local optimality is avoided by constraint equations | Overall search speed is fast | [102] |
Circle-RRT | Sampling strategy combined with circular constraints | Circular constraint sampling; energy obstacle optimization. | [103] |
KD-RRT | Test case generation strategy; nearest neighbor search optimization | Strong versatility; scalable; high efficiency | [104] |
Dynamic RRT (DRRT) | Supports path replanning for dynamic obstacle update | Real-time replanning; dynamic obstacle adaptation. | [105] |
Hybrid RRT (HRRT) | The RRT and A* algorithms are combined and a heuristic search strategy is used | Prefers target bias node; fast response | [106] |
3.4. Bio-Inspired Algorithms
- Genetic algorithms (GAs) simulate the process of natural evolution, treating candidate paths as individuals that evolve over successive generations through selection, crossover, and mutation operations [107]. GAs are particularly effective in exploring complex, multi-objective optimization landscapes, making them a popular choice for multi-UAV cooperative tasks [108] and other scenarios with intricate constraints, as shown in Figure 6a. However, GAs are susceptible to premature convergence to local optima and often exhibit slower convergence rates. This necessitates careful parameter tuning and, in many cases, hybridization with other methods to enhance performance.
- Particle swarm optimization (PSO) simulates the social behavior observed in flocks of birds or schools of fish searching for food, where each particle in the swarm represents a potential solution and adjusts its trajectory based on both individual and collective best experiences, as shown in Figure 6b. Known for its rapid convergence and simplicity in parameter configuration, PSO is particularly attractive for static environments that require energy-efficient path planning. However, its performance can be highly sensitive to the initial distribution of particles, and its ability to adapt to dynamic changes is generally limited [109,110].
- Ant colony optimization models the foraging behavior of ants, where artificial agents (ants) deposit virtual pheromones along the paths they traverse, as shown in Figure 6c. Over time, paths with higher pheromone concentrations become more attractive, guiding the swarm toward an optimal solution [111]. ACO is robust and adaptable, making it particularly useful in scenarios involving dynamic task allocation and complex route planning. However, the algorithm often requires extensive computation and iterative processing, which leads to slower convergence and increased computational complexity, especially in large-scale problems [112,113].
- Hybrid algorithms have emerged as a promising strategy to overcome the inherent limitations of individual methods [114]. By integrating multiple techniques, hybrid algorithms capitalize on their complementary strengths, effectively addressing the challenges posed by dynamic environments and complex constraints. Path planning algorithms are typically defined by distinct performance characteristics and limitations [115]. For example, deterministic methods such as A* provide optimal solutions in static environments but lack the flexibility needed to adapt to real-time changes. In contrast, sampling-based algorithms like RRT excel in quickly exploring high-dimensional spaces, but may generate suboptimal or non-smooth paths. Bio-inspired methods, including genetic algorithms (GAs) and particle swarm optimization (PSO), offer robust global search capabilities, yet are susceptible to challenges such as premature convergence and sensitivity to parameter initialization. The integration of these diverse approaches is motivated by the need to harness their respective strengths—achieving global optimality while ensuring rapid local adaptability—thereby facilitating more robust and efficient performance in both static and dynamic operational contexts.
3.5. Key Trade-Off Relationships Between Traditional Path Planning Algorithms
4. Advanced Artificial Intelligence Path Planning Methods
4.1. Machine Learning in Path Planning
4.2. Reinforcement Learning in Path Planning
4.3. Deep Learning in Path Planning
4.3.1. Deep Neural Network (DNN)
4.3.2. Convolutional Neural Network (CNN)
4.3.3. Generative Adversarial Network (GAN)
4.3.4. Critical Analysis
5. Energy-Aware Path Planning
5.1. Energy Model and Optimization Objective
5.2. Energy Perception Path Planning Algorithm
5.3. Environmental Factors
- WindWind speed and direction are the key factors affecting UAV flight energy consumption, which directly determines the flight energy consumption. During actual flight, wind speed and direction change, and to deal with these changes, UAVs can sense the wind in real-time through integrated sensors such as anemometers, GPS and IMUs, and adjust their flight path based on the measured wind speed and direction to optimize energy consumption. As mentioned in ref. [176], fixed-wing UAVs utilize wind speed measurement equipment (such as conventional pitot tubes or porous pitot tubes) combined with inertial measurement units (IMUs) to estimate wind speed. In the case of headwinds, the flight path is adjusted to a low-wind-speed area or by adjusting the climb angle to reduce energy consumption, and similar optimization strategies are often implemented with an extended Kalman filter (EKF). In addition, the UAV also analyzes weather data in real time to predict changes in wind speed over a period of time to plan the optimal flight path. For example, a stochastic process model is proposed in ref. [177,178] to describe changes in wind speed, which can help adjust flight strategies according to the predicted wind speed during flight.
- Air densityAir density changes with height. Generally, in higher airspace the air is less dense, which means that the vehicle needs to provide more thrust and lift to maintain stable flight, thus consuming more energy. UAV flight path planning needs to take this into account to select the flight altitude with the least energy consumption. For example, in order to solve the path planning problem of electric vertical take-off and landing UAVs (eVTOL UAV) in urban areas, Li et al. [179] proposed a planning method that considers minimum energy consumption. Based on the change in air density with height, a more accurate calculation formula of battery energy consumption is derived and, combined with the improved Voronoi diagram, Dubins geometric curve, and the Floyd algorithm, a safe, shortest, and obstacle-free path is planned. Through simulation analysis, it is found that the path length planned by this method is shorter than that of particle swarm optimization algorithm, which can effectively reduce energy consumption and increase the transportation range of UAVs.
- TemperatureChanges in temperature have a significant effect on the performance of aircraft. Temperature not only affects the density of the air, but also directly affects the performance of the drone battery and the efficiency of the engine. In a low-temperature environment, the battery performance of the UAV decreases and the discharge ability weakens, resulting in an increase in energy consumption [180]. Therefore, under different temperature conditions, path planning needs to accurately predict the performance changes of the battery to ensure the stability of the energy supply. Kim et al. [181] proposed a quadratic function model by using the historical and predicted temperature data of the operating area of UAVs and taking into account the effect of UAVs’ flight height on temperature by fitting the data with a regression analysis method, and verified that this model was statistically significant and had high reliability.
5.4. Case Study
- Distribution tasksIn the field of drone delivery, path planning must not only find the shortest path, but also be as energy efficient as possible [182]. Kevin et al. [180] proposed a multi-travel vehicle routing problem (MTVRP) for UAV delivery, and verified the energy consumption model of a multi-rotor UAV through experiments, and aimed at UAV delivery problems (DDPs). In this paper, the minimum-cost drone delivery problem (MC-DDP) and minimum-time drone delivery problem (MT-DDP) are proposed and the simulated annealing (SA) algorithm is used to solve these problems. The experiments show that SA is close to the optimal solution for both large- and small-scale problems. At the same time, it is found that the cost and delivery time limit, the total delivery time, and the budget are inversely exponential. Reuse of UAVs and optimization of battery weight can significantly reduce the cost and shorten the delivery time.
- Agricultural monitoringIn agricultural monitoring missions, drones need to cover large areas of farmland and collect data [183]. By using a path planning algorithm based on energy optimization, the aircraft can reasonably plan a flight path to avoid repeated flights and unnecessary climbs, thus reducing energy consumption and improving operational efficiency. Based on the perception of terrain and wind, path planning can be adjusted in real time to avoid energy-intensive flights in areas with high wind speeds.
- Disaster reliefIn disaster relief, drones often need to fly for long periods of time and face complex environmental conditions. Through energy optimization path planning, the aircraft can adjust the flight path according to real-time meteorological data, avoiding high winds and unstable airflow areas, thereby reducing energy consumption and improving rescue efficiency.
6. Multi-UAV Collaborative Path Planning
- -
- is the path of UAV i;
- -
- are the cost terms for the energy, time, and task-specific objectives;
- -
- represents obstacles, and the constraints ensure collision avoidance and feasibility.
6.1. Features of Collaborative Path Planning
- Task allocationIn multi-UAV collaboration, task assignment is a key step in path planning, optimizing resources and reducing flight time and energy. Strategies are categorized as optimization-based or demand-based. The Performance Impact (PI) algorithm, a demand-based method, evaluates inclusion (IPI) and removal (RPI) impacts, considering task cost and priority. Optimization-based methods include exact techniques, heuristics, and hybrids [186]. Task assignment also considers UAV battery levels, sensor capabilities, and task urgency [187].
- Communication constraintsMulti-drone collaboration relies on continuous communication for mission updates, flight status, and environmental data. However, dynamic and interference-prone networks pose challenges. Meng et al. [188] address this with the LR-PI algorithm, enhancing task allocation by considering communication delays and packet loss. Additionally, UAV network topology must adapt to changing environments.
- Collaborative obstacle avoidanceTraditional path planning focuses on single-UAV obstacle avoidance, while multi-UAV collaborative planning considers dynamic avoidance among multiple aircraft. Rule-based strategies adjust speed and altitude, as seen in Zhang et al. [189], who combined optimal consensus control, particle swarm optimization, and an improved artificial potential field (APF). Path prediction methods anticipate collisions and adjust trajectories. Learning-based approaches, like Luo et al. [190], who used Deep-SARSA, train neural networks for reliable path planning and collision avoidance in dynamic environments.
6.2. Representative Methods
6.3. Typical Applications of Multi-UAV Collaboration
- Disaster rescueIn disaster rescue scenarios, multiple UAVs collaborate on tasks like regional search, material delivery, and personnel positioning. Each drone plans its path independently using mission requirements and real-time data, while coordinating to avoid obstacles and improve efficiency. Xiong et al. [197] addressed supply delivery in disaster areas by modeling flight distance, payload, terrain, and threats. They used an adaptive genetic algorithm (AGA) for task assignment and sine–cosine particle swarm optimization (SCPSO) for path planning. Chandran et al. [198] proposed drones as communication relays to establish temporary networks, exploring architecture, routing, and security for multi-UAV disaster monitoring.
- Area coverageIn agricultural monitoring, multi-drone collaboration covers large areas efficiently compared to single drones. Ju et al. [31] proposed a distributed group control algorithm for multi-UAV systems, evaluated through metrics like total time, flight time, and battery consumption. The results showed better performance over single UAVs, addressing battery shortages, reducing working time, and improving efficiency. Multi-UAVs can dynamically adjust paths, avoid redundant coverage, and optimize mission execution, offering valuable insights for advancing agricultural technologies.
- Monitoring patrolIn border patrol and urban security, multi-drone collaboration enables real-time, continuous surveillance over large areas. Drones perform distinct tasks or alternate patrols while using real-time path adjustments and obstacle avoidance. Muñoz et al. [199] tackled urban multi-UAV path planning with two algorithms: one uses round-trip movements, and the other connects landmark points. Both rely on approximate cell decomposition and the Fast Marching Square () strategy for obstacle avoidance, maintaining triangular formations. Simulations showed the algorithms could generate safe, smooth paths and reduce computation time, though challenges remained with large obstacles and real-world validation.
7. Future Directions
7.1. Advanced Optimization of Algorithm Performance
- Enhancement of computing efficiencyOptimize the computing speed and resource consumption of existing path planning algorithms, especially in large-scale tasks and complex environments, to ensure that path planning can be executed in real time. In the tasks of large-scale cluster control, multi-objective path planning, and high-dimensional-space search, the traditional algorithms such as the classical graph search algorithm have difficulties in meeting the real-time requirements because of the large amount of computation. According to the advantages of each algorithm’s principles and the complementarities among algorithms, hybrid algorithms have shown great potential in UAV path planning in recent years. For example, liu et al. [201] proposed an improved artificial potential field (APF) UAV path planning algorithm (G-APF) guided by Rapidly Exploring Random Trees (RRT) based on environment perception modeling. By combining the advantages of the RRT and APF algorithms and introducing environment awareness, the advantages of each algorithm are utilized to overcome the limitations of traditional methods and optimize the computational efficiency of the existing path planning algorithm.
- Improvement of robustnessIn UAV applications, path planning algorithms need to deal with dynamic and complex environments, such as sudden obstacles, communication delays, target location changes, and other uncertainties that will have an impact on the planning results. The existing path algorithms often lack sufficient foresight when dealing with emergencies, which can easily lead to planning failure, or they need a short time to recalculate the path. Therefore, one of the important research directions is to improve the robustness of the algorithms so that they can maintain stable programming under dynamic environments. To solve this problem, some effective methods have been introduced so that path planning can be adjusted in real-time according to environmental changes. For example, Zhang et al. [202] proposed an improved adaptive gray wolf optimization (AGWO) algorithm to solve premature convergence and local optima issues in GWO. By designing an adaptive weight factor based on centrifugal distance change, the algorithm dynamically updates positions and improves robustness. Ramezani et al. [203] introduced the SERT-DQN+ algorithm, which ensures system stability by addressing UAV failures and communication interruptions in multi-UAV systems.
7.2. Edge Computing, Swarm Intelligence, and Safety
7.3. Integration of Deep Learning and Path Planning
7.4. Smart Sensors Fused with Path Planning
7.5. Path Planning Requirements in Special Scenarios
- Extreme weather conditions: In bad weather (such as heavy rain, strong wind, haze, etc.), the flight stability and sensor performance of drones will be greatly affected, and traditional path planning algorithms have difficulties in effectively coping [215]. This requires that the algorithm can obtain real-time meteorological data (such as wind speed, air pressure, humidity, etc.) [216], so that, combined with the dynamic characteristics of the aircraft and the energy consumption model, the UAV can optimize the path in bad weather and choose a more stable flight path with lower energy consumption.
- Navigation without GPS: In environments where GPS signals are weak or missing (e.g., indoors, underground, urban canyons, etc.), traditional GPS-based path planning methods will fail [217]. This requires the path planning algorithm to be able to integrate other positioning techniques, such as inertial navigation and visual SLAM. In a GPS-free environment, inertial navigation systems (INSs) and visual SLAM (Simultaneous Localization and Mapping) will play an important role. By combining these technologies, the path planning algorithm can make accurate positioning and obstacle avoidance decisions based on real-time sensor information, ensuring that the UAV can still complete its mission in a GPS-free environment. For example, Radwan et al. [218] proposed an end-to-end application that integrates a marker-based visual synchronous positioning and mapping (VSLAM) framework into drones to reconstruct maps and generate 3D scene maps in indoor environments, where GPS signals are missing.
- High-speed flight: Recent advances in UAV trajectory planning have also focused on scenarios involving high-speed flight, where traditional path planning and control algorithms may not be sufficient to ensure accurate and robust trajectory tracking. For instance, neural network-based PID controllers [219] have been proposed to enhance the adaptability and performance of UAVs in complex environments by learning optimal control strategies from data, thus improving trajectory tracking accuracy even under dynamic and uncertain conditions. Additionally, comparative studies of optimization algorithms, such as genetic algorithms and stochastic hill climbing, have demonstrated their effectiveness in multi-UAV path planning for inspection missions, particularly when UAVs operate at speeds approaching or exceeding the speed of sound [220]. These approaches highlight the importance of integrating advanced control and optimization techniques to address the unique challenges posed by special scenarios, ensuring safe, efficient, and reliable UAV operations.
- UAV-UGV cooperation: Recent developments in path planning have increasingly emphasized the significance of UAV–UGV cooperation, as such multi-agent systems present unique challenges and opportunities compared to single-platform scenarios. For example, effective path planning in cooperative UAV–UGV systems must address issues such as localization uncertainty, heterogeneous vehicle dynamics, and the need for real-time information sharing in complex or unknown environments. Petrillo et al. [221] explored search planning for UAV/UGV teams operating under localization uncertainty, demonstrating the necessity of robust algorithms for subterranean missions. Similarly, Li et al. [222] proposed a hybrid path planning method that leverages the complementary capabilities of UAVs and UGVs to enhance mission efficiency and adaptability. Recent work has also investigated the use of UAVs for advance reconnaissance to inform UGV path planning in unknown environments [223], as well as multi-agent frameworks for automatic sensory data collection in cluttered settings [224]. These studies highlight the importance of integrated, cooperative planning strategies that account for the distinct constraints and advantages of both aerial and ground vehicles, thereby broadening the scope of path planning research and offering more comprehensive solutions for real-world applications.
8. Conclusions
Author Contributions
Funding
Data Availability Statement
Conflicts of Interest
References
- Santoso, F.; Garratt, M.A.; Anavatti, S.G. State-of-the-art intelligent flight control systems in unmanned aerial vehicles. IEEE Trans. Autom. Sci. Eng. 2017, 15, 613–627. [Google Scholar] [CrossRef]
- Bae, J.; Sohn, K.Y.; Lee, H.; Lee, H.; Lee, H. Structure of UAV-based Emergency Mobile Communication Infrastructure. In Proceedings of the 2021 International Conference on Information and Communication Technology Convergence (ICTC), Jeju Island, Republic of Korea, 20–22 October 2021; pp. 634–636. [Google Scholar]
- Daniel, K.; Rohde, S.; Wietfeld, C. Leveraging public wireless communication infrastructures for UAV-based sensor networks. In Proceedings of the 2010 IEEE International Conference on Technologies for Homeland Security (HST), Waltham, MA, USA, 8–10 November 2010; pp. 179–184. [Google Scholar]
- Asadzadeh, S.; de Oliveira, W.J.; de Souza Filho, C.R. UAV-based remote sensing for the petroleum industry and environmental monitoring: State-of-the-art and perspectives. J. Pet. Sci. Eng. 2022, 208, 109633. [Google Scholar] [CrossRef]
- Aasen, H.; Honkavaara, E.; Lucieer, A.; Zarco-Tejada, P.J. Quantitative remote sensing at ultra-high resolution with UAV spectroscopy: A review of sensor technology, measurement procedures, and data correction workflows. Remote Sens. 2018, 10, 1091. [Google Scholar] [CrossRef]
- Abubakar, A.I.; Ahmad, I.; Omeke, K.G.; Ozturk, M.; Ozturk, C.; Abdel-Salam, A.M.; Mollel, M.S.; Abbasi, Q.H.; Hussain, S.; Imran, M.A. A survey on energy optimization techniques in UAV-based cellular networks: From conventional to machine learning approaches. Drones 2023, 7, 214. [Google Scholar] [CrossRef]
- Erenoglu, R.C.; Erenoglu, O.; Arslan, N. Accuracy assessment of low cost UAV based city modelling for urban planning. Teh. Vjesn. 2018, 25, 1708–1714. [Google Scholar]
- Islam, N.; Rashid, M.M.; Pasandideh, F.; Ray, B.; Moore, S.; Kadel, R. A review of applications and communication technologies for internet of things (Iot) and unmanned aerial vehicle (uav) based sustainable smart farming. Sustainability 2021, 13, 1821. [Google Scholar] [CrossRef]
- Lottes, P.; Khanna, R.; Pfeifer, J.; Siegwart, R.; Stachniss, C. UAV-based crop and weed classification for smart farming. In Proceedings of the 2017 IEEE International Conference on Robotics and Automation (ICRA), Singapore, 29 May–3 June 2017; pp. 3024–3031. [Google Scholar]
- Khan, A.; Gupta, S.; Gupta, S.K. Emerging UAV technology for disaster detection, mitigation, response, and preparedness. J. Field Robot. 2022, 39, 905–955. [Google Scholar] [CrossRef]
- Erdelj, M.; Natalizio, E.; Chowdhury, K.R.; Akyildiz, I.F. Help from the sky: Leveraging UAVs for disaster management. IEEE Pervasive Comput. 2017, 16, 24–32. [Google Scholar] [CrossRef]
- Chaturvedi, S.K.; Sekhar, R.; Banerjee, S.; Kamal, H. Comparative review study of military and civilian unmanned aerial vehicles (UAVs). INCAS Bull. 2019, 11, 181–182. [Google Scholar] [CrossRef]
- Yin, S.; He, R.; Li, J.; Chen, L.; Zhang, S. Research on the operational mode of manned/unmanned collaboratively detecting drone swarm. In Proceedings of the 2021 IEEE International Conference on Unmanned Systems (ICUS), Beijing, China, 15–17 October 2021; pp. 560–564. [Google Scholar]
- Song, B.D.; Park, K.; Kim, J. Persistent UAV delivery logistics: MILP formulation and efficient heuristic. Comput. Ind. Eng. 2018, 120, 418–428. [Google Scholar] [CrossRef]
- Zhang, H.-Y.; Lin, W.-M.; Chen, A.-X. Path planning for the mobile robot: A review. Symmetry 2018, 10, 450. [Google Scholar] [CrossRef]
- Sanchez-Ibanez, J.R.; Pérez-del Pulgar, C.J.; García-Cerezo, A. Path planning for autonomous mobile robots: A review. Sensors 2021, 21, 7898. [Google Scholar] [CrossRef] [PubMed]
- Karur, K.; Sharma, N.; Dharmatti, C.; Siegel, J.E. A survey of path planning algorithms for mobile robots. Vehicles 2021, 3, 448–468. [Google Scholar] [CrossRef]
- Huang, G.; Hu, M.; Yang, X.; Wang, X.; Wang, Y.; Huang, F. A Review of Constrained Multi-Objective Evolutionary Algorithm-Based Unmanned Aerial Vehicle Mission Planning: Key Techniques and Challenges. Drones 2024, 8, 316. [Google Scholar] [CrossRef]
- Monwar, M.; Semiari, O.; Saad, W. Optimized path planning for inspection by unmanned aerial vehicles swarm with energy constraints. In Proceedings of the 2018 IEEE Global Communications Conference (GLOBECOM), Abu Dhabi, United Arab Emirates, 9–13 December 2018; pp. 1–6. [Google Scholar]
- Yin, C.; Xiao, Z.; Cao, X.; Xi, X.; Yang, P.; Wu, D. Offline and online search: UAV multiobjective path planning under dynamic urban environment. IEEE Internet Things J. 2017, 5, 546–558. [Google Scholar] [CrossRef]
- Shivgan, R.; Dong, Z. Energy-efficient drone coverage path planning using genetic algorithm. In Proceedings of the 2020 IEEE 21st International Conference on High Performance Switching and Routing (HPSR), Newark, NJ, USA, 11–14 May 2020; pp. 1–6. [Google Scholar]
- Jin, H.; Jin, X.; Zhou, Y.; Guo, P.; Ren, J.; Yao, J.; Zhang, S. A survey of energy efficient methods for UAV communication. Veh. Commun. 2023, 41, 100594. [Google Scholar] [CrossRef]
- Ruz, J.J.; Pajares, G.; de la Cruz, J.M.; Arevalo, O. UAV Trajectory Planning for Static and Dynamic Environments; Citeseer: Princeton, NJ, USA, 2009. [Google Scholar]
- Budiyanto, A.; Cahyadi, A.; Adji, T.B.; Wahyunggoro, O. UAV obstacle avoidance using potential field under dynamic environment. In Proceedings of the 2015 International Conference on Control, Electronics, Renewable Energy and Communications (ICCEREC), Bandung, Indonesia, 27–29 August 2015; pp. 187–192. [Google Scholar]
- De Filippis, L.; Guglieri, G.; Quagliotti, F. Path planning strategies for UAVS in 3D environments. J. Intell. Robot. Syst. 2012, 65, 247–264. [Google Scholar] [CrossRef]
- Dai, R.; Fotedar, S.; Radmanesh, M.; Kumar, M. Quality-aware UAV coverage and path planning in geometrically complex environments. Ad Hoc Netw. 2018, 73, 95–105. [Google Scholar] [CrossRef]
- Kim, J.; Crassidis, J.L. UAV path planning for maximum visibility of ground targets in an urban area. In Proceedings of the 2010 13th International Conference on Information Fusion, Edinburgh, UK, 26–29 July 2010; pp. 1–7. [Google Scholar]
- Mesquita, R.; Gaspar, P.D. A novel path planning optimization algorithm based on particle swarm optimization for UAVs for bird monitoring and repelling. Processes 2021, 10, 62. [Google Scholar] [CrossRef]
- Boukoberine, M.N.; Zhou, Z.; Benbouzid, M. A critical review on unmanned aerial vehicles power supply and energy management: Solutions, strategies, and prospects. Appl. Energy 2019, 255, 113823. [Google Scholar] [CrossRef]
- Abeywickrama, H.V.; Jayawickrama, B.A.; He, Y.; Dutkiewicz, E. Comprehensive energy consumption model for unmanned aerial vehicles, based on empirical studies of battery performance. IEEE Access 2018, 6, 58383–58394. [Google Scholar] [CrossRef]
- Ju, C.; Son, H.I. Multiple UAV systems for agricultural applications: Control, implementation, and evaluation. Electronics 2018, 7, 162. [Google Scholar] [CrossRef]
- Skorobogatov, G.; Barrado, C.; Salamí, E. Multiple UAV systems: A survey. Unmanned Syst. 2020, 8, 149–169. [Google Scholar] [CrossRef]
- Bellingham, J.; Tillerson, M.; Richards, A.; How, J.P. Multi-task allocation and path planning for cooperating UAVs. In Cooperative Control: Models, Applications and Algorithms; Springer: Boston, MA, USA, 2003; pp. 23–41. [Google Scholar]
- Moon, S.; Oh, E.; Shim, D.H. An integral framework of task assignment and path planning for multiple unmanned aerial vehicles in dynamic environments. J. Intell. Robot. Syst. 2013, 70, 303–313. [Google Scholar] [CrossRef]
- Qin, P.; Li, J.; Zhang, J.; Fu, Y. Joint Task Allocation and Trajectory Optimization for Multi-UAV Collaborative Air-Ground Edge Computing. IEEE Trans. Netw. Sci. Eng. 2024, 11, 6231–6243. [Google Scholar] [CrossRef]
- Liu, D.; Bao, W.; Zhu, X.; Fei, B.; Men, T.; Xiao, Z. Cooperative path optimization for multiple UAVs surveillance in uncertain environment. IEEE Internet Things J. 2021, 9, 10676–10692. [Google Scholar] [CrossRef]
- López, B.; Muñoz, J.; Quevedo, F.; Monje, C.A.; Garrido, S.; Moreno, L.E. Path planning and collision risk management strategy for multi-UAV systems in 3D environments. Sensors 2021, 21, 4414. [Google Scholar] [CrossRef]
- Yao, P.; Wang, H.; Su, Z. Real-time path planning of unmanned aerial vehicle for target tracking and obstacle avoidance in complex dynamic environment. Aerosp. Sci. Technol. 2015, 47, 269–279. [Google Scholar] [CrossRef]
- Xu, C.; Liao, X.; Tan, J.; Ye, H.; Lu, H. Recent research progress of unmanned aerial vehicle regulation policies and technologies in urban low altitude. IEEE Access 2020, 8, 74175–74194. [Google Scholar] [CrossRef]
- Telli, K.; Kraa, O.; Himeur, Y.; Ouamane, A.; Boumehraz, M.; Atalla, S.; Mansoor, W. A comprehensive review of recent research trends on unmanned aerial vehicles (uavs). Systems 2023, 11, 400. [Google Scholar] [CrossRef]
- MahmoudZadeh, S.; Yazdani, A.; Kalantari, Y.; Ciftler, B.; Aidarus, F.; Al Kadri, M.O. Holistic review of UAV-centric situational awareness: Applications, limitations, and algorithmic challenges. Robotics 2024, 13, 117. [Google Scholar] [CrossRef]
- Xie, R.; Meng, Z.; Wang, L.; Li, H.; Wang, K.; Wu, Z. Unmanned aerial vehicle path planning algorithm based on deep reinforcement learning in large-scale and dynamic environments. IEEE Access 2021, 9, 24884–24900. [Google Scholar] [CrossRef]
- Hein, D.; Kraft, T.; Brauchle, J.; Berger, R. Integrated uav-based real-time mapping for security applications. ISPRS Int. J. Geo-Inf. 2019, 8, 219. [Google Scholar] [CrossRef]
- Schøler, F.; la Cour-Harbo, A.; Bisgaard, M. Generating approximative minimum length paths in 3D for UAVs. In Proceedings of the 2012 IEEE Intelligent Vehicles Symposium, Madrid, Spain, 3–7 June 2012; pp. 229–233. [Google Scholar]
- Techy, L.; Woolsey, C.A. Minimum-time path planning for unmanned aerial vehicles in steady uniform winds. J. Guid. Control Dyn. 2009, 32, 1736–1746. [Google Scholar] [CrossRef]
- Elmokadem, T.; Savkin, A.V. A hybrid approach for autonomous collision-free UAV navigation in 3D partially unknown dynamic environments. Drones 2021, 5, 57. [Google Scholar] [CrossRef]
- Chen, J.Y. UAV-guided navigation for ground robot tele-operation in a military reconnaissance environment. Ergonomics 2010, 53, 940–950. [Google Scholar] [CrossRef]
- Alotaibi, E.T.; Alqefari, S.S.; Koubaa, A. Lsar: Multi-uav collaboration for search and rescue missions. IEEE Access 2019, 7, 55817–55832. [Google Scholar] [CrossRef]
- Sun, R.; Zhang, W.; Zheng, J.; Ochieng, W.Y. GNSS/INS integration with integrity monitoring for UAV no-fly zone management. Remote Sens. 2020, 12, 524. [Google Scholar] [CrossRef]
- Jiménez López, J.; Mulero-Pázmány, M. Drones for conservation in protected areas: Present and future. Drones 2019, 3, 10. [Google Scholar] [CrossRef]
- Zhu, L.; Cheng, X.; Yuan, F.G. A 3D collision avoidance strategy for UAV with physical constraints. Measurement 2016, 77, 40–49. [Google Scholar] [CrossRef]
- Pastor, E.; Lopez, J.; Royo, P. UAV payload and mission control hardware/software architecture. IEEE Aerosp. Electron. Syst. Mag. 2007, 22, 3–8. [Google Scholar] [CrossRef]
- Yang, S. Analysis and Optimization of UAV Turning Methodology. 2022. Available online: https://escholarship.mcgill.ca/concern/papers/k35699091 (accessed on 4 April 2022).
- Kurdel, P.; Sedláčková, A.N.; Labun, J. UAV flight safety close to the mountain massif. Transp. Res. Procedia 2019, 43, 319–327. [Google Scholar] [CrossRef]
- Sujit, P.; Beard, R. Multiple UAV path planning using anytime algorithms. In Proceedings of the 2009 American Control Conference, St. Louis, MO, USA, 10–12 June 2009; pp. 2978–2983. [Google Scholar]
- Zeng, Y.; Zhang, R. Energy-efficient UAV communication with trajectory optimization. IEEE Trans. Wirel. Commun. 2017, 16, 3747–3760. [Google Scholar] [CrossRef]
- Paredes, J.A.; Saito, C.; Abarca, M.; Cuellar, F. Study of effects of high-altitude environments on multicopter and fixed-wing UAVs’ energy consumption and flight time. In Proceedings of the 2017 13th IEEE Conference on Automation Science and Engineering (CASE), Xi’an, China, 20–23 August 2017; pp. 1645–1650. [Google Scholar]
- Babu, N.; Ntougias, K.; Papadias, C.B.; Popovski, P. Energy efficient altitude optimization of an aerial access point. In Proceedings of the 2020 IEEE 31st Annual International Symposium on Personal, Indoor and Mobile Radio Communications, London, UK, 31 August–3 September 2020; pp. 1–7. [Google Scholar]
- Okulski, M.; Ławryńczuk, M. How much energy do we need to fly with greater agility? Energy consumption and performance of an attitude stabilization controller in a quadcopter drone: A modified MPC vs. PID. Energies 2022, 15, 1380. [Google Scholar] [CrossRef]
- Al-Sabban, W.H.; Gonzalez, L.F.; Smith, R.N. Wind-energy based path planning for unmanned aerial vehicles using markov decision processes. In Proceedings of the 2013 IEEE International Conference on Robotics and Automation, Karlsruhe, Germany, 6–10 May 2013; pp. 784–789. [Google Scholar]
- Javaid, A. Understanding Dijkstra’s Algorithm. 2013. Available online: https://ssrn.com/abstract=2340905 (accessed on 17 October 2013).
- 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]
- Karaman, S.; Frazzoli, E. Sampling-based algorithms for optimal motion planning. Int. J. Robot. Res. 2011, 30, 846–894. [Google Scholar] [CrossRef]
- Zammit, C.; Van Kampen, E.J. Comparison of a* and rrt in real–time 3d path planning of uavs. In Proceedings of the American Institute of Aeronautics and Astronautics Scitech 2020 Forum (AIAA), Orlando, FL, USA, 6–10 January 2020; p. 0861. [Google Scholar]
- Noreen, I.; Khan, A.; Habib, Z. Optimal path planning using RRT* based approaches: A survey and future directions. Int. J. Adv. Comput. Sci. Appl. 2016, 7, 97–107. [Google Scholar] [CrossRef]
- 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, 5–8 January 2000; Volume 2, pp. 995–1001. [Google Scholar]
- Haupt, R.L.; Werner, D.H. Genetic Algorithms in Electromagnetics; John Wiley & Sons: Hoboken, NJ, USA, 2007. [Google Scholar]
- Eberhart, R.; Kennedy, J. A new optimizer using particle swarm theory. In Proceedings of the MHS’95— Sixth International Symposium on Micro Machine and Human Science, Nagoya, Japan, 4–6 October 1995; pp. 39–43. [Google Scholar]
- Patle, B.; Babu L, G.; Pandey, A.; Parhi, D.; Jagadeesh, A. A review: On path planning strategies for navigation of mobile robot. Def. Technol. 2019, 15, 582–606. [Google Scholar] [CrossRef]
- Dorigo, M.; Maniezzo, V.; Colorni, A. Distributed optimization by ant colonies. In Proceedings of the European Conference on Artificial Life, Paris, France, 7–10 October 1991; Elsevier Publishing: Paris, France, 1991; Volume 134, pp. 134–142. [Google Scholar]
- Abhishek, B.; Ranjit, S.; Shankar, T.; Eappen, G.; Sivasankar, P.; Rajesh, A. Hybrid PSO-HSA and PSO-GA algorithm for 3D path planning in autonomous UAVs. SN Appl. Sci. 2020, 2, 1805. [Google Scholar] [CrossRef]
- Al-Ansarry, S.; Al-Darraji, S. Hybrid RRT-A*: An Improved Path Planning Method for an Autonomous Mobile Robots. Iraqi J. Electr. Electron. Eng. 2021, 17, 143–150. [Google Scholar] [CrossRef]
- Dirik, M.; Kocamaz, F. Rrt-dijkstra: An improved path planning algorithm for mobile robots. J. Soft Comput. Artif. Intell. 2020, 1, 69–77. [Google Scholar]
- Li, Y.; Scanavino, M.; Capello, E.; Dabbene, F.; Guglieri, G.; Vilardi, A. A novel distributed architecture for UAV indoor navigation. Transp. Res. Procedia 2018, 35, 13–22. [Google Scholar] [CrossRef]
- Malang, C.; Charoenkwan, P.; Wudhikarn, R. Implementation and critical factors of unmanned aerial vehicle (UAV) in warehouse management: A systematic literature review. Drones 2023, 7, 80. [Google Scholar] [CrossRef]
- Lu, Y.; Xue, Z.; Xia, G.S.; Zhang, L. A survey on vision-based UAV navigation. Geo-Spat. Inf. Sci. 2018, 21, 21–32. [Google Scholar] [CrossRef]
- Aloqaily, M.; Hussain, R.; Khalaf, D.; Slehat, D.; Oracevic, A. On the role of futuristic technologies in securing UAV-supported autonomous vehicles. IEEE Consum. Electron. Mag. 2022, 11, 93–105. [Google Scholar] [CrossRef]
- Faiçal, B.S.; Freitas, H.; Gomes, P.H.; Mano, L.Y.; Pessin, G.; de Carvalho, A.C.; Krishnamachari, B.; Ueyama, J. An adaptive approach for UAV-based pesticide spraying in dynamic environments. Comput. Electron. Agric. 2017, 138, 210–223. [Google Scholar] [CrossRef]
- Chai, R.; Savvaris, A.; Tsourdos, A.; Chai, S.; Xia, Y. A review of optimization techniques in spacecraft flight trajectory design. Prog. Aerosp. Sci. 2019, 109, 100543. [Google Scholar] [CrossRef]
- Liu, H.; Chen, Q.; Pan, N.; Sun, Y.; Yang, Y. Three-dimensional mountain complex terrain and heterogeneous multi-UAV cooperative combat mission planning. IEEE Access 2020, 8, 197407–197419. [Google Scholar] [CrossRef]
- Ruzgienė, B.; Berteška, T.; Gečyte, S.; Jakubauskienė, E.; Aksamitauskas, V.Č. The surface modelling based on UAV Photogrammetry and qualitative estimation. Measurement 2015, 73, 619–627. [Google Scholar] [CrossRef]
- Jung, S.; Kim, H. Analysis of amazon prime air uav delivery service. J. Knowl. Inf. Technol. Syst. 2017, 12, 253–266. [Google Scholar]
- Nex, F.; Remondino, F. UAV for 3D mapping applications: A review. Appl. Geomat. 2014, 6, 1–15. [Google Scholar] [CrossRef]
- Albani, D.; Nardi, D.; Trianni, V. Field coverage and weed mapping by UAV swarms. In Proceedings of the 2017 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Vancouver, BC, Canada, 24–28 September 2017; pp. 4319–4325. [Google Scholar]
- 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]
- Scherer, J.; Yahyanejad, S.; Hayat, S.; Yanmaz, E.; Andre, T.; Khan, A.; Vukadinovic, V.; Bettstetter, C.; Hellwagner, H.; Rinner, B. An autonomous multi-UAV system for search and rescue. In Proceedings of the First Workshop on Micro Aerial Vehicle Networks, Systems, and Applications for Civilian Use, Florence, Italy, 18 May 2015; pp. 33–38. [Google Scholar]
- Ya’acob, N.; Zolkapli, M.; Johari, J.; Yusof, A.L.; Sarnin, S.S.; Asmadinar, A.Z. UAV environment monitoring system. In Proceedings of the 2017 International Conference on Electrical, Electronics and System Engineering (ICEESE), Kanazawa, Japan, 9–10 November 2017; pp. 105–109. [Google Scholar]
- Noto, M.; Sato, H. A method for the shortest path search by extended Dijkstra algorithm. In Proceedings of the SMC 2000 Conference Proceedings—2000 IEEE International Conference on Systems, Man and Cybernetics, ‘Cybernetics Evolving to Systems, Humans, Organizations, and Their Complex Interactions’ (cat. no. 0), Nashville, TN, USA, 8–11 October 2000; Volume 3, pp. 2316–2320. [Google Scholar]
- Zhou, Y.; Huang, N. Airport AGV path optimization model based on ant colony algorithm to optimize Dijkstra algorithm in urban systems. Sustain. Comput. Inform. Syst. 2022, 35, 100716. [Google Scholar] [CrossRef]
- Xu, Y.; Wen, Z.; Zhang, X. Indoor optimal path planning based on Dijkstra Algorithm. In Proceedings of the International Conference on Materials Engineering and Information Technology Applications (MEITA 2015), Guangzhou, China, 17–18 January 2015; Atlantis Press: Dordrecht, The Netherlands, 2015; pp. 309–313. [Google Scholar]
- Nash, A.; Daniel, K.; Koenig, S.; Felner, A. Theta*: Any-angle path planning on grids. In Proceedings of the Association for the Advancement of Artificial Intelligence (AAAI), Vancouver, BC, Canada, 22–26 July 2007; Volume 7, pp. 1177–1183. [Google Scholar]
- Ferguson, D.; Stentz, A. Using interpolation to improve path planning: The Field D* algorithm. J. Field Robot. 2006, 23, 79–101. [Google Scholar] [CrossRef]
- LaValle, S. Rapidly-exploring random trees: A new tool for path planning. Annu. Res. Rep. TR 98-11 1998, 7, 1177–1183. [Google Scholar]
- Kavraki, L.E.; LaValle, S.M. Motion planning. In Springer Handbook of Robotics; Springer: Berlin/Heidelberg, Germany, 2016; pp. 139–162. [Google Scholar]
- Kavraki, L.E.; Svestka, P.; Latombe, J.C.; Overmars, M.H. Probabilistic roadmaps for path planning in high-dimensional configuration spaces. IEEE Trans. Robot. Autom. 1996, 12, 566–580. [Google Scholar] [CrossRef]
- LaValle, S.M. Planning Algorithms; Cambridge University Press: Cambridge, UK, 2006. [Google Scholar]
- Bohlin, R.; Kavraki, L.E. Path planning using lazy PRM. 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; Volume 1, pp. 521–528. [Google Scholar]
- Naderi, K.; Rajamäki, J.; Hämäläinen, P. RT-RRT* a real-time path planning algorithm based on RRT. In Proceedings of the 8th ACM SIGGRAPH Conference on Motion in Games, Paris, France, 16–18 November 2015; pp. 113–118. [Google Scholar]
- 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]
- 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]
- Wang, B.; Ju, D.; Xu, F.; Feng, C. Bi-RRT*: An Improved Bidirectional RRT* Path Planner for Robot in Two-Dimensional Space. IEEJ Trans. Electr. Electron. Eng. 2023, 18, 1639–1652. [Google Scholar] [CrossRef]
- Kalisiak, M.; van de Panne, M. RRT-blossom: RRT with a local flood-fill behavior. In Proceedings of the 2006 IEEE International Conference on Robotics and Automation (ICRA), Orlando, FL, USA, 15–19 May 2006; pp. 1237–1242. [Google Scholar]
- Meng, W.; Gong, Y.; Xu, F.; Tao, P.; Bo, P.; Xin, S. Efficient path planning for AUVs in unmapped marine environments using a hybrid local–global strategy. Ocean Eng. 2023, 288, 116227. [Google Scholar] [CrossRef]
- Lian, J.; Cui, C.; Sun, W.; Wu, Y.; Huang, R. KD-RRT: Restricted Random Testing based on K-Dimensional Tree. In Proceedings of the 2021 8th International Conference on Dependable Systems and Their Applications (DSA), Yinchuan, China, 5–6 August 2021; pp. 590–599. [Google Scholar]
- Zhao, P.; Chang, Y.; Wu, W.; Luo, H.; Zhou, Z.; Qiao, Y.; Li, Y.; Zhao, C.; Huang, Z.; Liu, B.; et al. Dynamic RRT: Fast feasible path planning in randomly distributed obstacle environments. J. Intell. Robot. Syst. 2023, 107, 48. [Google Scholar] [CrossRef]
- Mashayekhi, R.; Idris, M.Y.I.; Anisi, M.H.; Ahmedy, I. Hybrid RRT: A semi-dual-tree RRT-based motion planner. IEEE Access 2020, 8, 18658–18668. [Google Scholar] [CrossRef]
- Holland, J.H. Genetic algorithms. Sci. Am. 1992, 267, 66–73. [Google Scholar] [CrossRef]
- Ramirez-Atencia, C.; Bello-Orgaz, G.; R-Moreno, M.D.; Camacho, D. Solving complex multi-UAV mission planning problems using multi-objective genetic algorithms. Soft Comput. 2017, 21, 4883–4900. [Google Scholar] [CrossRef]
- Pradeepmon, T.; Sridharan, R.; Panicker, V.V. Development of modified discrete particle swarm optimization algorithm for quadratic assignment problems. Int. J. Ind. Eng. Comput. 2018, 9, 491–508. [Google Scholar] [CrossRef]
- Jain, M.; Saihjpal, V.; Singh, N.; Singh, S.B. An overview of variants and advancements of PSO algorithm. Appl. Sci. 2022, 12, 8392. [Google Scholar] [CrossRef]
- Dorigo, M.; Birattari, M.; Stutzle, T. Ant colony optimization. IEEE Comput. Intell. Mag. 2007, 1, 28–39. [Google Scholar] [CrossRef]
- Jiang, B.; Huang, G.; Wang, T.; Gui, J.; Zhu, X. Trust based energy efficient data collection with unmanned aerial vehicle in edge network. Trans. Emerg. Telecommun. Technol. 2022, 33, e3942. [Google Scholar] [CrossRef]
- Dorigo, M.; Blum, C. Ant colony optimization theory: A survey. Theor. Comput. Sci. 2005, 344, 243–278. [Google Scholar] [CrossRef]
- Minh, D.T.; Dung, N.B. Hybrid algorithms in path planning for autonomous navigation of unmanned aerial vehicle: A comprehensive review. Meas. Sci. Technol. 2024, 35, 112002. [Google Scholar] [CrossRef]
- Ting, T.; Yang, X.S.; Cheng, S.; Huang, K. Hybrid metaheuristic algorithms: Past, present, and future. In Recent Advances in Swarm Intelligence and Evolutionary Computation; Springer: Cham, Switzerland, 2015; pp. 71–83. [Google Scholar]
- Abdel-Basset, M.; Abdel-Fatah, L.; Sangaiah, A.K. Metaheuristic algorithms: A comprehensive review. In Computational Intelligence for Multimedia Big Data on the Cloud with Engineering Applications; Academic Press: Cambridge, MA, USA, 2018; pp. 185–231. [Google Scholar]
- Chen, C.; Cao, L.; Chen, Y.; Chen, B.; Yue, Y. A comprehensive survey of convergence analysis of beetle antennae search algorithm and its applications. Artif. Intell. Rev. 2024, 57, 141. [Google Scholar] [CrossRef]
- Wu, Q.; Shen, X.; Jin, Y.; Chen, Z.; Li, S.; Khan, A.H.; Chen, D. Intelligent beetle antennae search for UAV sensing and avoidance of obstacles. Sensors 2019, 19, 1758. [Google Scholar] [CrossRef]
- Kang, Y.; Hedrick, J.K. Linear tracking for a fixed-wing UAV using nonlinear model predictive control. IEEE Trans. Control Syst. Technol. 2009, 17, 1202–1210. [Google Scholar] [CrossRef]
- Mkiramweni, M.E.; Yang, C.; Li, J.; Zhang, W. A survey of game theory in unmanned aerial vehicles communications. IEEE Commun. Surv. Tutor. 2019, 21, 3386–3416. [Google Scholar] [CrossRef]
- Cui, Z.; Wang, Y. UAV path planning based on multi-layer reinforcement learning technique. IEEE Access 2021, 9, 59486–59497. [Google Scholar] [CrossRef]
- Afifi, G.; Gadallah, Y. Cellular Network-Supported Machine Learning Techniques for Autonomous UAV Trajectory Planning. IEEE Access 2022, 10, 131996–132011. [Google Scholar] [CrossRef]
- 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]
- Wang, Z.; Ng, S.X.; El-Hajjar, M. A 3D Spatial Information Compression Based Deep Reinforcement Learning Technique for UAV Path Planning in Cluttered Environments. IEEE Open J. Veh. Technol. 2025, 6, 647–661. [Google Scholar] [CrossRef]
- Sanyal, S.; Joshi, A.; Nagaraj, M.; Manna, R.K.; Roy, K. Energy-Efficient Autonomous Aerial Navigation with Dynamic Vision Sensors: A Physics-Guided Neuromorphic Approach. arXiv 2025, arXiv:2502.05938. [Google Scholar]
- Mahesh, B. Machine learning algorithms—A review. Int. J. Sci. Res. (IJSR) 2020, 9, 381–386. [Google Scholar] [CrossRef]
- Cunningham, P.; Cord, M.; Delany, S.J. Supervised learning. In Machine Learning Techniques for Multimedia: Case Studies on Organization and Retrieval; Springer: Berlin/Heidelberg, Germany, 2008; pp. 21–49. [Google Scholar]
- Hastie, T.; Tibshirani, R.; Friedman, J.; Hastie, T.; Tibshirani, R.; Friedman, J. Overview of supervised learning. In The Elements of Statistical Learning: Data Mining, Inference, and Prediction; Springer: New York, NY, USA, 2009; pp. 9–41. [Google Scholar]
- Miura, J. Support vector path planning. In Proceedings of the 2006 IEEE/RSJ International Conference on Intelligent Robots and Systems, Beijing, China, 9–15 October 2006; pp. 2894–2899. [Google Scholar]
- Chen, Y.; Zu, W.; Fan, G.; Chang, H. Unmanned aircraft vehicle path planning based on SVM algorithm. In Foundations and Practical Applications of Cognitive Systems and Information Processing; Springer: Berlin/Heidelberg, Germany, 2014; pp. 705–714. [Google Scholar]
- Moon, B.; Akagi, C.; Peterson, C.K. Decentralized Multi-Agent Search for Moving Targets Using Road Network Gaussian Process Regressions. Drones 2024, 8, 606. [Google Scholar] [CrossRef]
- Zhang, C.; Wang, Y.; Zheng, W. Multi-UAVs Tracking Non-Cooperative Target Using Constrained Iterative Linear Quadratic Gaussian. Drones 2024, 8, 326. [Google Scholar] [CrossRef]
- Almazrouei, K.; Kamel, I.; Rabie, T. Dynamic obstacle avoidance and path planning through reinforcement learning. Appl. Sci. 2023, 13, 8174. [Google Scholar] [CrossRef]
- Hong, D.; Lee, S.; Cho, Y.H.; Baek, D.; Kim, J.; Chang, N. Energy-efficient online path planning of multiple drones using reinforcement learning. IEEE Trans. Veh. Technol. 2021, 70, 9725–9740. [Google Scholar] [CrossRef]
- Li, B.; Wu, Y. Path planning for UAV ground target tracking via deep reinforcement learning. IEEE Access 2020, 8, 29064–29074. [Google Scholar] [CrossRef]
- He, L.; Aouf, N.; Song, B. Explainable Deep Reinforcement Learning for UAV autonomous path planning. Aerosp. Sci. Technol. 2021, 118, 107052. [Google Scholar] [CrossRef]
- Zhang, D.; Xuan, Z.; Zhang, Y.; Yao, J.; Li, X.; Li, X. Path planning of unmanned aerial vehicle in complex environments based on state-detection twin delayed deep deterministic policy gradient. Machines 2023, 11, 108. [Google Scholar] [CrossRef]
- Wu, X.; Huang, S.; Huang, G. Deep reinforcement learning-based 2.5 D multi-objective path planning for ground vehicles: Considering distance and energy consumption. Electronics 2023, 12, 3840. [Google Scholar] [CrossRef]
- Kaelbling, L.P.; Littman, M.L.; Moore, A.W. Reinforcement learning: A survey. J. Artif. Intell. Res. 1996, 4, 237–285. [Google Scholar] [CrossRef]
- Wiering, M.A.; Van Otterlo, M. Reinforcement learning. Adapt. Learn. Optim. 2012, 12, 729. [Google Scholar]
- Yan, C.; Xiang, X. A path planning algorithm for UAV based on improved Q-learning. In Proceedings of the 2018 2nd International Conference on Robotics and Automation Sciences (ICRAS), Wuhan, China, 23–25 June 2018; pp. 1–5. [Google Scholar]
- Yang, Y.; Juntao, L.; Lingling, P. Multi-robot path planning based on a deep reinforcement learning DQN algorithm. CAAI Trans. Intell. Technol. 2020, 5, 177–183. [Google Scholar] [CrossRef]
- Yan, C.; Xiang, X.; Wang, C. Towards real-time path planning through deep reinforcement learning for a UAV in dynamic environments. J. Intell. Robot. Syst. 2020, 98, 297–309. [Google Scholar] [CrossRef]
- Tian, S.; Li, Y.; Zhang, X.; Zheng, L.; Cheng, L.; She, W.; Xie, W. Fast UAV path planning in urban environments based on three-step experience buffer sampling DDPG. Digit. Commun. Netw. 2024, 10, 813–826. [Google Scholar] [CrossRef]
- Bouhamed, O.; Ghazzai, H.; Besbes, H.; Massoud, Y. Autonomous UAV navigation: A DDPG-based deep reinforcement learning approach. In Proceedings of the 2020 IEEE International Symposium on Circuits and Systems (ISCAS), Seville, Spain, 12–14 October 2020; pp. 1–5. [Google Scholar]
- LeCun, Y.; Bengio, Y.; Hinton, G. Deep learning. Nature 2015, 521, 436–444. [Google Scholar] [CrossRef] [PubMed]
- 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]
- Bayerlein, H.; Theile, M.; Caccamo, M.; Gesbert, D. Multi-UAV path planning for wireless data harvesting with deep reinforcement learning. IEEE Open J. Commun. Soc. 2021, 2, 1171–1187. [Google Scholar] [CrossRef]
- Castro, G.G.d.; Berger, G.S.; Cantieri, A.; Teixeira, M.; Lima, J.; Pereira, A.I.; Pinto, M.F. Adaptive path planning for fusing rapidly exploring random trees and deep reinforcement learning in an agriculture dynamic environment UAVs. Agriculture 2023, 13, 354. [Google Scholar] [CrossRef]
- Voulodimos, A.; Doulamis, N.; Doulamis, A.; Protopapadakis, E. Deep learning for computer vision: A brief review. Comput. Intell. Neurosci. 2018, 2018, 7068349. [Google Scholar] [CrossRef]
- Li, Y.; Ma, L.; Zhong, Z.; Liu, F.; Chapman, M.A.; Cao, D.; Li, J. Deep learning for lidar point clouds in autonomous driving: A review. IEEE Trans. Neural Netw. Learn. Syst. 2020, 32, 3412–3432. [Google Scholar] [CrossRef]
- Zhang, L.; Zhang, L.; Du, B. Deep learning for remote sensing data: A technical tutorial on the state of the art. IEEE Geosci. Remote Sens. Mag. 2016, 4, 22–40. [Google Scholar] [CrossRef]
- Sze, V.; Chen, Y.H.; Yang, T.J.; Emer, J.S. Efficient processing of deep neural networks: A tutorial and survey. Proc. IEEE 2017, 105, 2295–2329. [Google Scholar] [CrossRef]
- Zhang, Z.; Wang, S.; Chen, J.; Han, Y. A bionic dynamic path planning algorithm of the micro UAV based on the fusion of deep neural network optimization/filtering and hawk-eye vision. IEEE Trans. Syst. Man Cybern. Syst. 2023, 53, 3728–3740. [Google Scholar] [CrossRef]
- Akshya, J.; Neelamegam, G.; Sureshkumar, C.; Nithya, V.; Kadry, S. Enhancing UAV Path Planning Efficiency through Adam-Optimized Deep Neural Networks for Area Coverage Missions. Procedia Comput. Sci. 2024, 235, 2–11. [Google Scholar]
- Sivaranjani, A.; Vinod, B. Artificial Potential Field Incorporated Deep-Q-Network Algorithm for Mobile Robot Path Prediction. Intell. Autom. Soft Comput. 2023, 35, 1745–1760. [Google Scholar] [CrossRef]
- Cuomo, S.; Di Cola, V.S.; Giampaolo, F.; Rozza, G.; Raissi, M.; Piccialli, F. Scientific machine learning through physics–informed neural networks: Where we are and what’s next. J. Sci. Comput. 2022, 92, 88. [Google Scholar] [CrossRef]
- Kyrkou, C.; Plastiras, G.; Theocharides, T.; Venieris, S.I.; Bouganis, C.S. DroNet: Efficient convolutional neural network detector for real-time UAV applications. In Proceedings of the 2018 Design, Automation & Test in Europe Conference & Exhibition (DATE), Dresden, Germany, 19–23 March 2018; pp. 967–972. [Google Scholar]
- O’Shea, K. An introduction to convolutional neural networks. arXiv 2015, arXiv:1511.08458. [Google Scholar]
- Bae, H.; Kim, G.; Kim, J.; Qian, D.; Lee, S. Multi-robot path planning method using reinforcement learning. Appl. Sci. 2019, 9, 3057. [Google Scholar] [CrossRef]
- Li, S.; Qian, Y. Unmanned Aerial Vehicle Autonomous Flight Path Planning Algorithm Based on Deep Learning. In Proceedings of the 2024 International Conference on Telecommunications and Power Electronics (TELEPE), Frankfurt, Germany, 29–31 May 2024; pp. 632–637. [Google Scholar]
- Porzi, L.; Rota Bulò, S.; Lepri, B.; Ricci, E. Predicting and understanding urban perception with convolutional neural networks. In Proceedings of the 23rd ACM International Conference on Multimedia, Brisbane, Australia, 26–30 October 2015; pp. 139–148. [Google Scholar]
- McGuire, K.N.; De Wagter, C.; Tuyls, K.; Kappen, H.J.; de Croon, G.C. Minimal navigation solution for a swarm of tiny flying robots to explore an unknown environment. Sci. Robot. 2019, 4, eaaw9710. [Google Scholar] [CrossRef]
- Creswell, A.; White, T.; Dumoulin, V.; Arulkumaran, K.; Sengupta, B.; Bharath, A.A. Generative adversarial networks: An overview. IEEE Signal Process. Mag. 2018, 35, 53–65. [Google Scholar] [CrossRef]
- Ma, N.; Wang, J.; Liu, J.; Meng, M.Q.H. Conditional generative adversarial networks for optimal path planning. IEEE Trans. Cogn. Dev. Syst. 2021, 14, 662–671. [Google Scholar] [CrossRef]
- Eskandari, M.; Savkin, A.V. GANs the UAV Path Planner: UAV-Based RIS-Assisted Wireless Communication for Internet of Autonomous Vehicles. In Proceedings of the 2024 IEEE 19th Conference on Industrial Electronics and Applications (ICIEA), Kristiansand, Norway, 5–8 August 2024; pp. 1–6. [Google Scholar]
- Gan, J.; Li, M.; Li, Q.; Zhang, R.; Zheng, X. IUAV Path Planning Using a Multiobjective Projection Algorithm. IEEE Trans. Ind. Inform. 2024, 20, 13069–13076. [Google Scholar] [CrossRef]
- Mohammadi, M.; Al-Fuqaha, A.; Oh, J.S. Path planning in support of smart mobility applications using generative adversarial networks. In Proceedings of the 2018 IEEE International Conference on Internet of Things (iThings) and IEEE Green Computing and Communications (GreenCom) and IEEE Cyber, Physical and Social Computing (CPSCom) and IEEE Smart Data (SmartData), Halifax, NS, Canada, 30 July–3 August 2018; pp. 878–885. [Google Scholar]
- Yan, H.; Chen, Y.; Yang, S.H. New energy consumption model for rotary-wing UAV propulsion. IEEE Wirel. Commun. Lett. 2021, 10, 2009–2012. [Google Scholar] [CrossRef]
- Na, Y.; Li, Y.; Chen, D.; Yao, Y.; Li, T.; Liu, H.; Wang, K. Optimal energy consumption path planning for unmanned aerial vehicles based on improved particle swarm optimization. Sustainability 2023, 15, 12101. [Google Scholar] [CrossRef]
- Cabreira, T.M.; Di Franco, C.; Ferreira, P.R.; Buttazzo, G.C. Energy-aware spiral coverage path planning for uav photogrammetric applications. IEEE Robot. Autom. Lett. 2018, 3, 3662–3668. [Google Scholar] [CrossRef]
- Palossi, D.; Furci, M.; Naldi, R.; Marongiu, A.; Marconi, L.; Benini, L. An energy-efficient parallel algorithm for real-time near-optimal uav path planning. In Proceedings of the ACM International Conference on Computing Frontiers, Como, Italy, 16–19 May 2016; pp. 392–397. [Google Scholar]
- Yacef, F.; Rizoug, N.; Degaa, L.; Hamerlain, M. Energy-efficiency path planning for quadrotor UAV under wind conditions. In Proceedings of the 2020 7th International Conference on Control, Decision and Information Technologies (CoDIT), Prague, Czech Republic, 29 June–2 July 2020; Volume 1, pp. 1133–1138. [Google Scholar]
- Sarıçiçek, İ.; Akkuş, Y. Unmanned aerial vehicle hub-location and routing for monitoring geographic borders. Appl. Math. Model. 2015, 39, 3939–3953. [Google Scholar] [CrossRef]
- Yu, V.F.; Lin, S.Y. Solving the location-routing problem with simultaneous pickup and delivery by simulated annealing. Int. J. Prod. Res. 2016, 54, 526–549. [Google Scholar] [CrossRef]
- Tian, P.; Chao, H.; Rhudy, M.; Gross, J.; Wu, H. Wind sensing and estimation using small fixed-wing unmanned aerial vehicles: A survey. J. Aerosp. Inf. Syst. 2021, 18, 132–143. [Google Scholar] [CrossRef]
- Shamshad, A.; Bawadi, M.; Hussin, W.W.; Majid, T.A.; Sanusi, S. First and second order Markov chain models for synthetic generation of wind speed time series. Energy 2005, 30, 693–708. [Google Scholar] [CrossRef]
- Negra, N.B.; Holmstrøm, O.; Bak-Jensen, B.; Sørensen, P. Model of a synthetic wind speed time series generator. Wind Energy Int. J. Prog. Appl. Wind Power Convers. Technol. 2008, 11, 193–209. [Google Scholar] [CrossRef]
- Li, Y.; Liu, M. Path planning of electric VTOL UAV considering minimum energy consumption in urban areas. Sustainability 2022, 14, 13421. [Google Scholar] [CrossRef]
- Dorling, K.; Heinrichs, J.; Messier, G.G.; Magierowski, S. Vehicle routing problems for drone delivery. IEEE Trans. Syst. Man Cybern. Syst. 2016, 47, 70–85. [Google Scholar] [CrossRef]
- Kim, S.J.; Lim, G.J.; Cho, J. Drone flight scheduling under uncertainty on battery duration and air temperature. Comput. Ind. Eng. 2018, 117, 291–302. [Google Scholar] [CrossRef]
- Yan, X.; Chen, R.; Jiang, Z. UAV Cluster Mission Planning Strategy for Area Coverage Tasks. Sensors 2023, 23, 9122. [Google Scholar] [CrossRef] [PubMed]
- Makam, S.; Komatineni, B.K.; Meena, S.S.; Meena, U. Unmanned aerial vehicles (UAVs): An adoptable technology for precise and smart farming. Discov. Internet Things 2024, 4, 12. [Google Scholar] [CrossRef]
- Ghauri, S.A.; Sarfraz, M.; Qamar, R.A.; Sohail, M.F.; Khan, S.A. A Review of Multi-UAV Task Allocation Algorithms for a Search and Rescue Scenario. J. Sens. Actuator Netw. 2024, 13, 47. [Google Scholar] [CrossRef]
- Wang, W.; Zhang, G.; Da, Q.; Lu, D.; Zhao, Y.; Li, S.; Lang, D. Multiple unmanned aerial vehicle autonomous path planning algorithm based on whale-inspired deep Q-network. Drones 2023, 7, 572. [Google Scholar] [CrossRef]
- Choi, H.L.; Brunet, L.; How, J.P. Consensus-based decentralized auctions for robust task allocation. IEEE Trans. Robot. 2009, 25, 912–926. [Google Scholar] [CrossRef]
- Qamar, R.A.; Sarfraz, M.; Ghauri, S.A.; Baig, N.A.; Cheema, T.A. Optimization of Dynamic Task. Allocation forMulti-UAV Systems: Search and Rescue Scenario. 2024. Available online: https://www.researchsquare.com/article/rs-3879027/v1 (accessed on 24 January 2024).
- Meng, K.; He, X.; Wu, Q.; Li, D. Multi-UAV collaborative sensing and communication: Joint task allocation and power optimization. IEEE Trans. Wirel. Commun. 2022, 22, 4232–4246. [Google Scholar] [CrossRef]
- Zhang, P.; He, Y.; Wang, Z.; Li, S.; Liang, Q. Research on Multi-UAV Obstacle Avoidance with Optimal Consensus Control and Improved APF. Drones 2024, 8, 248. [Google Scholar] [CrossRef]
- Luo, W.; Tang, Q.; Fu, C.; Eberhard, P. Deep-sarsa based multi-UAV path planning and obstacle avoidance in a dynamic environment. In Proceedings of the Advances in Swarm Intelligence: 9th International Conference, ICSI 2018, Shanghai, China, 17–22 June 2018; Proceedings, Part II 9. Springer: Berlin/Heidelberg, Germany, 2018; pp. 102–111. [Google Scholar]
- Wang, L.; Huang, W.; Li, H.; Li, W.; Chen, J.; Wu, W. A review of collaborative trajectory planning for multiple unmanned aerial vehicles. Processes 2024, 12, 1272. [Google Scholar] [CrossRef]
- Khan, A.A.; Khan, M.M.; Khan, K.M.; Arshad, J.; Ahmad, F. A blockchain-based decentralized machine learning framework for collaborative intrusion detection within UAVs. Comput. Netw. 2021, 196, 108217. [Google Scholar] [CrossRef]
- Mao, A.; Tang, X.; Ding, Z.; Li, Z. Scalability optimization of centralized cluster resource scheduling framework. J. Comput. Res. Dev. 2021, 58, 497–512. [Google Scholar]
- Liu, J.; Zhang, Z.; Xu, T.; Yan, C. Multi-UAV United Task Allocation via Extended Market Mechanism Based on Flight Path Cost. In Proceedings of the 2024 IEEE International Conference on Unmanned Systems (ICUS), Nanjing, China, 18–20 October 2024; pp. 50–55. [Google Scholar]
- Zhu, A.; Yang, S.X. A neural network approach to dynamic task assignment of multirobots. IEEE Trans. Neural Netw. 2006, 17, 1278–1287. [Google Scholar] [PubMed]
- Dai, W.; Lu, H.; Xiao, J.; Zeng, Z.; Zheng, Z. Multi-robot dynamic task allocation for exploration and destruction. J. Intell. Robot. Syst. 2020, 98, 455–479. [Google Scholar] [CrossRef]
- Xiong, T.; Liu, F.; Liu, H.; Ge, J.; Li, H.; Ding, K.; Li, Q. Multi-drone optimal mission assignment and 3D path planning for disaster rescue. Drones 2023, 7, 394. [Google Scholar] [CrossRef]
- Chandran, I.; Vipin, K. Multi-UAV networks for disaster monitoring: Challenges and opportunities from a network perspective. Drone Syst. Appl. 2024, 12, 1–28. [Google Scholar]
- Muñoz, J.; López, B.; Quevedo, F.; Monje, C.A.; Garrido, S.; Moreno, L.E. Multi UAV coverage path planning in urban environments. Sensors 2021, 21, 7365. [Google Scholar] [CrossRef]
- Wu, Q.; Su, Y.; Tan, W.; Zhan, R.; Liu, J.; Jiang, L. UAV Path Planning Trends from 2000 to 2024: A Bibliometric Analysis and Visualization. Drones 2025, 9, 128. [Google Scholar] [CrossRef]
- Liu, J.; Yan, Y.; Yang, Y.; Li, J. An improved artificial potential field UAV path planning algorithm guided by RRT under environment-aware modeling: Theory and simulation. IEEE Access 2024, 12, 12080–12097. [Google Scholar] [CrossRef]
- Zhang, W.; Zhang, S.; Wu, F.; Wang, Y. Path planning of UAV based on improved adaptive grey wolf optimization algorithm. IEEE Access 2021, 9, 89400–89411. [Google Scholar] [CrossRef]
- Ramezani, M.; Amiri Atashgah, M.; Rezaee, A. A Fault-Tolerant Multi-Agent Reinforcement Learning Framework for Unmanned Aerial Vehicles–Unmanned Ground Vehicle Coverage Path Planning. Drones 2024, 8, 537. [Google Scholar] [CrossRef]
- McEnroe, P.; Wang, S.; Liyanage, M. A survey on the convergence of edge computing and AI for UAVs: Opportunities and challenges. IEEE Internet Things J. 2022, 9, 15435–15459. [Google Scholar] [CrossRef]
- Zhang, T.; Xu, Y.; Loo, J.; Yang, D.; Xiao, L. Joint computation and communication design for UAV-assisted mobile edge computing in IoT. IEEE Trans. Ind. Inform. 2019, 16, 5505–5516. [Google Scholar] [CrossRef]
- Zhou, F.; Wu, Y.; Sun, H.; Chu, Z. UAV-enabled mobile edge computing: Offloading optimization and trajectory design. In Proceedings of the 2018 IEEE International Conference on Communications (ICC), Kansas City, MO, USA, 20–24 May 2018; pp. 1–6. [Google Scholar]
- Xu, J.; Yao, H.; Zhang, R.; Mai, T.; Huang, S.; Guo, S. Federated learning powered semantic communication for UAV swarm cooperation. IEEE Wirel. Commun. 2024, 31, 140–146. [Google Scholar] [CrossRef]
- Lim, W.Y.B.; Garg, S.; Xiong, Z.; Zhang, Y.; Niyato, D.; Leung, C.; Miao, C. UAV-assisted communication efficient federated learning in the era of the artificial intelligence of things. IEEE Netw. 2021, 35, 188–195. [Google Scholar] [CrossRef]
- Balestrieri, E.; Daponte, P.; De Vito, L.; Picariello, F.; Tudosa, I. Sensors and measurements for UAV safety: An overview. Sensors 2021, 21, 8253. [Google Scholar] [CrossRef]
- Khan, A.A.; Laghari, A.A.; Awan, S.A. Machine learning in computer vision: A review. EAI Endorsed Trans. Scalable Inf. Syst. 2021, 8, 1–11. [Google Scholar] [CrossRef]
- Al-Fraihat, D.; Sharrab, Y.; Alzyoud, F.; Qahmash, A.; Tarawneh, M.; Maaita, A. Speech recognition utilizing deep learning: A systematic review of the latest developments. Hum.-Centric Comput. Inf. Sci. 2024, 14, 1–34. [Google Scholar] [CrossRef]
- Luo, X.; Wang, Q.; Gong, H.; Tang, C. UAV path planning based on the average TD3 algorithm with prioritized experience replay. IEEE Access 2024, 12, 38017–38029. [Google Scholar] [CrossRef]
- Abdalmanan, N.; Kamarudin, K.; Bakar, M.A.A.; Rahiman, M.H.F.; Zakaria, A.; Mamduh, S.M.; Kamarudin, L.M. 2D lidar based reinforcement learning for multi-target path planning in unknown environment. IEEE Access 2023, 11, 35541–35555. [Google Scholar] [CrossRef]
- Harun, M.H.; Abdullah, S.S.; Aras, M.S.M.; Bahar, M.B. Sensor fusion technology for unmanned autonomous vehicles (UAV): A review of methods and applications. In Proceedings of the 2022 IEEE 9th International Conference on Underwater System Technology: Theory and Applications (USYS), Kuala Lumpur, Malaysia, 5–6 December 2022; pp. 1–8. [Google Scholar]
- Derrouaoui, S.H.; Bouzid, Y.; Guiatni, M.; Dib, I. A comprehensive review on reconfigurable drones: Classification, characteristics, design and control technologies. Unmanned Syst. 2022, 10, 3–29. [Google Scholar] [CrossRef]
- Gianfelice, M.; Aboshosha, H.; Ghazal, T. Real-time wind predictions for safe drone flights in Toronto. Results Eng. 2022, 15, 100534. [Google Scholar] [CrossRef]
- Youn, W.; Ko, H.; Choi, H.; Choi, I.; Baek, J.H.; Myung, H. Collision-free autonomous navigation of a small UAV using low-cost sensors in GPS-denied environments. Int. J. Control Autom. Syst. 2021, 19, 953–968. [Google Scholar] [CrossRef]
- Radwan, A.; Tourani, A.; Bavle, H.; Voos, H.; Sanchez-Lopez, J.L. UAV-assisted Visual SLAM Generating Reconstructed 3D Scene Graphs in GPS-denied Environments. In Proceedings of the 2024 International Conference on Unmanned Aircraft Systems (ICUAS), Chania, Crete, Greece, 4–7 June 2024; pp. 1109–1116. [Google Scholar]
- Siwek, M.; Baranowski, L.; Ładyżyńska-Kozdraś, E. The Application and Optimisation of a Neural Network PID Controller for Trajectory Tracking Using UAVs. Sensors 2024, 24, 8072. [Google Scholar] [CrossRef] [PubMed]
- Aljalaud, F.; Alohali, Y. Optimizing Autonomous Multi-UAV Path Planning for Inspection Missions: A Comparative Study of Genetic and Stochastic Hill Climbing Algorithms. Energies 2024, 18, 50. [Google Scholar] [CrossRef]
- De Petrillo, M.; Beard, J.; Gu, Y.; Gross, J.N. Search planning of a uav/ugv team with localization uncertainty in a subterranean environment. IEEE Aerosp. Electron. Syst. Mag. 2021, 36, 6–16. [Google Scholar] [CrossRef]
- Li, J.; Deng, G.; Luo, C.; Lin, Q.; Yan, Q.; Ming, Z. A hybrid path planning method in unmanned air/ground vehicle (UAV/UGV) cooperative systems. IEEE Trans. Veh. Technol. 2016, 65, 9585–9596. [Google Scholar] [CrossRef]
- Nowakowski, M.; Berger, G.S.; Braun, J.; Mendes, J.a.; Bonzatto Junior, L.; Lima, J. Advance Reconnaissance of UGV Path Planning Using Unmanned Aerial Vehicle to Carry Our Mission in Unknown Environment. In Robot 2023: Sixth Iberian Robotics Conference; Springer: Cham, Switzerland, 2023; pp. 50–61. [Google Scholar]
- Hu, D.; Gan, V.J.; Wang, T.; Ma, L. Multi-agent robotic system (MARS) for UAV-UGV path planning and automatic sensory data collection in cluttered environments. Build. Environ. 2022, 221, 109349. [Google Scholar] [CrossRef]
Objective | Description |
---|---|
Minimum length path | Determines the route that minimizes total distance traveled, reducing flight time and enhancing task efficiency. Under constant-velocity conditions, this path corresponds to the shortest flight duration [44,45]. |
Energy consumption path | Focuses on minimizing UAV energy usage by considering factors such as flight speed, altitude changes, and air resistance. Rational path planning ensures optimal energy efficiency during the mission [30]. |
Collision-free path | Ensures UAV safety by navigating around static and dynamic obstacles. Hybrid navigation approaches allow safe operation in 3D, partially unknown, and dynamic environments [46]. |
Multi-objective optimization path | Balances multiple objectives, such as minimizing travel time, energy consumption, and risks. Advanced algorithms are used in complex scenarios like military reconnaissance or emergency rescue to achieve optimal trade-offs [47,48]. |
Evaluation Metric | Description | Influencing Factors |
---|---|---|
Path length | The total length of the path, typically used to measure the brevity of the route, especially in shortest-path problems. | Obstacle distribution, environmental complexity |
Computation time | The time required by the path planning algorithm. In real-time tasks, it directly determines whether the task can be completed on schedule. | Environmental complexity, algorithm efficiency, hardware performance |
Energy consumption | The energy consumed during the UAV’s flight, often related to battery usage. Optimizing energy consumption is critical for long-duration tasks. | Flight trajectory, altitude, speed control, environmental factors |
Path safety | The safety of the path, assessing its ability to avoid collisions with static and dynamic obstacles to prevent UAV damage. | Obstacle types, density, dynamics |
Path smoothness | The smoothness of the path, ensuring it aligns with the UAV’s motion characteristics. Sharp turns may hinder efficient task execution. | Flight control limitations, smoothing strategies in the algorithm |
Robustness | The adaptability of the algorithm to environmental changes and uncertainties, such as dynamic obstacles in changing environments. | Algorithm adaptability, real-time responsiveness |
Category | Subdivided Algorithms | Core Principle | Typical Application Scenarios | Advantages | Disadvantages |
---|---|---|---|---|---|
Graph-Based Algorithms | Static Optimal Search (Dijkstra, A*) | Discrete graph model and priority queue; Dijkstra without heuristics, A* with heuristic function | Indoor navigation; road network path planning; grid map scenarios | Dijkstra: Globally optimal, theoretically complete; A*: Heuristic acceleration balancing efficiency and optimality; high path smoothness | Dijkstra: Complexity , inefficient for large-scale scenarios; A*: Heuristic-dependent, suboptimal with poor design; only suitable for known environments |
Dynamic Replanning (D*, D*-Lite) | Incremental replanning by reverse-updating affected nodes | Dynamic obstacle scenarios (e.g., disaster relief, dynamic obstacle avoidance) | Incremental update using historical information, avoiding global replanning; strong adaptability to dynamic environments | Dramatic overhead with frequent changes; time-consuming node priority calculation in complex environments | |
Optimization Methods | Linear Programming (LP) | Linear objective function and linear constraints, relying on mature solvers | Simple kinematic constraints | Fast solving, suitable for simple scenarios with low real-time requirements; mathematically guaranteed solution feasibility | Unable to handle nonlinear constraints; model simplification may lead to practical infeasibility |
Nonlinear Programming (NLP, SNLP) | Nonlinear objectives/constraints, supporting curved trajectories and kinematic limitations | UAV formation control 3D complex trajectory generation | Accurate modeling of UAV kinematic constraints; support for curved trajectory optimization adapting to complex kinematic limitations | High computational complexity, poor real-time performance; prone to local optima, dependent on initial point selection | |
Random Sampling Algorithms | Random Sampling Algorithms (RRT, RRT*, RRT-Connect) | Random sampling + tree structure expansion; RRT* for asymptotic optimality, RRT-Connect for bidirectional search acceleration | Unknown dynamic environments | No prior environment knowledge, suitable for unknown/dynamic scenarios; RRT* for asymptotic optimality, RRT-Connect for accelerated search | Poor path quality of basic RRT (non-optimal); low passage rate in narrow channels due to sampling randomness |
Probabilistic Roadmap (PRM, PRM*, Lazy PRM) | Preprocessing to construct collision-free graphs, using graph-based search for queries | Static high-dimensional environments | Efficient multiple queries after preprocessing; PRM* improves success rate in narrow areas via adaptive sampling | Long preprocessing time, unsuitable for dynamic environments; uniform sampling may miss critical passages | |
Bio-inspired Algorithms | GA | Evolution of path populations via selection, crossover, and mutation, supporting multi-objective optimization | Multi-UAV task allocation, complex constraint scenarios | Native support for multi-objective optimization; strong robustness adapting to complex constraint combinations; strong solution-space-exploration ability; prone to premature convergence into local optima; | Time-consuming evolution process, sensitive to parameters (crossover/mutation probabilities) |
PSO | Simulating bird/fish swarm behavior, iteratively updating individual and global best solutions | Rapid feasible solution generation | Fast convergence; few parameters, simple implementation | Particle aggregation in high-dimensional spaces, reduced search accuracy; dependent on initial distribution, weak global search capability | |
ACO | Pheromone accumulation guiding path search, adapting to dynamic task allocation | Multi-robot collaboration, logistics distribution path optimization | Suitable for dynamic task allocation and path optimization; natural balance between exploration and exploitation via pheromone mechanism | High computational complexity, inefficient for large-scale scenarios; difficult parameter tuning for pheromone evaporation, prone to stagnation |
Dimension | Path Length | Consumption Time | Energy Consumption | Path Safety | Path Smoothness | Robustness | Multi-Objective Handling |
---|---|---|---|---|---|---|---|
Static Optimal Search | Theoretically shortest | High | Relatively low | High | High | High | Single objective |
Dynamic Replanning | Close to optimal | Medium | Relatively low | Medium | High | Medium | Single objective and dynamic weights |
LP | Theoretically optimal | Medium | Relatively low | Medium | High | Low | Single objective |
NLP | Locally optimal solution length | Extremely high | Relatively low | High | High | Low | Single objective + weighted sum |
RRT | Usually longer | Low | Relatively high | Medium | Low | Medium | Single objective |
PRM | Probabilistically close to optimal | High | Medium | Medium | Medium | Low | Single objective |
GA | Approaching optimality through iteration | High | Medium | High | Medium | High | Native support |
PSO | Locally optimal solution length | Low | Medium | Medium | Medium | Medium | Weighted transformation to single objective |
ACO | Asymptotically approaching optimal length | High | Medium | Medium | Medium | High | Multi-stage optimization |
Attribute | DNN | CNN | GAN |
---|---|---|---|
Core Function | High-dimensional feature extraction; trajectory prediction | Image feature extraction; obstacle recognition | Trajectory generation; environment simulation |
Network Structure | Multi-layer fully connected network (FC) | Convolution and pooling network (Conv + Pool) | Generator–discriminator adversarial architecture |
Training Method | Supervised learning (regression/classification) | Supervised learning (visual navigation) | Unsupervised adversarial training |
Advantages | Fast convergence; high trajectory continuity | Accurate perception; strong local feature modeling | Diversity generation; augmenting training data |
Disadvantages | Error accumulation; poor adaptability to dynamic environments | Sensitive to lighting/occlusion; inference latency | Unstable training; risk of mode collapse |
Suitable Scenarios | Static area coverage; trajectory prediction | UAV visual obstacle avoidance; visual navigation | Complex environment simulation; reinforcement learning assistance |
Aspect | Description |
---|---|
Minimize flight distance | Calculating the shortest path from the starting point to the target point can effectively reduce the total energy consumption of the aircraft [172]. |
Flight path optimization | Optimizing flight speed to minimize air resistance and improve the efficiency of propulsion systems is a key part of energy optimization [173]. |
Dynamic adjustment of flight strategy | Real-time missions require UAVs to dynamically adjust their paths based on environmental changes, such as wind variations or obstacles [60]. |
Aspect | Centralized Path Planning | Distributed Path Planning |
---|---|---|
Advantages |
|
|
Limitations |
|
|
Key Methods |
| |
Application Scenarios |
|
|
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. |
© 2025 by the authors. Licensee MDPI, Basel, Switzerland. This article is an open access article distributed under the terms and conditions of the Creative Commons Attribution (CC BY) license (https://creativecommons.org/licenses/by/4.0/).
Share and Cite
Meng, W.; Zhang, X.; Zhou, L.; Guo, H.; Hu, X. Advances in UAV Path Planning: A Comprehensive Review of Methods, Challenges, and Future Directions. Drones 2025, 9, 376. https://doi.org/10.3390/drones9050376
Meng W, Zhang X, Zhou L, Guo H, Hu X. Advances in UAV Path Planning: A Comprehensive Review of Methods, Challenges, and Future Directions. Drones. 2025; 9(5):376. https://doi.org/10.3390/drones9050376
Chicago/Turabian StyleMeng, Wenlong, Xuegang Zhang, Lvzhuoyu Zhou, Hangyu Guo, and Xin Hu. 2025. "Advances in UAV Path Planning: A Comprehensive Review of Methods, Challenges, and Future Directions" Drones 9, no. 5: 376. https://doi.org/10.3390/drones9050376
APA StyleMeng, W., Zhang, X., Zhou, L., Guo, H., & Hu, X. (2025). Advances in UAV Path Planning: A Comprehensive Review of Methods, Challenges, and Future Directions. Drones, 9(5), 376. https://doi.org/10.3390/drones9050376