A literature review of UAV 3D path planning

3D path planning of unmanned aerial vehicle (UAV) targets at finding an optimal and collision free path in a 3D cluttered environment while taking into account the geometric, physical and temporal constraints. Although a lot of works have been done to solve UAV 3D path planning problem, there lacks a comprehensive survey on this topic, let alone the recently published works that focus on this field. This paper analyses the most successful UAV 3D path planning algorithms that developed in recent years. This paper classifies the UAV 3D path planning methods into five categories, sampling-based algorithms, node-based algorithms, mathematical model based algorithms, Bio-inspired algorithms, and multi-fusion based algorithms. For each category a critical analysis and comparison is given. Furthermore a comprehensive applicable analysis for each kind of method is presented after considering its working mechanism and time complexity.

  • DOI: 10.1109/WCICA.2014.7053093
  • Corpus ID: 18742752

A literature review of UAV 3D path planning

  • Liang Yang , Juntong Qi , +1 author Xia Yong
  • Published in Proceeding of the 11th World… 1 June 2014
  • Computer Science, Engineering
  • Proceeding of the 11th World Congress on Intelligent Control and Automation

Figures and Tables from this paper

figure 3

175 Citations

Survey of robot 3d path planning algorithms, a study on 3d optimal path planning for quadcopter uav based on d* lite, sampling based path planning algorithm for uav collision avoidance, a 3d uav path planning model based on improved a* algorithm and dem data, uav path planning using optimization approaches: a survey, improved chimp optimization algorithm for three-dimensional path planning problem, path planning in unmanned aerial vehicles: an optimistic overview, 3d path planning, routing algorithms and routing protocols for unmanned air vehicles: a review, a distributed pareto-based path planning algorithm for autonomous unmanned aerial vehicles (extended abstract) ∗, unmanned aerial vehicle path planning based on a* algorithm and its variants in 3d environment, 42 references, 3d smooth path planning for a uav in cluttered natural environments.

  • Highly Influential

3-D path planning for the navigation of unmanned aerial vehicles by using evolutionary algorithms

3d path planning in a threat environment, path planning in complex 3d environments using a probabilistic roadmap method.

  • 12 Excerpts

Path Planning Strategies for UAVS in 3D Environments

Path planning of unmanned aerial vehicles using b-splines and particle swarm optimization, 3d off-line path planning for aerial vehicle using distance transform technique, generating approximative minimum length paths in 3d for uavs, 3d path planning and stereo-based obstacle avoidance for rotorcraft uavs, path planning for autonomous uav via vibrational genetic algorithm, related papers.

Showing 1 through 3 of 0 Related Papers

Thank you for visiting nature.com. You are using a browser version with limited support for CSS. To obtain the best experience, we recommend you use a more up to date browser (or turn off compatibility mode in Internet Explorer). In the meantime, to ensure continued support, we are displaying the site without styles and JavaScript.

  • View all journals
  • Explore content
  • About the journal
  • Publish with us
  • Sign up for alerts
  • Open access
  • Published: 12 January 2024

APPA-3D: an autonomous 3D path planning algorithm for UAVs in unknown complex environments

  • Jintao Wang 1 , 2 ,
  • Zuyi Zhao 1 ,
  • Jiayi Qu 1 &
  • Xingguo Chen 1  

Scientific Reports volume  14 , Article number:  1231 ( 2024 ) Cite this article

2695 Accesses

3 Citations

Metrics details

  • Aerospace engineering
  • Computational science
  • Computer science

Due to their high flexibility, low cost, and ease of handling, Unmanned Aerial Vehicles (UAVs) are often used to perform difficult tasks in complex environments. Stable and reliable path planning capability is the fundamental demand for UAVs to accomplish their flight tasks. Most researches on UAV path planning are carried out under the premise of known environmental information, and it is difficult to safely reach the target position in the face of unknown environment. Thus, an autonomous collision-free path planning algorithm for UAVs in unknown complex environments (APPA-3D) is proposed. An anti-collision control strategy is designed using the UAV collision safety envelope, which relies on the UAV's environmental awareness capability to continuously interact with external environmental information. A dynamic reward function of reinforcement learning combined with the actual flight environment is designed and an optimized reinforcement learning action exploration strategy based on the action selection probability is proposed. Then, an improved RL algorithm is used to simulate the UAV flight process in unknown environment, and the algorithm is trained by interacting with the environment, which finally realizes autonomous collision-free path planning for UAVs. The comparative experimental results in the same environment show that APPA-3D can effectively guide the UAV to plan a safe and collision-free path from the starting point to the target point in an unknown complex 3D environment.

Similar content being viewed by others

a literature review of uav 3d path planning

Autonomous localized path planning algorithm for UAVs based on TD3 strategy

a literature review of uav 3d path planning

Research on obstacle avoidance path planning of UAV in complex environments based on improved Bézier curve

a literature review of uav 3d path planning

A new method for unmanned aerial vehicle path planning in complex environments

Introduction.

Unmanned Aerial Vehicles (UAVs) are widely used in a variety of scenarios due to their abilities of high flexibility, high productivity, ease of maneuverability, and adapting to hazardous environments. The increasing complexity of flight environments requires UAVs to have the ability to interact with highly dynamic and strongly real-time space operating environments, which put forward new demands for UAVs’ autonomy and safety. UAVs detect and determine whether there is a potential conflict in the future period through the sensors so that they can maintain a certain safe distance from the dynamic/static obstacles in the airspace, and thus plan an ideal flight path from the starting point to the target point and avoid conflicts.

Unlike civil aircraft, UAVs usually perform tasks in lower airspace. There are many static obstacles in lower airspace such as buildings, trees, and dynamic aircraft. Flight conflict is a state when the distance between two aircraft in the direction of horizontal, longitudinal, or vertical is less than a specific interval resulting in the aircraft being at risk 1 . UAVs are required to have autonomous environment sensing, collision threat estimation, avoidance path planning, and maneuver control. These abilities are referred to as Sense And Avoid (SAA). Airspace environment sensing in UAV SAA refers to the detection and acquisition of various static/moving, cooperative/non-cooperative targets in the flying space, based on the onboard sensors or data links carried by the UAV, and evaluating the environmental situation and the degree of collision threat 2 . As shown in Fig.  1 , SAA is an important safety guarantee for future UAV airspace integration applications and is also an important sign of autonomy and intelligence of UAVs 3 .

figure 1

Schematic diagram of UAV perception and avoidance.

For UAVs, the ability of SAA is extremely important. The ability of path planning in the avoidance function of UAVs is an important foundation for the basis for them to complete the flight task. Complex flight environments put forward higher demands for path planning algorithms of UAVs, thus the research in autonomous obstacle avoidance path planning algorithms for UAVs is necessary.

It has to find the optimal flight path from the initial location to the target location under the constraints of environmental factors such as terrain, weather, threats, and flight performance of autonomous path planning for UAVs. Significantly, the optimal path does not always mean the shortest path or a straight line between two locations; instead, the UAV aims to find a safe path under limited power and flight task. There are a lot of UAV path planning algorithms, such as the Voronoi diagram algorithm, Rapidly-exploring Random Tree (RRT) algorithm, A* algorithm, etc. However, these algorithms cannot deal with dynamic environments effectively because they require global environmental information to calculate the optimal result. Once the environment changes, the original results will fail. Furthermore, the process of recalculating the optimal results is too slow for real-time operations because of the large number of calculations required. The above algorithms may still be effective if the obstacle is moving slowly. But when moving faster, the movement of the surrounding vehicles may cannot be predicted thus result in a collision. These shortcomings limit the application of the above algorithms to UAVs in real, dynamic environments.

To address these shortcomings, reinforcement learning algorithms are applied to the path planning process. Reinforcement learning (RL) is a branch of machine learning. UAVs can learn through continuous interaction with the environment, using training and learning to master the environment gradually, and optimize the state-behavior continuously to obtain the optimal strategy through the feedback (rewards) given by the environment, which is closer to the human learning process.

Compared with traditional algorithms, RL performs better when the environment is unknown and dynamic. Moreover, the inference speed and generalization of RL have advantages in real-time decision-making tasks. Therefore, the path planning algorithm based on RL has certain advantages in solving the UAV path planning problem in unknown and dynamic environments.

This paper considers the real-time and location limitation characteristics of path planning and refers to the existing research on UAV path planning problems and collision avoidance strategies for various stationary/motion threats. An autonomous collision-free path planning algorithm for UAVs in unknown complex 3D environments (APPA-3D) is proposed. Thus, UAVs can perform tasks with APPA-3D more safely and efficiently in complex flight environments. Firstly, the UAV spherical safety envelope is designed to research the anti-collision avoidance strategy, which will be used as an action plan for UAVs to realize dynamic obstacle avoidance. Secondly, we assume that the environment model when path planning is unknown, so the UAV needs to have the ability to learn and adjust flight state intelligently according to its surroundings. In this paper, the traditional model-free RL algorithm is improved to reduce the complexity of the algorithm and adapt to the demands of UAV path planning in an unknown complex 3D environment. It takes into account the search efficiency while guaranteeing the optimal search path.

Compared with the existing research, the innovative work of this paper mainly manifests in the following several aspects:

Based on the UAV environment sensing capability, a collision safety envelope is designed, and the anti-collision control strategy is studied concerning the Near Mid Air Collision (NMAC) rules for civil airliners and the International Regulations for Preventing Collisions at Sea (COLREGS). It provides a theoretical basis for UAVs to carry out collision detection and avoidance schemes, which can detect and avoid dynamic threats effectively in the flight environment.

To address the difficulty of convergence of traditional algorithms in solving 3D path planning. The artificial potential field method (APF) is used to optimize the mechanism of reward function generation in RL. The optimized algorithm can output the dynamic reward function by combining the actual flight environment information. Thus, the problems of path planning convergence difficulty, unreachable target point and model stop learning in high dimensional space caused by sparse reward function are solved.

Aiming at the "exploration-exploitation dilemma" of RL in the path planning process of UAVs, an RL action exploration strategy based on action selection probability is proposed. The strategy dynamically adjusts the action selection strategy by combining the size of the value function in different states, thus solving the RL exploration-exploitation problem and improving the efficiency of path search.

The rest of the paper is organized as follows: Section " Related research on UAV path planning " introduces the research status of UAV path planning; an anti-collision control strategy for UAVs is designed in Section " UAV anti-collision control strategy "; an Autonomous collision-free path planning algorithm is proposed in Section " Design of autonomous collision-free path planning algorithm for UAVs "; simulation experiment design and result analysis are presented in Section " Experiment and results "; the paper is summarized in Section " Conclusion ".

Related research on UAV path planning

Autonomous mobile robots (AMRs) has attracted more and more attention due to their practicality and potential uses in the modern world 4 . AMRs is widely used in different fields, such as agricultural production 5 , 6 , unmanned underwater vehicles (AUVs) 7 , 8 , automated guided vehicles (AGVs) 9 , autonomous cleaning robots 10 , industrial robots 11 , 12 , etc. The similarity of the above studies is that they are all need 3D path planning algorithms. Path planning is one of the most important tasks in AMR navigation since it demands the robot to identify the best route based on desired performance criteria such as safety margin, shortest time, and energy consumption. As an important part of AMRs, with the popularization of consumer-grade UAVs, the research on path planning of UAVs has become a hot topic.

UAV path planning refers to the formulation of the optimal flight path from the initial location to the target location, considering environmental factors such as terrain, meteorology, threats, and their flight performance constraints The aim is to improve the reliability and safety of UAVs while ensuring the efficiency of their task execution.

A lot of research has been done on the UAV path planning problem. Sampling-based path planning algorithms are widely used in UAV path planning due to their simplicity, intuitiveness, and ease of implementation. A simple sampling-based path planning algorithm is the Voronoi diagram algorithm 13 . The Voronoi diagram algorithm transforms the complex problem of searching for a trajectory in a spatial region into a simple search problem with a weighted diagram. However, the Voronoi diagram algorithm is only suitable for solving 2D path planning problems. 2D path planning divides the flight environment into passable and impassable areas through "rasterization" processing, and then route planning is performed on the processed map. The algorithm is easy to implement and is more intuitive and feasible, but it is difficult to consider terrain following, terrain avoidance, and threat avoidance simultaneously. Therefore, it is necessary to consider the real sense of 3D route planning with real-time and effective requirements to solve the UAV path planning problem in real scenarios. Another intuitive algorithm is the Rapidly exploring Random Tree (RRT) 14 . RRT can quickly and efficiently search in the smallest possible space, avoiding the need to model the space, and can effectively solve motion planning problems with high-dimensional spaces and complex constraints. However, it is less repeatable and the planned paths are often far from the shortest path.

In node-based path planning algorithms, Dijkstra's algorithm searches for the shortest path by cyclic traversal 15 , However, as the complexity of the flight map increases and the number of nodes increases, Dijkstra's algorithm suffers from too low execution efficiency. Reference 16 designed the solution model of the "Dijkstra -based route planning method", which simplifies the search path, reduces the calculation amount, and improves the execution efficiency through the optimization of correction strategies, correction schemes, and O-D Adjacency matrix processing methods, thereby improving the traditional Dijkstra algorithm. The A* algorithm is a classical and commonly used heuristic search algorithm 17 . The A* algorithm guides the search through heuristic information to achieve the purpose of reducing the search range and improving the computational speed and can obtain real-time feasible paths. The A* algorithm is well-established in the field of path search in 2D environments 18 . If it is directly applied to a 3D environment, the problem of exponential rise in computing data and increase in computing time, which leads to slow search efficiency, needs to be improved. Reference 19 proposes a model-constrained A * -based three-dimensional trajectory planning for unmanned aerial vehicles. By optimizing the cost function of the traditional A * and selecting extension nodes by controlling the value of the coefficient, the search efficiency of the algorithm is improved. Reference 20 proposes a model-constrained A * -based three-dimensional trajectory planning for unmanned aerial vehicles. By optimizing the cost function of the traditional A * and selecting extension nodes by controlling the value of the coefficient, the search efficiency of the is improved.

Computational intelligence (CI) algorithms can provide solutions to NP-hard problems with many variables. CI algorithms are a group of nature-inspired methods, which have been raised as a solution for these problems. They can address complex real-world scenarios that algorithms. Genetic Algorithm (GA) 21 is an adaptive global optimization probabilistic search algorithm developed by simulating the genetic and evolutionary processes of organisms in the natural environment. However, the GA algorithm is time-consuming and generally not suitable for real-time planning. Reference 22 proposes an improved adaptive GA that adaptively adjusts the probabilities of crossover and genetic operators in a nonlinear manner, enabling the generation of more optimal individuals during the evolution process and obtaining the global optimal solution. Simulation results show that the improved adaptive GA enhances the local search capability of the genetic algorithm, improves the planning efficiency, and can accomplish the UAV path planning task. Particle Swarm Optimization (PSO) 23 is an evolutionary computational method based on group intelligence. The biggest advantage of PSO is its simplicity, fast operation speed, and short convergence time. However, in the face of high-dimensional complex problems, PSOs often encounter the drawbacks of premature convergence and poor convergence performance, which cannot guarantee convergence to the optimal point. In recent years, the grey wolf optimization (GWO) algorithm has been widely used in various fields 24 . The while optimizer (WOA) 25 is a GWO-based method because of the success of GWO. Reference 26 proposes a parallel PSO and enhanced sparrow search algorithm (ESSA) for unmanned aerial vehicle path planning. In the ESSA, the random jump of the producer’s position is strengthened to guarantee the global search ability. Ni and Wu et al. 27 proposes an improved dynamic bioinspired neural network (BINN) to solve the AUV real-time path planning problem. A virtual target is proposed in the path planning method to ensure that the AUV can move to the real target effectively and avoid big-size obstacles automatically. Furthermore, a target attractor concept is introduced to improve the computing efficiency of neural activities. Ni and Yang 28 studied the heterogeneous AUV cooperative hunting problem and proposed a novel spinal neural system-based approach. The presented algorithms not only accomplishes the search task but also maintains a stable formation without obstacle collisions. These methods provide some new ideas for the study of UAV path planning in this paper.

Real-time and autonomy in complex flight environments are important indicators for measuring different path-planning algorithms. In the above algorithms, the sampling-based path planning algorithms reduce the traversal search space by sampling, sacrificing the optimality of paths in exchange for a shorter computation time. As the size of the environment increases, the number of operation iterations increases dramatically, making it difficult to achieve simultaneous optimization accuracy and optimal paths in 3D complex environments. Node-based path planning algorithms can obtain the optimal path between the start and endpoints. However, as the environment expands, the dimensionality increases and the number of search nodes increases, the computational size of these algorithms will increase dramatically. Intelligent biomimetic algorithms optimize paths in a mutation-like manner, which can better handle unstructured constraints in complex scenarios. However, its variational solving process requires a long iteration period and cannot be adapted to path planning in dynamic environments 29 .

In response to the limitations of the traditional algorithms mentioned above, a new feasible solution is to update the distance information between the UAVs and the obstacles and target points in real-time and feed it back to the UAV, as well as to make real-time adjustments to its flight status and maneuvers 30 . Reinforcement learning (RL)is a branch of machine learning. The UAVs and the flight environment are modeled using Markov Decision Process (MDP), then the UAV chooses the optimal action to maximize the cumulative reward 31 . UAVs can learn through continuous interaction with the environment, using training and learning to help UAVs gradually master the environment, and continuously optimize the state-behavior to obtain the optimal strategy through the feedback (rewards) given by the environment, which is closer to the human learning process.

In the face of the problem that the environment model is unknown and the transfer probability and value function are difficult to determine, the RL algorithm of interactive learning with the environment to obtain the optimal strategy needs to be a model-free RL algorithm. The Q-Learning (QL) algorithm is one of the most commonly used model-free RL algorithms and has been widely applied to solve path-planning problems. Reference 32 proposes a Dynamic Fast Q-Learning (DFQL) algorithm to solve the path planning problem of USV in partially known marine environments, DFQL algorithm combines Q-Learning with an Artificial Potential Field (APF) to initialize the Q-table and provides USV with a priori knowledge from the environment. Reference 33 introduces an Improved Q-Learning (IQL) with three modifications. First, add a distance metric to QL to guide the agent toward the target. Second, modify the Q function of QL to overcome dead ends more effectively. Finally, introduce the concept of virtual goal in QL to bypass the dead end. Reference 34 proposed a multi-strategy Cuckoo search based on RL. Reference 35 uses potential field information to simply initialize the Q-value table, giving it certain basic guidance for the target point. Reference 36 proposes a QL algorithm based on neural networks, which uses Radial Basis Function (RBF) networks to approximate the action value function of the QL algorithm.

All in all, RL takes rewards from exploring the environment as training data by imitating the learning process of human beings and trains itself without requiring preset training data. The path planning algorithm of UAV based on RL senses the state information of obstacles in the environment continuously and inputs the information into the algorithm, The optimal collision-free path can be obtained by adjusting the flight state of the UAV through RL, which can solve the problems of poor real-time and long planning time of traditional trajectory planning.

However, in practice, due to the complexity of the flight environment, the traditional RL algorithms do not run well in complex scenarios. More concretely, the memory size of a Q-table increases exponentially as the dimensionality of the state space or action space associated with the environment increases 37 ; The slow convergence caused by dimension explosion will lead to disastrous consequences in path planning, thus limiting the performance of RL in practice; The sparse reward function of the traditional RL algorithm will lead to algorithm convergence difficulties, resulting in the model stops learning and cannot improve; The algorithm faces the "exploration–exploitation dilemma" because it needs to consider both exploration and exploitation in action selection 38 . Therefore, the RL algorithm needs to be improved and optimized before it is used to solve the UAV path planning problem.

UAV anti-collision control strategy

Uav spherical safety envelope.

UAVs are unable to obtain complete priori information about the environment during the flight, and can only obtain the information within a certain range centered on themselves through various onboard sensors such as Light Detection And Ranging (LiDAR), and vision sensors. The maximum distance that the sensors of a UAV can detect is defined as \({D}_{max}\) . This paper constructs a spherical safety envelope for UAVs The spherical security envelope is centered at the centroid position of the UAV, which is the demarcation of the threat that the UAV can avoid. It can be used to calculate the action reward of the UAV during RL, and act as an event-triggered mechanism for mandatory UAV anti-collision avoidance strategies. As is shown in Fig.  2 , the thresholds of the safety zone named SZ) is \({D}_{max}\) ; the thresholds of the collision avoidance zone (named CZ) and the mandatory collision avoidance zone (named MZ) are represented by \({D}_{cz}\) and \({D}_{mz}\) , respectively. When the obstacle is in SZ, there is no collision risk between the UAV and the obstacles; when the obstacle is in CZ, the UAV needs to conduct a collision warning and be aware that the obstacle may enter the MZ; when the obstacle is in MZ, the anti-collision avoidance strategy will be triggered to ensure safety.

figure 2

UAV spherical safety envelope profile.

UAV anti-collision avoidance strategies

Before applying APPA-3D to solve the UAV path planning problem, an anti-collision avoidance strategy should be designed. The purpose is to adjust the UAV's flight status such as direction or speed in response to dynamic obstacles (such as other vehicles in the airspace, birds, etc.) to achieve obstacle avoidance. The design of the anti-collision avoidance strategy refers to the method of setting up collision zones in (NMAC) and (COLREGS).

When a dynamic obstacle enters a UAV's MZ, a collision avoidance strategy will be triggered to reduce the risk of collision until the distance between the UAV and the obstacle is greater than \({D}_{mz}\) . According to the rules of NMAC, we divide the possible conflict scenarios into flight path opposing conflict、pursuit conflict, and cross conflict. The relative position of the UAV to the dynamic obstacle is shown in Fig.  3 .

figure 3

The relative position of the UAV and the dynamic obstacle.

In Fig.  3 , when the flight path of the dynamic obstacle is in the same straight line as the UAV, the two are about to have an opposing conflict or pursuit conflict, and their relative positions are schematically shown in Fig.  3 A,B. The vertical direction vector \({f}_{1}\) is added to the direction vector \(f\) of the connection between the UAV and the obstacle. The UAV flies along the direction of merging vector \(F\) of vectors \(f\) and \({f}_{1}\) until it avoids or overtakes an obstacle.

When the flight path of the dynamic obstacle is in the same straight line as the UAV, the two flight paths cross and conflict, and their relative positions are shown in Fig.  3 C. Vector \(F\) is the combined vector direction of vector \(f\) and vector \({f}_{1}\) . Vector \({f}_{1}\) is opposite to the direction of obstacle movement \(v\) . The UAV flies along the merging vector \(F\) to avoid the obstacle.

Based on the different collision scenarios generated by the relative positions of the UAV and dynamic obstacles, four corresponding anti-collision avoidance strategies are designed, as shown in Fig.  4 .

figure 4

Schematic of UAV anti-collision avoidance strategies.

In Fig.  4 A, there is a risk of opposing conflict between the dynamic obstacle and the UAV. Similar to the method shown in Fig.  3 A, the UAV will fly along the merging vector \(\overrightarrow{F}\) , to avoid obstacles. The flight paths of the UAV and the dynamic obstacle are shown in Fig.  4 A.

In Fig.  4 B,C, there is a risk of cross-conflict between dynamic obstacles and UAVs. Similar to the method shown in Fig.  3 C, the UAV will fly along the merging vector direction \(\overrightarrow{F}\) and pass behind the moving direction of the dynamic obstacle, thus the UAV can avoid the dynamic obstacle successfully with the shortest avoidance path. The flight paths of the UAV and the dynamic obstacle are shown in Fig.  4 B,C.

In Fig.  4 D, dynamic obstacles are in the UAV's path of travel and moving at a speed less than the UAV. There is a risk of pursuit and conflict between the dynamic obstacles and the UAV. Similar to the method shown in Fig.  3 B, the UAV will fly along the merging vector direction \(\overrightarrow{F}\) to complete the overtaking of the dynamic obstacle. The flight paths of the UAV and the dynamic obstacle are shown in Fig.  4 D.

Design of autonomous collision-free path planning algorithm for UAVs

The basic framework of RL is shown in Fig.  5 .

figure 5

Framework of RL.

Essentially, RL is the use of the Agent to interact with the environment constantly, and obtain the optimal value function \({q}^{*}\) for state \(S\) , through the feedback (reward) given by the environment to continuously optimize the state-action to obtain the optimal strategy \({\pi }^{*}\) . The mathematical formula is expressed as Eq. ( 1 ) and Eq. ( 2 ):

Thus, the problem of finding the optimal strategy translates into finding the largest of the action state value functions produced under all strategies.

RL-based path planning algorithm allows UAVs to learn and gain rewards through constant interaction with the surroundings through trial and error with little knowledge of the environment and is, therefore, suitable for UAV ‘s path planning under complex conditions. The advantage of an RL-based path planning algorithm is that it can realize path planning in the absence of a priori information about the environment and is highly searchable, but it suffers from the problem of reward sparsity 39 , which can cause convergence difficulties in high-dimensional spaces.

APPA-3D first combines the principle of the APF method and designs an adaptive reward function. Dynamic rewards are generated in real time by judging the effectiveness of UAV movements with environmental information. Secondly, to address the "exploration-utilization dilemma" of RL in the UAV path planning process, an RL action exploration strategy based on action selection probability is proposed. The strategy dynamically adjusts the action selection strategy by combining the size of the value function in different states, to solve the exploration-utilization problem of RL and improve the efficiency of path search.

Virtual force generation for UAV based on APF

The basic idea of path planning with the APF 40 is to design the motion of an object in its surroundings as the motion of an abstract artificial gravitational field. The target point has "gravitational force" on the object, while the obstacle has "repulsive force" on the object, and the motion of the object is controlled by the net force.

The current position of the UAV is denoted as \(X=\left(x,y,z\right)\) ; the position of the target point is denoted as \({X}_{g}=\left({x}_{g},{y}_{g},{z}_{g}\right)\) ; and the position of the start point is denoted as \({X}_{0}=\left({x}_{0},{y}_{0},{z}_{0}\right)\) . The gravitational potential field function is defined as Eq. ( 3 ):

In Eq. ( 3 ), \(k\) > 0 is the gravitational potential field function coefficient constant. The distance from the UAV to the target point is \({D}_{goal}=\Vert X-{X}_{g}\Vert\) , and the gravitational force is the negative gradient of the gravitational potential field function, defined as Eq. ( 4 ):

Define the repulsive potential field function as Eq. ( 5 ):

In Eq. ( 5 ), \(m\) > 0 is a repulsive potential field coefficient constant. The position of the obstacle is \({X}_{b}=\left({x}_{b},{y}_{b},{z}_{b}\right)\) . The distance from the UAV to the obstacle is \({D}_{barrier}=\Vert X-{X}_{b}\Vert\) . \({\rho }_{0}\) is the maximum range of influence of the obstacle. Define the repulsive force as Eq. ( 6 ) and Eq. ( 7 ):

Thus the net force \(F\left(X\right)\) on the UAV is shown in Eq. ( 8 )

Design of adaptive reward function

The reward function is used to evaluate the actions of the Agent. In traditional RL algorithms, the Agent can only obtain the positive and negative sparse reward function by reaching the target point or colliding with an obstacle. The model does not receive any feedback until it receives the first reward, which may cause the model to stop learning and fail to improve. This reward function will make the algorithm convergence difficult, and in most states cannot reflect the good or bad of its action choice. he sparse reward function \(R\) is shown in Eq. ( 9 ):

In Eq. ( 9 ), \({s}_{t}=Filure\) means that the UAV collides with an obstacle in state t and receives a negative reward − 1, while \({s}_{t}=Success\) means that the UAV reaches the target point in state t and receives a positive reward + 1. Other states have no reward.

To solve the difficult problem of sparse rewards, in this paper, combined with the artificial potential field algorithm, the gravitational force generated by the target point and the repulsive force generated by the obstacle on the agent are converted into the reward or punishment obtained by the agent after performing the action \({a}_{t}\) in the state \({s}_{t}\) . The optimized reward function is shown in Eq. ( 10 ):

In Eq. ( 10 ), \({R}_{a}\) represents the reward function when the obstacle is within the SZ or when no obstacle is detected. the collision avoidance action reward function is \({R}_{ca}\) , and the mandatory collision avoidance action reward function is \({R}_{mz}\) .

The Euclidean distance between the starting point of the agent and the target is denoted by \({d}_{max}\) , and the Euclidean distance between the current position of the agent and the target is denoted by \({d}_{goal}\) . The formula as Eq. ( 11 ) and Eq. ( 12 ):

The hyperbolic tangent function can map all will any real number to (− 1, 1). The hyperbolic tangent function can be written as Eq. ( 13 ):

As shown in Fig.  6 A, when the obstacle is in the SZ, or no obstacle is detected, the UAV is only affected by the gravitational force \({F}_{att}\) generated by the target point, reward function \({R}_{a}\) is as shown in Eq. ( 14 )

figure 6

Direction of UAV movement when the obstacle in different zones.

In Eq. ( 14 ): \({d}_{goal}^{t}\) denotes the Euclidean distance between the agent position and the target point position at moment \(t\) .

From Eq. ( 14 ), it can be seen that after each state change of the agent, if the distance between the agent and the target point under \(t+1\) decreases compared to \(t\) moments, then \({R}_{a}>0\) , the agent gets a positive reward at this time, and vice versa, it gets a negative reward, which is consistent with the principle of RL.

As shown in Fig.  6 B, when the obstacle is in the CZ, the UAV is affected by the repulsive force \({F}_{rep}\) of the obstacle and the attractive force \({F}_{att}\) of the target point. At this time, the reward function decreases with the increase of the distance between the agent and the obstacle. The reward function \({R}_{ca}\) can be written as Eq. ( 15 ):

where: \({d}_{barrier}^{t}\) denotes the Euclidean distance between the agent position and the obstacle position at moment \(t\) .

From Eq. ( 15 ), it can be seen that the reward function \({R}_{ca}\) when the obstacle is in the CZ consists of two parts, one is the reward generated by the obstacle to the UAV, if the distance between the UAV and the obstacle under the \(t+1\) moment is reduced compared to the \(t\) moment, then the reward generated by the obstacle to the agent is negative, and vice versa is positive. The other is the reward generated by the target point to the UAV, and the principle is the same as Eq. ( 5 ). When the obstacle is in the CZ, the agent accepts the reward function of the obstacle and the target point at the same time, which can solve the defects that the traditional APF method is easy to fall into the local minima and oscillate in the narrow passage, to guide the UAV out of the trap area and move toward the target point smoothly.

As shown in Fig.  6 C, when the obstacle is within the MZ, the risk of UAV collision with the obstacle is high. To prevent conflicts, A collision avoidance strategy \({A}_{C}\) is mandatory for the UAV, The reward function \({R}_{ca}\) can be written as Eq. ( 16 ):

The adaptive reward function is consistent with RL. By converting the reward values of each action-state into continuous value between (− 1, 1), the problem of sparse reward functions is solved. The adaptive reward function solves the problem that traditional reward functions can only earn positive or negative rewards by reaching a target point or colliding with an obstacle, and other actions do not receive any positive or negative feedback. The adaptive reward functions are generated by determining the validity of the executed action and environmental information. Compared to the traditional sparse reward function, the adaptive reward function proposed in this paper combines the good performance of APF to make the reward accumulation process smoother, and can also reflect the relationship between the current state of the UAV and the target state.

Action exploration strategy optimization of reinforcement learning

In the process of constant interaction with the environment, the Agent keeps exploring different states and obtains feedback on different actions. Exploration helps the Agent to obtain feedback through continuous experimentation, and Exploitation is where the Agent refers to the use of existing feedback to choose the best action.

On the one hand, RL obtains more information by exploring more of the unknown action space to search for the global optimal solution, but a large amount of exploration reduces the performance of the algorithm and leads to the phenomenon of non-convergence of the algorithm. On the other hand, too much exploitation will fail to choose the optimal behavior because of the unknown knowledge of the environment. Therefore how to balance exploration and utilization is an important issue for the Agent to continuously learn in interaction.

There is a contradiction between "exploration" and "exploitation ", as the number of attempts is limited, and strengthening one naturally weakens the other. Excessive exploration of the unknown action space can degrade the performance of the algorithm and lead to non-convergence of the algorithm while obtaining more information to search for a globally optimal solution. In contrast, too much exploitation prevents the selection of optimal behavior because of the unknown knowledge of the environment. This is the Exploration—Exploitation dilemma faced by RL. To maximize the accumulation of rewards, a better compromise between exploration and exploitation must be reached.

Action exploration strategies can be categorized into directed and undirected exploration methods. The directed exploration approach reduces the blindness in the pre-exploration phase of action exploration and thus improves the exploration efficiency by introducing a priori knowledge into the action exploration strategy. directed exploration methods, on the other hand, make a compromise between exploration and exploitation by setting parameters, and the usual approaches are the \(\epsilon -greedy\) strategy and the Softmax distribution strategy.

The \(\epsilon -greedy\) strategy usually sets a parameter \(\epsilon\) to select the current optimal action with a probability of \(\left(1-\epsilon \right)\) , and randomly selects among all the actions with a probability of \(\epsilon\) , which is represented by Eq. ( 17 ):

In Eq. ( 17 ), When \(\varepsilon\) is 0, the \(\epsilon -greedy\) strategy is transformed into a greedy strategy, and the degree of exploration gradually increases as \(\varepsilon\) is gradually increased from 0 to 1; when \(\varepsilon\) is 1, the \(\epsilon -greedy\) strategy is transformed into a randomized choice action. Although the \(\epsilon -greedy\) strategy solves the problem between exploration and exploitation to a certain extent, the problem of exploration and exploitation still exists because the parameter \(\epsilon\) is fixed and there are problems such as the difficulty of setting the parameter \(\epsilon\) , and the lack of differentiation between non-optimal actions.

The Softmax distribution strategy makes a tradeoff between exploration and exploitation based on the average reward of currently known actions. If the average rewards of the maneuvers are comparable, the probability of selecting each maneuver is also comparable; if the average reward of some maneuvers is significantly higher than that of other maneuvers, the probability of their selection is also significantly higher.

The action assignment for the Softmax distribution strategy is based on the Boltzmann distribution, which is represented by Eq. ( 18 ):

In Eq. ( 18 ), \(Q\left(s,{a}_{j}\right)\) records the average reward of the current action; \(\tau >0\) is called “temperature”, The smaller of \(\tau\) , the higher the probability of selecting actions with higher average rewards. When τ tends to 0, Softmax tends to " exploitation only", when τ tends to infinity. Softmax tends to "exploration only".

Both \(\epsilon -greedy\) strategy and the Softmax distribution strategy are iterated in such a way that the action with the largest action-value function has the largest probability of selection. Based on this, this paper proposes a new action selection strategy, the new strategy solves the balance problem between exploration and exploitation by introducing the concept of "action selection probability " and making action preference selection accordingly.

Action selection probability represents the probability value that an Agent chooses to perform an action in a given state. As shown in Eq. ( 19 ), the initial value of the action selection probability for a state-action is the inverse of the size of the action set for that state:

In Eq. ( 19 ), \(card\left({A}_{s}\right)\) denotes the number of actions in the action set \({A}_{s}\) in state \(s\) .

The action selection probability is dynamically adjusted as the size of the value function of the action changes. During the RL process, Agent in state \(s\) , selects action \(A\) based on the size of the action selection probability value, and after executing the action, Agent obtains the reward \(R\) and enters state \({S}^{\mathrm{^{\prime}}}\) and selects the action \({A}^{\mathrm{^{\prime}}}\) with the largest value function to update the value function. Subsequently, the value function for each action in state \(s\) is is divided into two parts according to the size of the value: The largest value function is the first part; the rest is the second part. Reduce the probability values of each action in the second part by half and add them evenly to the first part.

The Agent updates the action selection probability after completing an action, according to the size of the state action value function. The update rule is as Eq. ( 20 ):

In Eq. ( 20 ): \(m\) is the rate of change, which represents the rate of change of the action probability; \({A}^{*}\left(s\right)\) is the set of actions with the largest value function, \({a}_{i}\) is the action of the set \({A}^{*}\left(s\right)\) , and \({a}_{j}\) is the action with non-maximum value function.

In the initial phase of the algorithm, each action has the same probability of being selected by the Agent, i.e., the action selection probabilities \(P\left(a|s\right)\) are equal, at which point the Agent will randomly select the action.

After an Agent completes the exploration of an action, if this exploration results in \(R<0\) , the action selection probability for that action is halved, at which point the probability of other actions being selected increases, so that in the early stages of the exploration the Agent will be more inclined to select actions that have not been performed. If \(R>0\) for this exploration, it indicates that this exploration is a beneficial exploration, which will increase the action selection probability of this action, when the probability of other actions being selected decreases, and therefore the Agent tends to select this action more often; However, there is still a probability of exploration for other actions, thus reducing the risk of action exploration falling into a local optimum.

The pseudo-code for APPA-3D is shown in Algorithm 1:

figure a

Experiment and results

To verify the feasibility of an autonomous path planning algorithm in complex 3D environments (APPA-3D) for UAVs, this paper selects real environment maps to conduct simulation experiments. The UAV's range of action is limited to the map, and if the UAV moves outside the range of the map or above the low altitude limit altitude, it is determined that a collision has occurred. The starting point for UAV path planning is represented by a black dot, and the target point is represented by a red dot. The maximum flight altitude is 1 km above the peak line, and the no-fly zone is indicated by a green cylinder. The UAV needs to avoid mountains and no-fly zones to fly from the starting point to the target point.

UAV anti-collision avoidance strategies experiments

The anti-collision avoidance strategies experiments were designed to verify whether APPA-3D can achieve anti-collision avoidance strategies while implementing path planning. Figures  7 , 8 and 9 are simulation experimental diagrams of anti-collision avoidance strategies for UAVs.

figure 7

Opposing Conflict Avoidance Simulation.

figure 8

Cross-conflict avoidance simulation.

figure 9

Pursuit conflict avoidance simulation.

As shown in Fig.  7 , in the opposing conflict avoidance simulation, the intrusion direction of the dynamic obstacle is set to be directly opposite the movement direction of the UAV. When a dynamic obstacle is detected, the UAV chooses to turn right to avoid the dynamic obstacle according to the anti-collision avoidance strategy. The reward function is recalculated after finishing the anti-collision avoidance strategy and guiding the UAV to continue flying toward the target point.

As shown in Fig.  8 , in the cross-conflict avoidance simulation, dynamic obstacles invade from the left and right sides of the UAV's flight direction. According to the anti-collision avoidance strategy, when the UAV detects a dynamic obstacle and chooses to pass behind the moving direction of the dynamic obstacle, it can ensure that the UAV and the dynamic obstacle are avoided successfully and the avoidance path is the shortest. The reward function is recalculated after finishing the anti-collision avoidance strategy and guiding the UAV to continue flying toward the target point.

As shown in Fig.  9 , in the pursuit conflict avoidance simulation, the flight direction of the dynamic obstacle is the same as the UAV flight direction. Referring to the anti-collision avoidance strategy, when the UAV detects a dynamic obstacle, the UAV chooses to complete the overtake from the right side of the dynamic obstacle's direction of motion, which ensures that the UAV can successfully overtake the dynamic obstacle with the shortest overtake avoidance path; The reward function is recalculated after finishing anti-collision avoidance strategy and guiding the UAV to continue flying towards the target point.

Multi-obstacle path planning and collision avoidance verification

To verify the performance of the APPA-3D, this paper randomly generates 3, 6, and 10 different moving and static obstacles in the same simulation environment and conducts three sets of randomized experiments each. The 3D view of APPA-3D is exhibited in this paper, as shown in Fig.  10 .

figure 10

3D view of APPA-3D flight path.

The 3D view of the paths planned by APPA-3D shows that the flight paths of the UAVs are feasible in nine different scenarios. The distance between the UAV and the obstacle is well-maintained in complex terrain. This further demonstrates that APPA-3D can help the UAV to plan a path that is both short and safe at the same time.

This paper calculates four parameters: UAV path planning time, planned path length, number of planned path points, and planned path ground projection length in 9 scenarios, the average values of the four parameters are shown in Table 1 .

Comparative experiments

To verify the enhancement effect of the adaptive reward function and the new action selection strategy proposed in this paper, two sets of ablation experiments were conducted firstly before conducting the comparison experiments.

The first set of ablation experiments is to verify the enhancement effect of the new adaptive reward function proposed in this paper, and the experimental results are shown in Fig.  11 :

figure 11

UAV path planning results under sparse reward function and adaptive reward function.

The yellow path in Fig.  11 represents the UAV flight path under the sparse reward function, and the blue path represents the flight path under the adaptive reward function proposed in this paper. Figure  11 clearly shows that the performance of UAV path planning based on sparse reward function is poor in complex 3D environments. This is because under sparse reward function, it can only obtain positive and negative reward when reaching the target point or colliding with obstacles, and other actions will not get any positive or negative feedback. So the UAV is random flight blindly, unable to find the correct flight direction in this way. Compared with the sparse reward function, the adaptive reward function we proposed combines the good performance of APF to make the reward accumulation process smoother and can also reflect the relationship between the current state and the target state of the UAV.

To verify the improvement effect of the new action selection strategy proposed in this paper, the second set of ablation experiments was set up. The experiments were analyzed using the \(\epsilon -greedy\) strategy, Softmax distribution strategy, and the new action selection strategy. All RL algorithms adopt Q-learning algorithm, which excludes the influence of learning algorithm on different exploration strategies.

Tables 2 and 3 show the results of three exploration strategies. To prevent the impact of single data on the experiment, the data in Tables 2 and 3 is the average value obtained after 5 experiments.

The experimental results show that after a period of exploration, three different exploration strategies are able to guide the UAV to the target point. Compared with the other two exploration strategies, the action selection probability we proposed is more advantageous in terms of path planning time and number of path planning points.

To evaluate whether the APPA-3D proposed in this paper has significant advantages over other classical or RL based algorithms, two sets of experiments were utilized to test the ability of the six methods to solve path planning problems under the same conditions. According to the characteristics of algorithms, they can be divided into two categories: classic algorithms (APF, RRT, and A*) and QL-based algorithms (DFQL, IQL, and MEAEO-RL). It should be noted that, to prevent the impact of single data on the experiment, the data in Table 4 , 5 , 6 and 7 is the average value obtained after 5 experiments.

The experimental results of the first group are displayed in Fig.  12 and Tables 4 and 5 :

figure 12

Path planning comparison of A*, RRT, APF and APPA-3D.

It can be seen from Fig.  12 that the three classic algorithms perform better than APPA-3D algorithm in the front part of the path. However, the performance of classic algorithms is poor in the latter part of the path, which is caused by their algorithm characteristics. Because sampling-based and search-based characteristics of algorithms respectively, it is hard to generate smooth and optimal paths with RRT and A*. Although the path planning time of A* is short, the UAV collided with obstacles unfortunately. The reason for the poor effect of APF is that the obstacle surrounds the destination, and the repulsive force field of the obstacle directly acts on the agent, making it unable to approach the obstacle. The agent can only move in the direction where the gravitational force is greater than the repulsive force.

The results of the second group of experiments are displayed in Fig.  13 . It is worth mentioning that DFQL, IQL, MEAEO-R, and APPA-3D are all optimized based on traditional RL algorithms. The simulation results are shown in Fig.  13 , Table 6 and Table 7 .

figure 13

Path planning comparison of DFQL, IQL, MEAEO-RL and APPA-3D.

Experimental results clearly show that APPA-3D can reach the destination with the shortest distance and time. In the initial phase of path planning, APPA-3D is not very different from other algorithms, and all four algorithms can help the UAV plan a relatively high-quality flight path quickly. While in the middle and later stages of path planning, the differences between APPA-3D and the other three compared algorithms can be seen clearly, especially when facing multi-dynamic obstacles. Because RL algorithm assigns a probability to each possible action and selects the action based on these probabilities, path planning algorithms based on RL often fall into the dilemma of exploration–exploitation when facing complex environments.

To solve this problem, the APPA-3D algorithm proposes a new action selection strategy. This strategy solves the balance problem between exploration and exploitation by introducing the concept of action selection probability and making action preference selection accordingly.

The Fig.  14 presents the loss function used to observe the convergence behavior over iterations of all algorithms. It can be seen that after about 130 iterations, the loss function begins to stabilize. The rapid convergence of value loss also shows that the APPA-3D is more accurate, which is a good performance and means that the agents won’t fall into a local optimum. The algorithms compared requires more iteration to complete convergence. This is because they use \(\epsilon -greedy\) strategy or Softmax distribution strategy as an action exploration strategy of reinforcement learning. And their performance is consistent with the results of the second set of ablation experiments.

figure 14

The loss function of DFQL, IQL, MEAEO-RL and APPA-3D.

In conclusion, APPA-3D is far better than the compared algorithms in the 3D UAV path planning optimization problem. This is because APPA-3D dynamically adjusts the action selection strategy by combining the size of the value function in different states, thus solving the problem of exploration-utilization of RL and improving the efficiency of path search.

The path planning problem in unknown environments is the focus of UAV task planning research and the key to achieving autonomous flight. Therefore, UAVs need to have the ability to autonomous path planning and avoid potential obstacles. In this paper, an autonomous collision-free path planning algorithm for unknown complex 3D environments is proposed. Firstly, based on the environment sensing capability, a UAV collision safety envelope is designed, and the anti-collision control strategy is investigated, which can effectively deal with the collision problem triggered by dynamic obstacles in the flight environment. Secondly, this paper optimizes the traditional RL algorithm. On the one hand, the reward function for RL is optimized by transforming the relationship between the current state of the UAV and the task into a suitable dynamic reward function. The presence of a dynamic reward function allows the UAV to fly toward the target point without getting too close to the obstacles. On the other hand, an RL action exploration strategy based on action selection probability is proposed. The strategy dynamically adjusts the action selection strategy by combining the size of the value function in different states, thus solving the RL exploration-utilization problem and improving the efficiency of path search. To verify the effectiveness of the designed APPA-3D algorithm in the dynamic collision avoidance model, three typical collision experiments were set up, including flight path opposing collision, pursuit collision, and cross collision. The experimental results verify that the APPA-3D can effectively avoid safety threats that may be caused by dynamic obstacles in complex environments according to the designed anti-collision control strategy. Meanwhile, the results of the algorithm testing experiments in nine different scenarios verified that the algorithm still performs well in the face of random and complex flight environments.

APPA-3D demonstrates better performance in path planning performance comparison tests with other classical and novel optimized RL algorithms. The advantages in path planning length and convergence curves again show that APPA-3D can effectively help UAVs solve the path planning problem.

Data availability

The datasets used and analysed during the current study will be available from the corresponding author on reasonable request.

Lanicci, J. et al. General aviation weather encounter case studies. Case Stud. 56 , 1233 (2012).

Google Scholar  

Lyu, Y. et al. UAV sense and avoidance: concepts, technologies, and systems (in Chinese). Sci. Sin. Inform. 49 , 520–537 (2019).

Article   Google Scholar  

Li, Y. J., Quan, P., Feng, Y., et al. Multi-source information fusion for sense and avoidance of UAV[C]. Control Conf (IEEE, 2010).

Loganathan, A. & Ahmad, N. S. A systematic review on recent advances in autonomous mobile robot navigation. Eng. Sci. Technol. Int. J. 40 , 101343 (2023).

Fasiolo, D. T., Scalera, L., Maset, E. & Gasparetto, A. Towards autonomous mapping in agriculture: A review of supportive technologies for ground robotics. Robot. Auto. Syst. 25 , 104514 (2023).

Hameed, I. A., la Cour-Harbo, A. & Osen, O. L. Side-to-side 3D coverage path planning approach for agricultural robots to minimize skip/overlap areas between swaths. Robot. Auton. Syst. 76 , 36–45 (2016).

Yan, Z., Yan, J., Wu, Y., Cai, S. & Wang, H. A novel reinforcement learning based tuna swarm optimization algorithm for autonomous underwater vehicle path planning. Math. Comput. Simul. 209 , 55–86 (2023).

Article   MathSciNet   Google Scholar  

Hadi, B., Khosravi, A. & Sarhadi, P. Deep reinforcement learning for adaptive path planning and control of an autonomous underwater vehicle. Appl. Ocean Res. 129 , 103326 (2022).

Zhong, M., Yang, Y., Dessouky, Y. & Postolache, O. Multi-AGV scheduling for conflict-free path planning in automated container terminals. Comput. Indust. Eng. 142 , 106371 (2020).

Do, H. et al. Heat conduction combined grid-based optimization method for reconfigurable pavement sweeping robot path planning. Robot. Autonom. Syst. 152 , 104063 (2022).

Wang, X. et al. Adaptive path planning for the gantry welding robot system. J. Manuf. Process. 81 , 386–395 (2022).

Cheng, X. et al. An improved RRT-Connect path planning algorithm of robotic arm for automatic sampling of exhaust emission detection in Industry 4.0. J. Indust. Inf. Integr. 33 , 100436 (2023).

Pehlivanoglu, Y. V. A new vibrational genetic algorithm enhanced with a Voronoi diagram for path planning of autonomous UAV. Aerosp. Sci. Technol. 16 (1), 47–55 (2012).

Guo, J., Xia, W., Xiaoxuan, Hu. & Ma, H. Feedback RRT* algorithm for UAV path planning in a hostile environment. Comput. Ind. Eng. 174 , 108771 (2022).

Wang, H., Mao, W. & Eriksson, L. A three-dimensional dijkstra’s algorithm for multi-objective ship voyage optimization. Ocean Eng. 186 , 106131 (2019).

Li, Y. Q., Liu, Z. Q., Cheng, N. G., Wang, Y. G. & Zhu, C. L. Path Planning of UAV Under Multi-constraint Conditions. Comput. Eng. Appl. 57 (04), 225–230 (2021).

Huang, X. et al. The improved A* obstacle avoidance algorithm for the plant protection UAV with millimeter wave radar and monocular camera data fusion. Rem. Sens. 13 (17), 3364 (2021).

Article   ADS   Google Scholar  

Lu, F. Shortest path algorithms: Taxonomy and advance in research. Act a Geodaet Ica Et Cart Ograph. Sin. 03 : 269–275 (2001).

Shengyin, W., Teng, L. & Zhu, W. Dynamic path planning using anytime repairing sparse A~* algorithm. Syst. Eng. Electr. 40 (12), 2714–2721 (2018).

Zhang, R., Wang, W. & Tian, Z. UAV 3D path planning based on model constrained A* algorithm. Foreign Electr. Meas. Technol. 41 (09), 163–169. https://doi.org/10.19652/j.cnki.femt.2203963 (2022).

Shushan, L. et al. 3D track optimization of UAV ( unmanned aerial vehicles) inspection of transmission tower based on GA-SA. Sci. Technol. Eng. 23 (6), 2438–2446 (2023).

Zhou, Z. & Chen, P. 3D path planning of UAV based on improved adaptive genetic algorithm. J. Project. Rockets Miss. Guid. 2 , 1–7 (2023).

Yang, L. I. U., Zhang, X., Zhang, Y. & Xiangmin, G. Collision free 4D path planning for multiple UAVs based on spatial refined voting mechanism and PSO approach. Chin. J. Aeronaut. 32 (6), 1504–1519 (2019).

Jiang, W., Lyu, Y., Li, Y., Guo, Y. & Zhang, W. UAV path planning and collision avoidance in 3D environments based on POMPD and improved grey wolf optimizer. Aeros. Sci. Technol. 121 , 107314 (2022).

Sanjoy, C., Sushmita, S. & Apu, K. S. SHADE–WOA: A metaheuristic algorithm for global optimization. Appl. Soft Comput. 113 , 107866. https://doi.org/10.1016/j.asoc.2021.107866 (2021).

Wang, Z., Sun, G., Zhou, K. & Zhu, L. A parallel particle swarm optimization and enhanced sparrow search algorithm for unmanned aerial vehicle path planning. Heliyon 9 (4), e14784. https://doi.org/10.1016/j.heliyon.2023.e14784 (2023).

Article   PubMed   PubMed Central   Google Scholar  

Ni, J., Wu, L., Shi, P. & Yang, S. X. A dynamic bioinspired neural network based real-time path planning method for autonomous underwater vehicles. Comput. Intell. Neurosci. 2017 , 9269742. https://doi.org/10.1155/2017/9269742 (2017).

Ni, J. et al. An Improved Spinal Neural System-Based Approach for Heterogeneous AUVs Cooperative Hunting. Int. J. Fuzzy Syst. https://doi.org/10.1007/s40815-017-0395-x (2017).

Yang L, Qi JT, Xiao JZ, et al. A literature review of UAV 3D path planning. Proc of the 11th World Congress on Intelligent Control and Automation . (IEEE, 2015).

Yu, X., Zhou, X. & Zhang, Y. Collision-free trajectory generation and tracking for UAVs using markov decision process in a cluttered environment. J. Intell. Robot. Syst. 93 , 17–32 (2019).

Feinberg, A. Markov decision processes: discrete stochastic dynamic programming (Martin L. Puterman). SIAM Rev. 38 (4), 689–689 (1996).

Hao, B., He, Du. & Yan, Z. A path planning approach for unmanned surface vehicles based on dynamic and fast Q-learning. Ocean Eng. 270 , 113632 (2023).

Low, E. S., Ong, P., Low, C. Y. & Omar, R. Modified Q-learning with distance metric and virtual target on path planning of mobile robot. Exp. Syst. Appl. 199 , 117191 (2022).

Xiaobing, Yu. & Luo, W. Reinforcement learning-based multi-strategy cuckoo search algorithm for 3D UAV path planning. Exp. Syst. Appl. 63 , 119910 (2023).

Gong, M., Xu, H. & Feng, H. Ship local path planning based on improved Q-learning. J Ship Mech 26 (06), 824–833 (2022).

Yuliang, W. & Wuyin, J. Intelligent vehicle path planning based on neural network Q-learning algorithm. Fire Control Comm. Control 44 (02), 46–49 (2019).

Vanhulsel, M., Janssens, D., Wets, G. & Vanhoof, K. Simulation of sequential data: An enhanced reinforcement learning approach. Exp Syst. Appl 36 (4), 45660 (2009).

Zhi-Xiong, X. U. et al. Reward-Based Exploration: Adaptive Control for Deep Reinforcement Learning. IEICE Trans. Inf. Syst. 101 (9), 2409–2412. https://doi.org/10.1587/transinf.2018EDL8011 (2018).

Dann, M., Zambetta, F. & Thangarajah, J. Deriving subgoals autonomously to accelerate learning in sparse reward domains. Proc. AAAI Conf Artif. Intell. 33 (01), 881–889. https://doi.org/10.1609/aaai.v33i01.3301881 (2019).

Khatib O, Real-time obstacle avoidance for manipulators and mobile robots. Proc. 1985 IEEE International Conf. on Robotics and Automation , St. Louis, pp. 500–505 (1985). https://doi.org/10.1109/ROBOT.1985.1087247 .

Download references

Author information

Authors and affiliations.

Civil Aviation College, Shenyang Aerospace University, Shenyang, 110136, China

Jintao Wang, Zuyi Zhao, Jiayi Qu & Xingguo Chen

Henan Shijia Photons Technology Co., Ltd, Hebi, 458030, China

Jintao Wang

You can also search for this author in PubMed   Google Scholar

Contributions

J.W. designed the study and wrote the main manuscript text. Z.Z. experimented and analyzed the results and J.Q. collected the data and analyzed the results. X.C. prepared figures and tables, and all authors reviewed the manuscript.

Corresponding author

Correspondence to Jintao Wang .

Ethics declarations

Competing interests.

The authors declare no competing interests.

Additional information

Publisher's note.

Springer Nature remains neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Rights and permissions

Open Access This article is licensed under a Creative Commons Attribution 4.0 International License, which permits use, sharing, adaptation, distribution and reproduction in any medium or format, as long as you give appropriate credit to the original author(s) and the source, provide a link to the Creative Commons licence, and indicate if changes were made. The images or other third party material in this article are included in the article's Creative Commons licence, unless indicated otherwise in a credit line to the material. If material is not included in the article's Creative Commons licence and your intended use is not permitted by statutory regulation or exceeds the permitted use, you will need to obtain permission directly from the copyright holder. To view a copy of this licence, visit http://creativecommons.org/licenses/by/4.0/ .

Reprints and permissions

About this article

Cite this article.

Wang, J., Zhao, Z., Qu, J. et al. APPA-3D: an autonomous 3D path planning algorithm for UAVs in unknown complex environments. Sci Rep 14 , 1231 (2024). https://doi.org/10.1038/s41598-024-51286-2

Download citation

Received : 15 September 2023

Accepted : 03 January 2024

Published : 12 January 2024

DOI : https://doi.org/10.1038/s41598-024-51286-2

Share this article

Anyone you share the following link with will be able to read this content:

Sorry, a shareable link is not currently available for this article.

Provided by the Springer Nature SharedIt content-sharing initiative

This article is cited by

Trajectory optimization of uav-irs assisted 6g thz network using deep reinforcement learning approach.

  • Amany M. Saleh
  • Shereen S. Omar
  • Mostafa M. Abdelhakam

Scientific Reports (2024)

By submitting a comment you agree to abide by our Terms and Community Guidelines . If you find something abusive or that does not comply with our terms or guidelines please flag it as inappropriate.

Quick links

  • Explore articles by subject
  • Guide to authors
  • Editorial policies

Sign up for the Nature Briefing: AI and Robotics newsletter — what matters in AI and robotics research, free to your inbox weekly.

a literature review of uav 3d path planning

To read this content please select one of the options below:

Please note you do not have access to teaching notes, 3d path planning, routing algorithms and routing protocols for unmanned air vehicles: a review.

Aircraft Engineering and Aerospace Technology

ISSN : 0002-2667

Article publication date: 13 June 2019

Issue publication date: 17 September 2019

This paper aims to present a comprehensive review in major research areas of unmanned air vehicles (UAVs) navigation, i.e. three degree-of-freedom (3D) path planning, routing algorithm and routing protocols. The paper is further aimed to provide a meaningful comparison among these algorithms and methods and also intend to find the best ones for a particular application.

Design/methodology/approach

The major UAV navigation research areas are further classified into different categories based on methods and models. Each category is discussed in detail with updated research work done in that very domain. Performance evaluation criteria are defined separately for each category. Based on these criteria and research challenges, research questions are also proposed in this work and answered in discussion according to the presented literature review.

The research has found that conventional and node-based algorithms are a popular choice for path planning. Similarly, the graph-based methods are preferred for route planning and hybrid routing protocols are proved better in providing performance. The research has also found promising areas for future research directions, i.e. critical link method for UAV path planning and queuing theory as a routing algorithm for large UAV networks.

Originality/value

The proposed work is a first attempt to provide a comprehensive study on all research aspects of UAV navigation. In addition, a comparison of these methods, algorithms and techniques based on standard performance criteria is also presented the very first time.

  • Routing algorithm
  • 3D path planning algorithm
  • Routing protocol

Ben Amarat, S. and Zong, P. (2019), "3D path planning, routing algorithms and routing protocols for unmanned air vehicles: a review", Aircraft Engineering and Aerospace Technology , Vol. 91 No. 9, pp. 1245-1255. https://doi.org/10.1108/AEAT-01-2019-0023

Emerald Publishing Limited

Copyright © 2019, Emerald Publishing Limited

Related articles

All feedback is valuable.

Please share your general feedback

Report an issue or find answers to frequently asked questions

Contact Customer Support

arXiv's Accessibility Forum starts next month!

Help | Advanced Search

Computer Science > Computer Vision and Pattern Recognition

Title: a review on viewpoints and path-planning for uav-based 3d reconstruction.

Abstract: Unmanned aerial vehicles (UAVs) are widely used platforms to carry data capturing sensors for various applications. The reason for this success can be found in many aspects: the high maneuverability of the UAVs, the capability of performing autonomous data acquisition, flying at different heights, and the possibility to reach almost any vantage point. The selection of appropriate viewpoints and planning the optimum trajectories of UAVs is an emerging topic that aims at increasing the automation, efficiency and reliability of the data capturing process to achieve a dataset with desired quality. On the other hand, 3D reconstruction using the data captured by UAVs is also attracting attention in research and industry. This review paper investigates a wide range of model-free and model-based algorithms for viewpoint and path planning for 3D reconstruction of large-scale objects. The analyzed approaches are limited to those that employ a single-UAV as a data capturing platform for outdoor 3D reconstruction purposes. In addition to discussing the evaluation strategies, this paper also highlights the innovations and limitations of the investigated approaches. It concludes with a critical analysis of the existing challenges and future research perspectives.
Comments: 33 page- 177 references
Subjects: Computer Vision and Pattern Recognition (cs.CV); Graphics (cs.GR); Robotics (cs.RO)
Cite as: [cs.CV]
  (or [cs.CV] for this version)
  Focus to learn more arXiv-issued DOI via DataCite
Journal reference: IEEE Journal of Selected Topics in Applied Earth Observations and Remote Sensing-2023
: Focus to learn more DOI(s) linking to related resources

Submission history

Access paper:.

  • Other Formats

license icon

References & Citations

  • Google Scholar
  • Semantic Scholar

BibTeX formatted citation

BibSonomy logo

Bibliographic and Citation Tools

Code, data and media associated with this article, recommenders and search tools.

  • Institution

arXivLabs: experimental projects with community collaborators

arXivLabs is a framework that allows collaborators to develop and share new arXiv features directly on our website.

Both individuals and organizations that work with arXivLabs have embraced and accepted our values of openness, community, excellence, and user data privacy. arXiv is committed to these values and only works with partners that adhere to them.

Have an idea for a project that will add value for arXiv's community? Learn more about arXivLabs .

  •  Sign into My Research
  •  Create My Research Account
  • Company Website
  • Our Products
  • About Dissertations
  • Español (España)
  • Support Center

Select language

  • Bahasa Indonesia
  • Português (Brasil)
  • Português (Portugal)

Welcome to My Research!

You may have access to the free features available through My Research. You can save searches, save documents, create alerts and more. Please log in through your library or institution to check if you have access.

Welcome to My Research!

Translate this article into 20 different languages!

If you log in through your library or institution you might have access to this article in multiple languages.

Translate this article into 20 different languages!

Get access to 20+ different citations styles

Styles include MLA, APA, Chicago and many more. This feature may be available for free if you log in through your library or institution.

Get access to 20+ different citations styles

Looking for a PDF of this document?

You may have access to it for free by logging in through your library or institution.

Looking for a PDF of this document?

Want to save this document?

You may have access to different export options including Google Drive and Microsoft OneDrive and citation management tools like RefWorks and EasyBib. Try logging in through your library or institution to get access to these tools.

Want to save this document?

  • More like this
  • Preview Available
  • Scholarly Journal

3D path planning, routing algorithms and routing protocols for unmanned air vehicles: a review

Publisher logo. Links to publisher website, opened in a new window.

No items selected

Please select one or more items.

Select results items first to use the cite, email, save, and export options

You might have access to the full article...

Try and log in through your institution to see if they have access to the full text.

Content area

Introduction

Unmanned air vehicles (UAVs) were primarily developed for military applications (Amin et al. , 2016). The past few decades have witnessed the usages of UAVs in various civil applications ranging from urban surveillance to precision agriculture (Katsigiannis et al. , 2016). Some of these applications require multiple UAVs due to requirements such as multitasking, simultaneous operations in large areas and higher scalability among many. However, multiple UAVs operation is more complex and demanding research area with increased computational cost as compared to a single UAV operation. The major research areas in UAVs operations are guidance, navigation and control. There are many ongoing research activities in the navigation of multiple UAVs operation, but these research activities can be classified into three categories, namely, path planning, routing algorithms and routing protocols.

The proposed work, to the best of authors’ knowledge, is the first attempt to present a comprehensive yet succinct review study that deals with all major aspects of UAV navigation. A brief detail and updated literature review are provided about each aforementioned category. After the detailed literature review, a comprehensive discussion is also provided according to the performance evaluation criteria mentioned in the next section.

Although many reviews are there in the literature that dealt with different aspects of UAV such as:

Yang et al. (2015) presented a literature survey on UAV three degree-of-freedom (3D) path planning;

Sathyaraj et al. (2008) presented a comparative study on path planning algorithms of multiple UAV;

Yassein and Damer (2016) presented routing protocols and highlighted some issues in this regard; and

Nadeem et al. (2018) presented the classification of flying ad-hoc net routing strategies.

These surveys have only covered a single research area in UAV operation. Also, most of the available surveys have not provided a detailed comparison of algorithms and techniques based on performance criteria and further not discussed any prospective potential areas.

Hence, the proposed work is aimed to bridge this research gap by providing a comprehensive study on all research aspects of UAV navigation and further aimed to present a comparison of these methods, algorithms and techniques based on standard performance criteria. The basic purpose is to provide a complete overview and a performance comparison so that researchers in this area can select particular methods according...

You have requested "on-the-fly" machine translation of selected content from our databases. This functionality is provided solely for your convenience and is in no way intended to replace human translation. Show full disclaimer

Neither ProQuest nor its licensors make any representations or warranties with respect to the translations. The translations are automatically generated "AS IS" and "AS AVAILABLE" and are not retained in our systems. PROQUEST AND ITS LICENSORS SPECIFICALLY DISCLAIM ANY AND ALL EXPRESS OR IMPLIED WARRANTIES, INCLUDING WITHOUT LIMITATION, ANY WARRANTIES FOR AVAILABILITY, ACCURACY, TIMELINESS, COMPLETENESS, NON-INFRINGMENT, MERCHANTABILITY OR FITNESS FOR A PARTICULAR PURPOSE. Your use of the translations is subject to all use restrictions contained in your Electronic Products License Agreement and by using the translation functionality you agree to forgo any and all claims against ProQuest or its licensors for your use of the translation functionality and any output derived there from. Hide full disclaimer

Suggested sources

  • About ProQuest
  • Terms of Use
  • Privacy Policy
  • Cookie Policy

Information

  • Author Services

Initiatives

You are accessing a machine-readable page. In order to be human-readable, please install an RSS reader.

All articles published by MDPI are made immediately available worldwide under an open access license. No special permission is required to reuse all or part of the article published by MDPI, including figures and tables. For articles published under an open access Creative Common CC BY license, any part of the article may be reused without permission provided that the original article is clearly cited. For more information, please refer to https://www.mdpi.com/openaccess .

Feature papers represent the most advanced research with significant potential for high impact in the field. A Feature Paper should be a substantial original Article that involves several techniques or approaches, provides an outlook for future research directions and describes possible research applications.

Feature papers are submitted upon individual invitation or recommendation by the scientific editors and must receive positive feedback from the reviewers.

Editor’s Choice articles are based on recommendations by the scientific editors of MDPI journals from around the world. Editors select a small number of articles recently published in the journal that they believe will be particularly interesting to readers, or important in the respective research area. The aim is to provide a snapshot of some of the most exciting work published in the various research areas of the journal.

Original Submission Date Received: .

  • Active Journals
  • Find a Journal
  • Proceedings Series
  • For Authors
  • For Reviewers
  • For Editors
  • For Librarians
  • For Publishers
  • For Societies
  • For Conference Organizers
  • Open Access Policy
  • Institutional Open Access Program
  • Special Issues Guidelines
  • Editorial Process
  • Research and Publication Ethics
  • Article Processing Charges
  • Testimonials
  • Preprints.org
  • SciProfiles
  • Encyclopedia

drones-logo

Article Menu

a literature review of uav 3d path planning

  • Subscribe SciFeed
  • Google Scholar
  • on Google Scholar
  • Table of Contents

Find support for a specific problem in the support section of our website.

Please let us know what you think of our products and services.

Visit our dedicated information section to learn more about MDPI.

JSmol Viewer

A systematic literature review (slr) on autonomous path planning of unmanned aerial vehicles.

a literature review of uav 3d path planning

1. Introduction

  • Identify various parameters that are usually considered for the selection of literature from the primary studies and offer them as a look-up referral for the readers; and
  • Establish research directions, open challenges, and highlight state-of-the-art solutions through SLR methodology.

Why Systematic Literature Review (SLR)?

2. slr methodology.

  • Identify the key Research Questions (RQs);
  • Database selection;
  • Inclusion and exclusion Criteria;
  • Quality assurance; and
  • Biased studies identification
  • Related work;
  • Review parameters and synthesis; and
  • Research Directions (RDs)

Research Questions

3. review protocol, 3.1. employed database.

Database:Web of Science Core Collection
Keywords set:Autonomous + path planning + UAV
Search Field:All Fields

3.2. Inclusion Criteria

Duration:5 years approx. (2017–2022).
Publications Type:Journal Articles.
Journals Credibility:Q1–Q4 (JCR 2020).
Access Consideration:Open access

3.3. Exclusion Criteria

Publication Type:Review Articles.
Meetings:Conference Proceedings.
Language:Other than the English language.
Access Consideration:Early Access.

3.4. Quality Assurance

3.5. bias evasion, 3.6. internal peer review, 4. related work, 5. review parameters and synthesis, 5.1. metrics for workspace and environment configuration, 5.2. trajectory modes and dimensions, 5.3. nature of computation, 5.4. solution characterization, 5.5. testing and validation, 5.6. uav configuration by flight & design, 6. research directions (rd), 6.1. rd1: research sectors and challenges in autonomous path planning, 6.1.1. research sectors.

  • Nature of computational algorithm and the type of its solution

6.1.2. Current Challenges and Significant Contributions

  • Large and complex Environment
  • Perception Problems in Cooperative UAVs:
  • Tracking targets with moving obstacles:
  • Remote Sensing and Inspections in unknown environments:
  • Collaboration with heterogeneous robots in complex/hazardous scenarios:

6.2. RD2: The Measure of Autonomy among Autonomous Systems

6.3. rd3: employed technologies, 6.4. rd4: the ‘explain-ability’ in ai decisions (xai), 7. discussion, 8. conclusions, data availability statement, acknowledgments, conflicts of interest.

  • Borrego, M.; Foster, M.J.; Froyd, J.E. Systematic Literature Reviews in Engineering Education and Other Developing Interdisciplinary Fields. J. Eng. Educ. 2014 , 103 , 45–76. [ Google Scholar ] [ CrossRef ]
  • PRISMA. Preferred Reporting Items for Systematic Reviews and Meta-Analyses (PRISMA). Available online: https://www.prisma-statement.org/PRISMAStatement/ (accessed on 15 October 2021).
  • Maw, A.A.; Tyan, M.; Nguyen, T.A.; Lee, J.W. iADA*-RL: Anytime Graph-Based Path Planning with Deep Reinforcement Learning for an Autonomous UAV. Appl. Sci. 2021 , 11 , 18. (In English) [ Google Scholar ] [ CrossRef ]
  • Wang, B.; Bao, J.W.; Zhang, L.; Sheng, Q.H. UAV autonomous path optimization simulation based on radar tracking prediction. EURASIP J. Wirel. Commun. Netw. 2018 , 2018 , 8. (In English) [ Google Scholar ] [ CrossRef ]
  • Causa, F.; Fasano, G.; Grassi, M. Multi-UAV Path Planning for Autonomous Missions in Mixed GNSS Coverage Scenarios. Sensors 2018 , 18 , 27. (In English) [ Google Scholar ] [ CrossRef ]
  • Mardani, A.; Chiaberge, M.; Giaccon, P. Communication-Aware UAV Path Planning. IEEE Access 2019 , 7 , 52609–52621. (In English) [ Google Scholar ] [ CrossRef ]
  • Faria, M.; Marin, R.; Popovic, M.; Maza, I.; Viguria, A. Efficient Lazy Theta Path Planning over a Sparse Grid to Explore Large 3D Volumes with a Multirotor UAV. Sensors 2019 , 19 , 21. (In English) [ Google Scholar ] [ CrossRef ]
  • de Santos, L.M.G.; Nores, E.F.; Sanchez, J.M.; Jorge, H.G. Indoor Path-Planning Algorithm for UAV-Based Contact Inspection. Sensors 2021 , 21 , 23. (In English) [ 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. (In English) [ Google Scholar ] [ CrossRef ]
  • Jayaweera, H.; Hanoun, S. A Dynamic Artificial Potential Field (D-APF) UAV Path Planning Technique for Following Ground Moving Targets. IEEE Access 2020 , 8 , 192760–192776. (In English) [ Google Scholar ] [ CrossRef ]
  • Zhao, Y.H.; Yan, L.; Chen, Y.; Dai, J.C.; Liu, Y.X. Robust and Efficient Trajectory Replanning Based on Guiding Path for Quadrotor Fast Autonomous Flight. Remote Sens. 2021 , 13 , 25. (In English) [ Google Scholar ] [ CrossRef ]
  • Kwak, J.; Sung, Y. Autonomous UAV Flight Control for GPS-Based Navigation. IEEE Access 2018 , 6 , 37947–37955. (In English) [ Google Scholar ] [ CrossRef ]
  • Popovic, M.; Vidal-Calleja, T.; Hitz, G.; Chung, J.J.; Sa, I.; Siegwart, R.; Nieto, J. An informative path planning framework for UAV-based terrain monitoring. Auton. Robot. 2020 , 44 , 889–911. (In English) [ Google Scholar ] [ CrossRef ]
  • Wang, Q.; Chen, H.; Qiao, L.; Tian, J.W.; Su, Y. Path planning for UAV/UGV collaborative systems in intelligent manufacturing. IET Intell. Transp. Syst. 2020 , 14 , 1475–1483. (In English) [ Google Scholar ] [ CrossRef ]
  • Nielsen, L.D.; Sung, I.; Nielsen, P. Convex Decomposition for a Coverage Path Planning for Autonomous Vehicles: Interior Extension of Edges. Sensors 2019 , 19 , 11. (In English) [ Google Scholar ] [ CrossRef ]
  • Melo, A.G.; Pinto, M.F.; Marcato, A.L.M.; Honorio, L.M.; Coelho, F.O. Dynamic Optimization and Heuristics Based Online Coverage Path Planning in 3D Environment for UAVs. Sensors 2021 , 21 , 25. (In English) [ Google Scholar ] [ CrossRef ]
  • Oh, D.; Han, J. Fisheye-Based Smart Control System for Autonomous UAV Operation. Sensors 2020 , 20 , 19. (In English) [ Google Scholar ] [ CrossRef ]
  • Huang, H.L.; Savkin, A.V. Autonomous Navigation of a Solar-Powered UAV for Secure Communication in Urban Environments with Eavesdropping Avoidance. Future Internet 2020 , 12 , 14. (In English) [ Google Scholar ] [ CrossRef ]
  • Faria, M.; Ferreira, A.S.; Perez-Leon, H.; Maza, I.; Viguria, A. Autonomous 3D Exploration of Large Structures Using an UAV Equipped with a 2D LIDAR. Sensors 2019 , 19 , 24. (In English) [ Google Scholar ] [ CrossRef ]
  • Hayat, S.; Yanmaz, E.; Bettstetter, C.; Brown, T.X. Multi-objective drone path planning for search and rescue with quality-of-service requirements. Auton. Robot. 2020 , 44 , 1183–1198. (In English) [ Google Scholar ] [ CrossRef ]
  • Tullu, A.; Endale, B.; Wondosen, A.; Hwang, H.Y. Machine Learning Approach to Real-Time 3D Path Planning for Autonomous Navigation of Unmanned Aerial Vehicle. Appl. Sci. 2021 , 11 , 19. (In English) [ Google Scholar ] [ CrossRef ]
  • Koohifar, F.; Guvenc, I.; Sichitiu, M.L. Autonomous Tracking of Intermittent RF Source Using a UAV Swarm. IEEE Access 2018 , 6 , 15884–15897. (In English) [ Google Scholar ] [ CrossRef ]
  • Schellenberg, B.; Richardson, T.; Richards, A.; Clarke, R.; Watson, M. On-Board Real-Time Trajectory Planning for Fixed Wing Unmanned Aerial Vehicles in Extreme Environments. Sensors 2019 , 19 , 21. (In English) [ Google Scholar ] [ CrossRef ] [ PubMed ]
  • Xie, R.L.; Meng, Z.J.; Wang, L.F.; Li, H.C.; Wang, K.P.; 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. (In English) [ Google Scholar ] [ CrossRef ]
  • Zhang, C.; Hu, C.X.; Feng, J.R.; Liu, Z.B.; Zhou, Y.; Zhang, Z.X. A Self-Heuristic Ant-Based Method for Path Planning of Unmanned Aerial Vehicle in Complex 3-D Space With Dense U-Type Obstacles. IEEE Access 2019 , 7 , 150775–150791. (In English) [ Google Scholar ] [ CrossRef ]
  • Sanchez-Lopez, J.L.; Wang, M.; Olivares-Mendez, M.A.; Molina, M.; Voos, H. A Real-Time 3D Path Planning Solution for Collision-Free Navigation of Multirotor Aerial Robots in Dynamic Environments. J. Intell. Robot. Syst. 2019 , 93 , 33–53. (In English) [ Google Scholar ] [ CrossRef ]
  • Tan, L.G.; Wu, J.C.; Yang, X.Y.; Song, S.M. Research on Optimal Landing Trajectory Planning Method between an UAV and a Moving Vessel. Appl. Sci. 2019 , 9 , 14. (In English) [ Google Scholar ] [ CrossRef ]
  • Razzaq, S.; Xydeas, C.; Everett, M.E.; Mahmood, A.; Alquthami, T. Three-Dimensional UAV Routing With Deconfliction. IEEE Access 2018 , 6 , 21536–21551. (In English) [ Google Scholar ] [ CrossRef ]
  • Liu, Z.F.; Wang, X.Y.; Liu, Y.Y. Application of Unmanned Aerial Vehicle Hangar in Transmission Tower Inspection Considering the Risk Probabilities of Steel Towers. IEEE Access 2019 , 7 , 159048–159057. (In English) [ Google Scholar ] [ CrossRef ]
  • Hong, Y.; Jung, S.; Kim, S.; Cha, J. Autonomous Mission of Multi-UAV for Optimal Area Coverage. Sensors 2021 , 21 , 21. (In English) [ Google Scholar ] [ CrossRef ]
  • Wu, C.X.; Ju, B.B.; Wu, Y.; Lin, X.; Xiong, N.X.; Xu, G.Q.; Li, H.Y.; Liang, X.F. UAV Autonomous Target Search Based on Deep Reinforcement Learning in Complex Disaster Scene. IEEE Access 2019 , 7 , 117227–117245. (In English) [ Google Scholar ] [ CrossRef ]
  • Andrade, F.A.D.; Hovenburg, A.R.; de Lima, L.N.; Rodin, C.D.; Johansen, T.A.; Storvold, R.; Correia, C.A.M.; Haddad, D.B. Autonomous Unmanned Aerial Vehicles in Search and Rescue Missions Using Real-Time Cooperative Model Predictive Control. Sensors 2019 , 19 , 22. (In English) [ Google Scholar ] [ CrossRef ]
  • Liu, J.; Han, W.; Liu, C.; Peng, H.J. A New Method for the Optimal Control Problem of Path Planning for Unmanned Ground Systems. IEEE Access 2018 , 6 , 33251–33260. (In English) [ Google Scholar ] [ CrossRef ]
  • Ling, H.F.; Luo, H.C.A.; Chen, H.S.; Bai, L.Y.; Zhu, T.; Wang, Y.J. Modelling and Simulation of Distributed UAV Swarm Cooperative Planning and Perception. Int. J. Aerosp. Eng. 2021 , 2021 , 11. (In English) [ Google Scholar ] [ CrossRef ]
  • Akagi, J.; Morris, T.D.; Moon, B.; Chen, X.G.; Peterson, C.K. Gesture commands for controlling high-level UAV behavior. SN Appl. Sci. 2021 , 3 , 23. (In English) [ Google Scholar ] [ CrossRef ]
  • Charrier, T.; Queffelec, A.; Sankur, O.; Schwarzentruber, F. Complexity of planning for connected agents. Auton. Agents Multi-Agent Syst. 2020 , 34 , 31. (In English) [ Google Scholar ] [ CrossRef ]
  • Li, Z.Y.; Liu, W.D.; Gao, L.E.; Li, L.; Zhang, F.H. Path Planning Method for AUV Docking Based on Adaptive Quantum-Behaved Particle Swarm Optimization. IEEE Access 2019 , 7 , 78665–78674. (In English) [ Google Scholar ] [ CrossRef ]
  • Kuhlman, M.J.; Otte, M.W.; Sofge, D.; Gupta, S.K. Multipass Target Search in Natural Environments. Sensors 2017 , 17 , 36. (In English) [ Google Scholar ] [ CrossRef ]
  • Sanchez, P.; Casado, R.; Bermudez, A. Real-Time Collision-Free Navigation of Multiple UAVs Based on Bounding Boxes. Electronics 2020 , 9 , 19. (In English) [ Google Scholar ] [ CrossRef ]
  • Lee, G.T.; Kim, C.O. Autonomous Control of Combat Unmanned Aerial Vehicles to Evade Surface-to-Air Missiles Using Deep Reinforcement Learning. IEEE Access 2020 , 8 , 226724–226736. (In English) [ Google Scholar ] [ CrossRef ]
  • Simon, J.; Petkovic, I.; Petkovic, D.; Petkovics, A. Navigation and Applicability of Hexa Rotor Drones in Greenhouse Environment. Teh. Vjesn. 2018 , 25 , 249–255. (In English) [ Google Scholar ] [ CrossRef ]
  • Papa, U.; Ponte, S. Preliminary Design of an Unmanned Aircraft System for Aircraft General Visual Inspection. Electronics 2018 , 7 , 15. (In English) [ Google Scholar ] [ CrossRef ]
  • Allak, E.; Brommer, C.; Dallenbach, D.; Weiss, S. AMADEE-18: Vision-Based Unmanned Aerial Vehicle Navigation for Analog Mars Mission (AVI-NAV). Astrobiology 2020 , 20 , 1321–1337. (In English) [ Google Scholar ] [ CrossRef ] [ PubMed ]
  • Bian, J.; Huie, X.L.; Zhao, X.G.; Tan, M. A monocular vision-based perception approach for unmanned aerial vehicle close proximity transmission tower inspection. Int. J. Adv. Robot. Syst. 2019 , 16 , 20. (In English) [ Google Scholar ] [ CrossRef ]
  • Lazna, T.; Gabrlik, P.; Jilek, T.; Zalud, L. Cooperation between an unmanned aerial vehicle and an unmanned ground vehicle in highly accurate localization of gamma radiation hotspots. Int. J. Adv. Robot. Syst. 2018 , 15 , 16. (In English) [ Google Scholar ] [ CrossRef ]
  • Pinto, M.F.; Honorio, L.M.; Melo, A.; Marcato, A.L.M. A Robotic Cognitive Architecture for Slope and Dam Inspections. Sensors 2020 , 20 , 19. (In English) [ Google Scholar ] [ CrossRef ]
  • Mazzia, V.; Salvetti, F.; Aghi, D.; Chiaberge, M. DeepWay: A Deep Learning waypoint estimator for global path generation. Comput. Electron. Agric. 2021 , 184 , 9. (In English) [ Google Scholar ] [ CrossRef ]
  • Masone, C.; Mohammadi, M.; Giordano, P.R.; Franchi, A. Shared planning and control for mobile robots with integral haptic feedback. Int. J. Robot. Res. 2018 , 37 , 1395–1420. (In English) [ Google Scholar ] [ CrossRef ]
  • Loianno, G.; Brunner, C.; McGrath, G.; Kumar, V. Estimation, Control, and Planning for Aggressive Flight With a Small Quadrotor with a Single Camera and IMU. IEEE Robot. Autom. Lett. 2017 , 2 , 404–411. (In English) [ Google Scholar ] [ CrossRef ]
  • Woods, A.C.; La, H.M. A Novel Potential Field Controller for Use on Aerial Robots. IEEE Trans. Syst. Man Cybern. Syst. 2019 , 49 , 665–676. (In English) [ Google Scholar ] [ CrossRef ]
  • Comba, L.; Zaman, S.; Biglia, A.; Aimonino, D.R.; Dabbene, F.; Gay, P. Semantic interpretation and complexity reduction of 3D point clouds of vineyards. Biosyst. Eng. 2020 , 197 , 216–230. (In English) [ Google Scholar ] [ CrossRef ]
  • Airlangga, G.; Liu, A. Online Path Planning Framework for UAV in Rural Areas. IEEE Access 2022 , 10 , 37572–37585. (In English) [ Google Scholar ] [ CrossRef ]
  • Cheng, Z.K.; Zhao, L.Y.; Shi, Z.J. Decentralized Multi-UAV Path Planning Based on Two-Layer Coordinative Framework for Formation Rendezvous. IEEE Access 2022 , 10 , 45695–45708. (In English) [ Google Scholar ] [ CrossRef ]
  • Sun, Y.F.; Ma, O. Automating Aircraft Scanning for Inspection or 3D Model Creation with a UAV and Optimal Path Planning. Drones 2022 , 6 , 15. (In English) [ Google Scholar ] [ CrossRef ]
  • Li, D.C.; Yin, W.P.; Wong, W.E.; Jian, M.Y.; Chau, M. Quality-Oriented Hybrid Path Planning Based on A* and Q-Learning for Unmanned Aerial Vehicle. IEEE Access 2022 , 10 , 7664–7674. (In English) [ Google Scholar ] [ CrossRef ]
  • Alajami, A.A.; Moreno, G.; Pous, R. Design of a UAV for Autonomous RFID-Based Dynamic Inventories Using Stigmergy for Mapless Indoor Environments. Drones 2022 , 6 , 21. (In English) [ Google Scholar ] [ CrossRef ]
  • Shao, S.K.; Shi, W.L.; Zhao, Y.J.; Du, Y. A New Method of Solving UAV Trajectory Planning Under Obstacles and Multi-Constraint. IEEE Access 2021 , 9 , 161161–161180. (In English) [ Google Scholar ] [ CrossRef ]
  • Vanegas, G.; Armesto, L.; Girbes-Juan, V.; Perez, J. Smooth Three-Dimensional Route Planning for Fixed-Wing Unmanned Aerial Vehicles With Double Continuous Curvature. IEEE Access 2022 , 10 , 94262–94272. (In English) [ Google Scholar ] [ CrossRef ]
  • Alharbi, H.A.; Yosuf, B.A.; Aldossary, M.; Almutairi, J.; Elmirghani, J.M.H. Energy Efficient UAV-Based Service Offloading Over Cloud-Fog Architectures. IEEE Access 2022 , 10 , 89598–89613. (In English) [ Google Scholar ] [ CrossRef ]
  • Lee, S.; Lee, H. Trajectory Generation of a Quadrotor Transporting a Bulky Payload in the Cluttered Environments. IEEE Access 2022 , 10 , 31586–31594. (In English) [ Google Scholar ] [ CrossRef ]
  • Miccinesi, L.; Bigazzi, L.; Consumi, T.; Pieraccini, M.; Beni, A.; Boni, E.; Basso, M. Geo-Referenced Mapping through an Anti-Collision Radar Aboard an Unmanned Aerial System. Drones 2022 , 6 , 17. (In English) [ Google Scholar ] [ CrossRef ]
  • Mathisen, S.G.; Leira, F.S.; Helgesen, H.H.; Gryte, K.; Johansen, T.A. Autonomous ballistic airdrop of objects from a small fixed-wing unmanned aerial vehicle. Auton. Robot. 2020 , 44 , 859–875. (In English) [ Google Scholar ] [ CrossRef ]
  • Yu, X.; Chen, W.N.; Gu, T.L.; Yuan, H.Q.; Zhang, H.X.; Zhang, J. ACO-A*: Ant Colony Optimization Plus A* for 3-D Traveling in Environments With Dense Obstacles. IEEE Trans. Evol. Comput. 2019 , 23 , 617–631. (In English) [ Google Scholar ] [ CrossRef ]
  • Chen, S.Y.; Chen, H.; Chang, C.W.; Wen, C.Y. Multilayer Mapping Kit for Autonomous UAV Navigation. IEEE Access 2021 , 9 , 31493–31503. (In English) [ Google Scholar ] [ CrossRef ]
  • Nguyen, H.V.; Chesser, M.; Koh, L.P.; Rezatofighi, S.H.; Ranasinghe, D.C. TrackerBots: Autonomous unmanned aerial vehicle for real-time localization and tracking of multiple radio-tagged animals. J. Field Robot. 2019 , 36 , 617–635. (In English) [ Google Scholar ] [ CrossRef ]
  • Spurny, V.; Baca, T.; Saska, M.; Penicka, R.; Krajnik, T.; Thomas, J.; Thakur, D.; Loianno, G.; Kumar, V. Cooperative autonomous search, grasping, and delivering in a treasure hunt scenario by a team of unmanned aerial vehicles. J. Field Robot. 2019 , 36 , 125–148. (In English) [ Google Scholar ] [ CrossRef ]
  • He, R.K.; Wei, R.X.; Zhang, Q.R. UAV autonomous collision avoidance approach. Automatika 2017 , 58 , 195–204. (In English) [ Google Scholar ] [ CrossRef ]
  • Iacono, M.; Sgorbissa, A. Path following and obstacle avoidance for an autonomous UAV using a depth camera. Robot. Auton. Syst. 2018 , 106 , 38–46. (In English) [ Google Scholar ] [ CrossRef ]
  • Zhou, B.Y.; Zhang, Y.C.; Chen, X.Y.; Shen, S.J. FUEL: Fast UAV Exploration Using Incremental Frontier Structure and Hierarchical Planning. IEEE Robot. Autom. Lett. 2021 , 6 , 779–786. (In English) [ Google Scholar ] [ CrossRef ]
  • Xu, Z.F.; Deng, D.; Shimada, K. Autonomous UAV Exploration of Dynamic Environments Via Incremental Sampling and Probabilistic Roadmap. IEEE Robot. Autom. Lett. 2021 , 6 , 2729–2736. (In English) [ Google Scholar ] [ CrossRef ]
  • Beck, Z.; Teacy, W.T.L.; Rogers, A.; Jennings, N.R. Collaborative online planning for automated victim search in disaster response. Robot. Auton. Syst. 2018 , 100 , 251–266. (In English) [ Google Scholar ] [ CrossRef ] [ Green Version ]
  • Christie, G.; Shoemaker, A.; Kochersberger, K.; Tokekar, P.; McLean, L.; Leonessa, A. Radiation search operations using scene understanding with autonomous UAV and UGV. J. Field Robot. 2017 , 34 , 1450–1468. (In English) [ Google Scholar ] [ CrossRef ]
  • Ramirez-Torres, J.G.; Larranaga-Cepeda, A. LTI-UAV3D: A solution of high quality and low cost for terrain 3D reconstruction using a mu-uav. Dyna 2017 , 92 , 412–419. (In English) [ Google Scholar ] [ CrossRef ]
  • Lo, L.Y.; Yiu, C.H.; Tang, Y.; Yang, A.S.; Li, B.Y.; Wen, C.Y. Dynamic Object Tracking on Autonomous UAV System for Surveillance Applications. Sensors 2021 , 21 , 22. (In English) [ 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 , 14. (In English) [ Google Scholar ] [ CrossRef ]
  • Kurdel, P.; Ceskovic, M.; Gecejova, N.; Adamcik, F.; Gamcova, M. Local Control of Unmanned Air Vehicles in the Mountain Area. Drones 2022 , 6 , 18. (In English) [ Google Scholar ] [ CrossRef ]
  • Doukhi, O.; Lee, D.J. Deep Reinforcement Learning for Autonomous Map-Less Navigation of a Flying Robot. IEEE Access 2022 , 10 , 82964–82976. (In English) [ Google Scholar ] [ CrossRef ]
  • Tordesillas, J.; How, J.P. PANTHER: Perception-Aware Trajectory Planner in Dynamic Environments. IEEE Access 2022 , 10 , 22662–22677. (In English) [ Google Scholar ] [ CrossRef ]
  • Shao, S.K.; He, C.L.; Zhao, Y.J.; Wu, X.J. Efficient Trajectory Planning for UAVs Using Hierarchical Optimization. IEEE Access 2021 , 9 , 60668–60681. (In English) [ Google Scholar ] [ CrossRef ]
  • Lopez, B.; Munoz, 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 , 21. (In English) [ Google Scholar ] [ CrossRef ]
  • Li, B.; Yang, Z.P.; Chen, D.Q.; Liang, S.Y.; Ma, H. Maneuvering target tracking of UAV based on MN-DDPG and transfer learning. Def. Technol. 2021 , 17 , 457–466. (In English) [ Google Scholar ] [ CrossRef ]
  • Feng, Y.R.; Tse, K.; Chen, S.Y.; Wen, C.Y.; Li, B.Y. Learning-Based Autonomous UAV System for Electrical and Mechanical (E&M) Device Inspection. Sensors 2021 , 21 , 19. (In English) [ Google Scholar ] [ CrossRef ]
  • Sandino, J.; Vanegas, F.; Maire, F.; Caccetta, P.; Sanderson, C.; Gonzalez, F. UAV Framework for Autonomous Onboard Navigation and People/Object Detection in Cluttered Indoor Environments. Remote Sens. 2020 , 12 , 31. (In English) [ Google Scholar ] [ CrossRef ]
  • Xu, C.C.; Liao, X.H.; Ye, H.P.; Yue, H.Y. Iterative construction of low-altitude UAV air route network in urban areas: Case planning and assessment. J. Geogr. Sci. 2020 , 30 , 1534–1552. (In English) [ Google Scholar ] [ CrossRef ]
  • Yang, J.; Wang, X.M.; Baldi, S.; Singh, S.; Fari, S. A Software-in-the-Loop Implementation of Adaptive Formation Control for Fixed-Wing UAVs. IEEE-CAA J. Automatica Sin. 2019 , 6 , 1230–1239. (In English) [ Google Scholar ] [ CrossRef ]
  • Guerra, A.; Dardari, D.; Djuric, P.M. Dynamic Radar Network of UAVs: A Joint Navigation and Tracking Approach. IEEE Access 2020 , 8 , 116454–116469. (In English) [ Google Scholar ] [ CrossRef ]
  • Albert, A.; Leira, F.S.; Imsland, L. UAV Path Planning using MILP with Experiments. Model. Identif. Control. 2017 , 38 , 21–32. (In English) [ Google Scholar ] [ CrossRef ]
  • Challita, U.; Saad, W.; Bettstetter, C. Interference Management for Cellular-Connected UAVs: A Deep Reinforcement Learning Approach. IEEE Trans. Wirel. Commun. 2019 , 18 , 2125–2140. (In English) [ Google Scholar ] [ CrossRef ]
  • Guo, T.; Jiang, N.; Li, B.Y.; Zhu, X.; Wang, Y.; Du, W.B. UAV navigation in high dynamic environments: A deep reinforcement learning approach. Chin. J. Aeronaut. 2021 , 34 , 479–489. (In English) [ Google Scholar ] [ CrossRef ]
  • Marco Protti, R.B. UAV Autonomy –Which level is desirable?—Which level is acceptable? Alenia Aeronautica Viewpoint. In Platform Innovations and System Integration for Unmanned Air, Land and Sea Vehicles (AVT-SCI Joint Symposium) ; NATO RTO: Neuilly-sur-Seine, France, 2007. [ Google Scholar ]
  • Turek, D.M. Explainable Artificial Intelligence (XAI). Available online: https://www.darpa.mil/program/explainable-artificial-intelligence (accessed on 15 October 2021).
  • Alammar, J. Ecco: An Open Source Library for the Explainability of Transformer Language Models. In Proceedings of the 11th International Joint Conference on Natural Language Processing: System Demonstrations: Association for Computational Linguistics, Online, 1–6 August 2021; pp. 249–257. Available online: https://aclanthology.org/2021.acl-demo.30 (accessed on 15 October 2021).

Click here to enlarge figure

ParameterReferences%Age
Predictable (with prior knowledge)[ , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , ]80%
Unpredictable[ , , , , , , , , , , , , , , , , ]20%
Static[ , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , ]77.6%
Dynamic[ , , , , , , , , , , , , , , ]22.4%
Indoor[ , , , , , , , , , , , , , , , , , , , , , , , , , ]40%
Outdoor or unspecified or Both[ , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , ]60%
ParameterReferences%Age
2D[ , , , , , , , , , , , , , , , , , , , , , , , , , , , , ]41.5%
3D[ , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , ]58.5%
Offline[ , , , , , , , , , , , , , , , , ]24.3%
Online[ , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , ]75.7%
ParameterReferences
Deterministic[ , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , ]
Stochastic[ , , , , , , , , , , , , , ]
Heuristic[ , , , , , , , , , , , , , , , , , , ]
Hybrid[ , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , ]
ParameterReferences
Complete[ , , , , , , , , , , , , , ]
Exact[ , , , , , , , , , , , , , , , , , , , , , , , , , , ]
Approximate[ , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , ]
Optimality[ , , , , , , , , , , , , , , , , , , , , , , , , , , , , , ]
ParameterReferences%Age
Simulation Only or Hardware In The Loop (HITL) Simulation[ , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , ]60%
Simulation with Hardware or real environment Validation[ , , , , , , , , , , , , , , , , , , , , , , , ]32%
ParameterReferences%Age
Single[ , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , ]63%
Multiple[ , , , , , , , , , , , , , , , , , ]24%
Fixed Wing[ , , , , , , , , , , , , , , , , , , , , ]29%
Rotary[ , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , , ]60%
Tool/Platform (SW/HW)References
ROS GAZEBO[ , , , , , , , , , , ]
MATLAB/Simulink[ , , , , , , , , , , , , , ]
Python (2.×, 3.×, PyCharm etc.)[ ]
V-REP[ , , ]
Kestrel (ViDAR)[ ]
Air-Learning[ ]
AirSim (Unreal Engine)[ , ]
Flight Gear Simulator[ ]
QGroundControl[ ]
ArduPilot[ , ]
PIXHAWK[ , , , , ]
HK Pilot 32[ ]
RaspberryPie[ ]
ODroidXU[ ]
Beaglebone[ ]
The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

ul Husnain, A.; Mokhtar, N.; Mohamed Shah, N.; Dahari, M.; Iwahashi, M. A Systematic Literature Review (SLR) on Autonomous Path Planning of Unmanned Aerial Vehicles. Drones 2023 , 7 , 118. https://doi.org/10.3390/drones7020118

ul Husnain A, Mokhtar N, Mohamed Shah N, Dahari M, Iwahashi M. A Systematic Literature Review (SLR) on Autonomous Path Planning of Unmanned Aerial Vehicles. Drones . 2023; 7(2):118. https://doi.org/10.3390/drones7020118

ul Husnain, Anees, Norrima Mokhtar, Noraisyah Mohamed Shah, Mahidzal Dahari, and Masahiro Iwahashi. 2023. "A Systematic Literature Review (SLR) on Autonomous Path Planning of Unmanned Aerial Vehicles" Drones 7, no. 2: 118. https://doi.org/10.3390/drones7020118

Article Metrics

Article access statistics, further information, mdpi initiatives, follow mdpi.

MDPI

Subscribe to receive issue release notifications and newsletters from MDPI journals

IEEE Account

  • Change Username/Password
  • Update Address

Purchase Details

  • Payment Options
  • Order History
  • View Purchased Documents

Profile Information

  • Communications Preferences
  • Profession and Education
  • Technical Interests
  • US & Canada: +1 800 678 4333
  • Worldwide: +1 732 981 0060
  • Contact & Support
  • About IEEE Xplore
  • Accessibility
  • Terms of Use
  • Nondiscrimination Policy
  • Privacy & Opting Out of Cookies

A not-for-profit organization, IEEE is the world's largest technical professional organization dedicated to advancing technology for the benefit of humanity. © Copyright 2024 IEEE - All rights reserved. Use of this web site signifies your agreement to the terms and conditions.

UAV Path Planning Using Optimization Approaches: A Survey

  • Survey article
  • Published: 18 April 2022
  • Volume 29 , pages 4233–4284, ( 2022 )

Cite this article

a literature review of uav 3d path planning

  • Amylia Ait Saadi 1 , 2 ,
  • Assia Soukane 3 ,
  • Yassine Meraihi   ORCID: orcid.org/0000-0002-3735-7797 1 ,
  • Asma Benmessaoud Gabis 4 ,
  • Seyedali Mirjalili 5 , 6 &
  • Amar Ramdane-Cherif 2  

6044 Accesses

70 Citations

Explore all metrics

Path planning is one of the most important steps in the navigation and control of Unmanned Aerial Vehicles (UAVs). It ensures an optimal and collision-free path between two locations from a starting point (source) to a destination one (target) for autonomous UAVs while meeting requirements related to UAV characteristics and the serving area. In this paper, we present an overview of UAV path planning approaches classified into five main categories including classical methods, heuristics, meta-heuristics, machine learning, and hybrid algorithms. For each category, a critical analysis is given based on targeted objectives, considered constraints, and environments. In the end, we suggest some highlights and future research directions for UAV path planning.

This is a preview of subscription content, log in via an institution to check access.

Access this article

Subscribe and save.

  • Get 10 units per month
  • Download Article/Chapter or eBook
  • 1 Unit = 1 Article or 1 Chapter
  • Cancel anytime

Price includes VAT (Russian Federation)

Instant access to the full article PDF.

Rent this article via DeepDyve

Institutional subscriptions

a literature review of uav 3d path planning

Similar content being viewed by others

a literature review of uav 3d path planning

Path Planning of Unmanned Aerial Vehicles: Current State and Future Challenges

a literature review of uav 3d path planning

Minimum Time Search Methods for Unmanned Aerial Vehicles

a literature review of uav 3d path planning

Path planning optimization in unmanned aerial vehicles using meta-heuristic algorithms: a systematic review

Explore related subjects.

  • Artificial Intelligence

Sullivan JM (2006) Evolution or revolution? the rise of UAVs. IEEE Technol Soc Mag 25(3):43–49

Article   Google Scholar  

Ibrahim AWN, Ching PW, Seet GG, Lau WM, Czajewski W (2010) Moving objects detection and tracking framework for UAV-based surveillance. In: 2010 fourth Pacific-Rim symposium on image and video technology, pp 456–461. IEEE

Ma'Sum MA, Arrofi MK, Jati G, Arifin F, Kurniawan MN, Mursanto P, Jatmiko W (2013) Simulation of intelligent unmanned aerial vehicle (UAV) for military surveillance. In: 2013 international conference on advanced computer science and information systems (ICACSIS), pp 161–166. IEEE

Senthilnath J, Kandukuri M, Dokania A, Ramesh KN (2017) Application of UAV imaging platform for vegetation analysis based on spectral-spatial methods. Comput Electron Agric 140:8–24

Katsigiannis P, Misopolinos L, Liakopoulos V, Alexandridis TK, Zalidis G (2016) An autonomous multi-sensor UAV system for reduced-input precision agriculture applications. In: 2016 24th Mediterranean conference on control and automation (MED), pp 60–64. IEEE

Hu D, Qi B, Du R, Yang H, Wang J, Zhuge J (2019) An atmospheric vertical detection system using the multi-rotor UAV. In: 2019 international conference on meteorology observations (ICMO), pp 1–4. IEEE

Rogers K, Rice F, Finn A (2015) UAV-based atmospheric tomography using large eddy simulation data. In: 2015 IEEE tenth international conference on intelligent sensors, sensor networks and information processing (ISSNIP), pp 1–6. IEEE

Holness C, Matthews T, Satchell K, Swindell EC (2016) Remote sensing archeological sites through unmanned aerial vehicle (UAV) imaging. In: 2016 IEEE international geoscience and remote sensing symposium (IGARSS), pp 6695–6698. IEEE

Botrugno MC, D’Errico G, De Paolis LT (2017) Augmented reality and UAVs in archaeology: development of a location-based ar application. In: International conference on augmented reality, virtual reality and computer graphics, pp 261–270. Springer

Doherty P, Rudol P (2007) A UAV search and rescue scenario with human body detection and geolocalization. In: Australasian joint conference on artificial intelligence, pp 1–13. Springer

Erdelj M, Natalizio E (2016) UAV-assisted disaster management: Applications and open issues. In: 2016 international conference on computing, networking and communications (ICNC), pp. 1–5. IEEE

Yuncheng L, Xue Z, Xia G-S, Zhang L (2018) A survey on vision-based UAV navigation. Geo-spatial Inf Sci 21(1):21–32

EUROCONTROL (1963) EUROCONTROL: airspace utilisation. https://www.eurocontrol.int/function/airspace-utilisation . Accessed 31 Jan 2021.

EUROCONTROL (1963) EUROCONTROL: UAS no-fly areas. https://www.eurocontrol.int/tool/uas-no-fly-areas-directory-information-resources . Accessed 31 Jan 2021

SESAR (2004) SESAR: CORUSXUAM objectives. https://www.sesarju.eu/projects/CORUSXUAM . Accessed 1 Feb 2021

CORUSXUAM (2020) CORUSXUAM: description. https://corus-xuam.eu/about/ . Accessed 1 Feb 2021

Vergouw B, Nagel H, Bondt G, Custers B (2016) Drone technology: types, payloads, applications, frequency spectrum issues and future developments. In: The future of drone use, pp 21–45. Springer

Goerzen C, Kong Z, Mettler B (2010) A survey of motion planning algorithms from the perspective of autonomous UAV guidance. J Intell Rob Syst 57(1–4):65

Article   MATH   Google Scholar  

Yang L, Qi J, Xiao J, Yong X (2014) A literature review of UAV 3d path planning. In: Proceeding of the 11th world congress on intelligent control and automation, pp. 2376–2381. IEEE

Pandey P, Shukla A, Tiwari R (2017) Aerial path planning using meta-heuristics: a survey. In: 2017 second international conference on electrical, computer and communication technologies (ICECCT), pp. 1–7. IEEE

Zhao Y, Zheng Z, Liu Y (2018) Survey on computational-intelligence-based UAV path planning. Knowl-Based Syst 158:54–64

Radmanesh M, Kumar M, Guentert PH, Sarim M (2018) Overview of path-planning and obstacle avoidance algorithms for UAVs: a comparative study. Unmanned Syst 6(02):95–118

Aggarwal S, Kumar N (2020) Path planning techniques for unmanned aerial vehicles: a review, solutions, and challenges. Comput Commun 149:270–299

Yang K, Keat Gan S, Sukkarieh S (2013) A gaussian process-based RRT planner for the exploration of an unknown and cluttered environment with a UAV. Adv Robot 27(6):431–443

Kothari M, Postlethwaite I (2013) A probabilistically robust path planning algorithm for UAVs using rapidly-exploring random trees. J Intell Robot Syst 71(2):231–253

Lin Y, Saripalli S (2014) Path planning using 3d dubins curve for unmanned aerial vehicles. In: 2014 international conference on unmanned aircraft systems (ICUAS), pp. 296–304. IEEE

Xinggang W, Cong G, Yibo L (2014) Variable probability based bidirectional RRT algorithm for UAV path planning. In: The 26th Chinese control and decision conference (2014 CCDC), pp 2217–2222. IEEE

Yang Hongji, Jia Qingzhong, Zhang Weizhong (2018) An environmental potential field based RRT algorithm for UAV path planning. In 2018 37th Chinese Control Conference (CCC) , pages 9922–9927. IEEE,

Zu W, Fan G, Gao Y, Ma Y, Zhang H, Zeng H (2018) Multi-UAVs cooperative path planning method based on improved RRT algorithm. In: 2018 IEEE international conference on mechatronics and automation (ICMA), pp 1563–1567. IEEE

Sun Q, Li M, Wang T, Zhao C (2018) UAV path planning based on improved rapidly-exploring random tree. In: 2018 Chinese control and decision conference (CCDC), pp 6420–6424. IEEE

Meng LI, Qinpeng SUN, Mengmei ZHU (2019) UAV 3-dimension flight path planning based on improved rapidly-exploring random tree. In: 2019 Chinese control and decision conference (CCDC), pp 921–925. IEEE

Wen N, Zhao L, Xiaohong S, Ma P (2015) UAV online path planning algorithm in a low altitude dangerous environment. IEEE/CAA J Autom Sin 2(2):173–185

Article   MathSciNet   Google Scholar  

Lee D, Shim DH (2016) Path planner based on bidirectional spline-RRT \(^{*}\) for fixed-wing UAVs. In: 2016 international conference on unmanned aircraft systems (ICUAS), pp 77–86. IEEE

Aguilar WG, Morales S, Ruiz H, Abad V (2017) RRT* gl based optimal path planning for real-time navigation of UAVs. In: International work-conference on artificial neural networks, pp 585–595. Springer

Meng J, Pawar VM, Kay S, Li (2018) Angran UAV path planning system based on 3d informed RRT* for dynamic obstacle avoidance. In: 2018 IEEE international conference on robotics and biomimetics (ROBIO), pp 1653–1658. IEEE

Mechali O, Xu L, Wei M, Benkhaddra I, Guo F, Senouci A (2019) A rectified RRT* with efficient obstacles avoidance method for UAV in 3d environment. In: 2019 IEEE 9th annual international conference on CYBER technology in automation, control, and intelligent systems (CYBER), pp 480–485. IEEE

Bortoff SA (2000) Path planning for UAVs. In: Proceedings of the 2000 American control conference. ACC (IEEE Cat. No. 00CH36334), vol 1, pp 364–368. IEEE

Chen X, Li G, Chen X (2017) Path planning and cooperative control for multiple UAVs based on consistency theory and voronoi diagram. In: 2017 29th Chinese control and decision conference (CCDC), pp 881–886. IEEE

Baek J, Han SI, Han Y (2019) Energy-efficient UAV routing for wireless sensor networks. IEEE Trans Veh Technol 69(2):1741–1750

Feng X, Murray AT (2018) Allocation using a heterogeneous space voronoi diagram. J Geogr Syst 20(3):207–226

Chen X, Zhao M (2019) Collaborative path planning for multiple unmanned aerial vehicles to avoid sudden threats. In: 2019 Chinese automation congress (CAC), pp 2196–2201. IEE

Moon S, Oh E, Shim DH (2013) An integral framework of task assignment and path planning for multiple unmanned aerial vehicles in dynamic environments. J Intell Robot Syst 70(1-4):303–313

Qian X, Peng C, Nong C, Xiang Z (2015) Dynamic obstacle avoidance path planning of UAVs. In: 2015 34th Chinese control conference (CCC), pp 8860–8865. IEEE

Budiyanto A, Cahyadi A, Adji TB, Wahyunggoro O (2015) UAV obstacle avoidance using potential field under dynamic environment. In: 2015 international conference on control, electronics, renewable energy and communications (ICCEREC), pp 187–192. IEEE

Chen Y, Luo G, Mei Y, Jian-qiao Yu, Xiao-long S (2016) UAV path planning using artificial potential field method updated by optimal control theory. Int J Syst Sci 47(6):1407–1420

Article   MathSciNet   MATH   Google Scholar  

Liu Y, Zhao Y (2016) A virtual-waypoint based artificial potential field method for UAV path planning. In: 2016 IEEE Chinese guidance, navigation and control conference (CGNCC), pp 949–953. IEEE

Mac TT, Copot C, Hernandez A, De Keyser R (2016) Improved potential field method for unknown obstacle avoidance using UAV in indoor environment. In: 2016 IEEE 14th international symposium on applied machine intelligence and informatics (SAMI), pages 345–350. IEEE

Abeywickrama HV, Jayawickrama BA, He Y, Dutkiewicz E (2017) Algorithm for energy efficient inter-UAV collision avoidance. In: 2017 17th international symposium on communications and information technologies (ISCIT), pp 1–5. IEEE

Sun J, Tang J, Lao S (2017) Collision avoidance for cooperative UAVs with optimized artificial potential field algorithm. IEEE Access 5:18382–18390

Woods AC, La HM (2017) A novel potential field controller for use on aerial robots. IEEE Trans Syst Man Cybern 49(4):665–676

Zhiyang L, Tao J (2017) Route planning based on improved artificial potential field method. In: 2017 2nd Asia-Pacific conference on intelligent robot systems (ACIRS), pp 196–199. IEEE

Dai J, Wang Y, Wang C, Ying J, Zhai J (2018) Research on hierarchical potential field method of path planning for UAVs. In: 2018 2nd IEEE advanced information management, communicates, electronic and automation control conference (IMCEC), pp 529–535. IEEE

Bai W, Wu X, Xie Y, Wang Y, Zhao H, Chen K, Li Y, Hao Y (2018) A cooperative route planning method for multi-UAVs based-on the fusion of artificial potential field and b-spline interpolation. In 2018 37th Chinese control conference (CCC), pp 6733–6738. IEEE

Feng Y, Wu Y, Cao H, Sun J (2018) UAV formation and obstacle avoidance based on improved apf. In: 2018 10th international conference on modelling, identification and control (ICMIC), pp 1–6. IEEE

Yingkun Zhang (2018) Flight path planning of agriculture UAV based on improved artificial potential field method. In 2018 Chinese Control And Decision Conference (CCDC) , pages 1526–1530. IEEE

Abeywickrama HV, Jayawickrama BA, He Y, Dutkiewicz E (2018) Potential field based inter-UAV collision avoidance using virtual target relocation. In: 2018 IEEE 87th vehicular technology conference (VTC Spring), pp 1–5. IEEE

D’Amato E, Mattei M, Notaro I (2019) Bi-level flight path planning of UAV formations with collision avoidance. J Intell Robot Syst 93(1–2):193–211

D’Amato E, Notaro I, Blasi L, Mattei M (2019) Smooth path planning for fixed-wing aircraft in 3d environment using a layered essential visibility graph. In: 2019 international conference on unmanned aircraft systems (ICUAS), pp 9–18. IEEE

Maini Parikshit, Sujit PB (2016) Path planning for a UAV with kinematic constraints in the presence of polygonal obstacles. In 2016 international conference on unmanned aircraft systems (ICUAS) , pages 62–67. IEEE

Wang J, Zhang YF, Geng L, Fuh JYH, Teo SH (2015) A heuristic mission planning algorithm for heterogeneous tasks with heterogeneous UAVs. Unmanned Syst 3(03):205–219

Lavalle SM (1998) Rapidly-exploring random trees: a new tool for path planning. Technical report

Fortune S (1987) A sweepline algorithm for voronoi diagrams. Algorithmica 2(1):153–174

Khatib O (1986) Real-time obstacle avoidance for manipulators and mobile robots. In: Autonomous robot vehicles, pp 396–404. Springer

Welzl E (1985) Constructing the visibility graph for n-line segments in o (n2) time. Inf Process Lett 20(4):167–171

Dijkstra EW et al (1959) A note on two problems in connexion with graphs. 1 Numerische mathematik 1(1):269–271

Kavraki L, Latombe J-C (1994) Randomized preprocessing of configuration for fast path planning. In: Proceedings of the 1994 IEEE international conference on robotics and automation, pp 2138–2145. IEEE

Charnes A, Cooper WW (1959) Chance-constrained programming. Manag Sci 6(1):73–79

Kuffner JJ, LaValle SM (2000) RRT-connect: an efficient approach to single-query path planning. In: Proceedings 2000 ICRA. Millennium conference. IEEE international conference on robotics and automation. Symposia proceedings (Cat. No. 00CH37065), vol 2, pp 995–1001. IEEE

Tang HB, Sun ZQ (2005) Parameter adaptive RRT-goalbias algorithm. Dyn Contin Discret Impuls Syst Ser B 1:381–386

Google Scholar  

Yershova A, Jaillet L, Siméon T, LaValle SM (2005) Dynamic-domain RRTs: Efficient exploration by controlling the sampling domain. In: Proceedings of the 2005 IEEE international conference on robotics and automation, pp 3856–3861. IEEE

Karaman S, Frazzoli E (2011) Sampling-based algorithms for optimal motion planning. Int J Robot Res 30(7):846–894

Han X-A, Ma YC, Huang XL (2009) The cubic trigonometric bézier curve with two shape parameters. Appl Math Lett 22(2):226–231

Wei X, Fengyang D, Qingjie Z, Bing Z, Hongchang S (2015) A new fast consensus algorithm applied in rendezvous of multi-UAV. In: The 27th Chinese control and decision conference (2015 CCDC), pp 55–60. IEEE

He L, Pan J, Xu J (2011) Reducing data collection latency in wireless sensor networks with mobile elements. In: 2011 IEEE conference on computer communications workshops (INFOCOM WKSHPS), pp 572–577. IEEE

Mertens S (1996) Exhaustive search for low-autocorrelation binary sequences. J Phys A: Math Gen 29(18):L473

Sankar PV, Ferrari LA (1988) Simple algorithms and architectures for b-spline interpolation. IEEE Trans Pattern Anal Mach Intell 10(2):271–276

Geng L, Zhang YF, Wang J, Fuh JYH, Teo SH (2014) Cooperative mission planning with multiple UAVs in realistic environments. Unmanned Syst 2(01):73–86

Dong Z, Chen Z, Zhou R, Zhang R (2011) A hybrid approach of virtual force and a* search algorithm for UAV path re-planning. In: 2011 6th IEEE conference on industrial electronics and applications, pp 1140–1145. IEEE

Wang Z, Liu L, Long T, Yu C, Kou J (2014) Enhanced sparse a* search for UAV path planning using dubins path estimation. In: Proceedings of the 33rd Chinese control conference, pp 738–742. IEEE

Tianzhu R, Rui Z, Jie X, Zhuoning D (2016) Three-dimensional path planning of UAV based on an improved a* algorithm. In: 2016 IEEE Chinese guidance, navigation and control conference (CGNCC), pp 140–145. IEEE

Chengjun Z, Xiuyun M (2017) Spare a* search approach for UAV route planning. In: 2017 IEEE international conference on unmanned systems (ICUS), pp 413–417. IEEE

Chen T, Zhang G, Hu X, Xiao J (2018) Unmanned aerial vehicle route planning method based on a star algorithm. In: 2018 13th IEEE conference on industrial electronics and applications (ICIEA), pp 1510–1514. IEEE

Zhang G, Hsu L-T (2019) A new path planning algorithm using a gnss localization error map for UAVs in an urban area. J Intell Robot Syst 94(1):219–235

Primatesta S, Guglieri G, Rizzo A (2019) A risk-aware path planning strategy for UAVs in urban environments. J Intell Robot Syst 95(2):629–643

Mardani A, Chiaberge M, Giaccone P (2019) Communication-aware UAV path planning. IEEE. Access 7:52609–52621

Xueli W, Lei X, Zhen R, Xiaojing W (2020) Bi-directional adaptive a* algorithm toward optimal path planning for large-scale UAV under multi-constraints. IEEE Access 8:85431–85440

Zhang Z, Jian W, Dai J, He C (2020) A novel real-time penetration path planning algorithm for stealth UAV in 3d complex dynamic environment. IEEE Access 8:122757–122771

Lim D, Park J, Han D, Jang H, Park W, Lee D (2021) UAV path planning with derivative of the heuristic angle. Int J Aeronaut Space Sci 22(1):140–150

Pohl I (1970) Heuristic search viewed as path finding in a graph. Artif Intell 1(3–4):193–204

Zhang Z, Jian W, Dai J, He C (2022) Optimal path planning with modified a-star algorithm for stealth unmanned aerial vehicles in 3d network radar environment. Proc Inst Mech Eng G 236(1):72–81

Liu W, Zheng Z, Cai K-Y (2013) Bi-level programming based real-time path planning for unmanned aerial vehicles. Knowl-Based Syst 44:34–47

Kang M, Liu Y, Ren Y, Zhao Y, Zheng Z (2017) An empirical study on robustness of UAV path planning algorithms considering position uncertainty. In: 2017 12th international conference on intelligent systems and knowledge engineering (ISKE), pp 1–6. IEEE

Ahmed S, Mohamed A, Harras K, Kholief M, Mesbah S (2016) Energy efficient path planning techniques for UAV-based systems with space discretization. In: 2016 IEEE wireless communications and networking conference, pp 1–6. IEEE

da Silva A, da Silva AM, Motta TCF, Júnior Onofre T, Williams BC (2017) Heuristic and genetic algorithm approaches for UAV path planning under critical situation. Int J Artif Intell Tools 26(01):1760008

Freitas H, Faiçal BS, Vinicius CA, Ueyama J (2020) Use of UAVs for an efficient capsule distribution and smart path planning for biological pest control. Comput Electron Agric 173:105387

De Filippis L, Guglieri G, Quagliotti F (2012) Path planning strategies for UAVs in 3d environments. J Intell Robot Syst 65(1–4):247–264

Hart PE, Nilsson NJ, Raphael B (1968) A formal basis for the heuristic determination of minimum cost paths. IEEE Trans Syst Sci Cybern 4(2):100–107

Dong ZN, Chi P, Zhang RL, Chen ZJ (2009) The algorithms on three-dimension route plan based on virtual forces. J Syst Simul 20(S):387–392

Szczerba RJ, Galkowski P, Glicktein IS, Ternullo N (2000) Robust algorithm for real-time route planning. IEEE Trans Aerosp Electron Syst 36(3):869–878

Guglieri G, Lombardi A, Ristorto G (2015) Operation oriented path planning strategies for rpas. Am J Sci Technol 2(6):1–8

Song R, Liu Y, Bucknall R (2019) Smoothed a* algorithm for practical unmanned surface vehicle path planning. Appl Ocean Res 83:9–20

Afram A, Janabi-Sharifi F, Fung AS, Raahemifar K (2017) Artificial neural network (ann) based model predictive control (mpc) and optimization of hvac systems: A state of the art review and case study of a residential hvac system. Energy Build 141:96–113

Liu X, Deng R, Wang J, Wang X (2014) Costar: A d-star lite-based dynamic search algorithm for codon optimization. J Theor Biol 344:19–30

Marcotte P, Savard G (2005) Bilevel programming: a combinatorial perspective. In: Graph theory and combinatorial optimization, pp 191–217. Springer

Kim Y, Da-Wei G, Postlethwaite I (2008) Real-time path planning with limited information for autonomous unmanned air vehicles. Automatica 44(3):696–712

Zheng Z, Shanjie W, Liu W, Cai K-Y (2011) A feedback based cri approach to fuzzy reasoning. Appl Soft Comput 11(1):1241–1255

Schouwenaars T (2006) Safe trajectory planning of autonomous vehicles. PhD thesis, Massachusetts Institute of Technology

Stützle T, Dorigo M et al (1999) Aco algorithms for the traveling salesman problem. Evol Algorithms Eng Comput Sci 4:163–183

MATH   Google Scholar  

Voudouris C, Tsang E (1999) Guided local search and its application to the traveling salesman problem. Eur J Oper Res 113(2):469–499

Glover F (1989) Tabu search-part i. ORSA J Comput 1(3):190–206

Yi-Chen D, Zhang M-X, Ling H-F, Zheng Y-J (2019) Evolutionary planning of multi-UAV search for missing tourists. IEEE Access 7:73480–73492

Brintaki AN, Nikolos IK (2005) Coordinated UAV path planning using differential evolution. Oper Res Int Journal 5(3):487–502

Mittal S, Deb K (2007) Three-dimensional offline path planning for UAVs using multiobjective evolutionary algorithms. In: 2007 IEEE congress on evolutionary computation, pp 3195–3202. IEEE

Roberge V, Tarbouchi M, Labonté G (2012) Comparison of parallel genetic algorithm and particle swarm optimization for real-time UAV path planning. IEEE Trans Industr Inf 9(1):132–141

Zhang X, Duan H (2015) An improved constrained differential evolution algorithm for unmanned aerial vehicle global route planning. Appl Soft Comput 26:270–284

Li J, Deng G, Luo C, Lin Q, Yan Q, Ming Z (2016) A hybrid path planning method in unmanned air/ground vehicle (UAV/ugv) cooperative systems. IEEE Trans Veh Technol 65(12):9585–9596

Adhikari D, Kim E, Reza H (2017) A fuzzy adaptive differential evolution for multi-objective 3d UAV path optimization. In: 2017 IEEE congress on evolutionary computation (CEC), pp 2258–2265. IEEE

Fu Z, Yu J, Xie G, Chen Y, Mao Y (2018) A heuristic evolutionary algorithm of UAV path planning. In: Wireless communications and mobile computing

Dai R, Fotedar S, Radmanesh M, Kumar M (2018) Quality-aware UAV coverage and path planning in geometrically complex environments. Ad Hoc Netw 73:95–105

Xiao C, Zou Y, Li S (2019) UAV multiple dynamic objects path planning in air-ground coordination using receding horizon strategy. In: 2019 3rd international symposium on autonomous systems (ISAS), pp 335–340. IEEE

Yang Q, Liu J, Li L (2020) Path planning of UAVs under dynamic environment based on a hierarchical recursive multiagent genetic algorithm. In: 2020 IEEE congress on evolutionary computation (CEC), pp 1–8. IEEE

Hayat S, Yanmaz E, Bettstetter C, Brown TX (2020) Multi-objective drone path planning for search and rescue with quality-of-service requirements. Auton Robot 44(7):1183–1198

Chawra VK, Gupta GP (2020) Multiple UAV path-planning for data collection in cluster-based wireless sensor network. In: 2020 first international conference on power, control and computing technologies (ICPC2T), pp 194–198. IEEE

Sujit PB, Beard R (2009) Multiple UAV path planning using anytime algorithms. In: 2009 American control conference, pp 2978–2983. IEEE

Zhang C, Zhen Z, Wang D, Li M (2010) UAV path planning method based on ant colony optimization. In: 2010 Chinese control and decision conference, pp 3790–3792. IEEE

Yangguang F, Ding M, Zhou C (2011) Phase angle-encoded and quantum-behaved particle swarm optimization applied to three-dimensional route planning for UAV. IEEE Trans Syst Man Cybern Part A 42(2):511–526

Liu Y, Zhang X, Guan X, Delahaye D (2016) Adaptive sensitivity decision based path planning algorithm for unmanned aerial vehicle with improved particle swarm optimization. Aerosp Sci Technol 58:92–102

Cekmez U, Ozsiginan M, Sahingoz OK (2016) Multi colony ant optimization for UAV path planning with obstacle avoidance. In: 2016 international conference on unmanned aircraft systems (ICUAS), pp 47–52. IEEE

Yao P, Wang H (2017) Dynamic adaptive ant lion optimizer applied to route planning for unmanned aerial vehicle. Soft Comput 21(18):5475–5488

Wu K, Xi T, Wang H (2017) Real-time three-dimensional smooth path planning for unmanned aerial vehicles in completely unknown cluttered environments. In: TENCON 2017-2017 IEEE Region 10 Conference. IEEE

Yong BC, Mei YSY, Xiao-Long JQS, Nuo X (2017) Three-dimensional unmanned aerial vehicle path planning using modified wolf pack search algorithm. Neurocomputing 266:445–457

Huang C, Fei J (2018) UAV path planning based on particle swarm optimization with global best path competition. Int J Pattern Recognit Artif Intell 32(06):1859008

Tian G, Zhang L, Bai X, Wang B (2018) Real-time dynamic track planning of multi-UAV formation based on improved artificial bee colony algorithm. In: 2018 37th Chinese control conference (CCC), pp 10055–10060. IEEE

Jianfa W, Wang H, Li N, Peng Y, Yu H, Hemeng Y (2018) Path planning for solar-powered UAV in urban environment. Neurocomputing 275:2055–2065

Zhang X, Xingyang L, Jia S, Li X (2018) A novel phase angle-encoded fruit fly optimization algorithm with mutation adaptation mechanism applied to UAV path planning. Appl Soft Comput 70:371–388

Pandey P, Shukla A, Tiwari R (2018) Three-dimensional path planning for unmanned aerial vehicles using glowworm swarm optimization algorithm. Int J Syst Assur Eng Manag 9(4):836–852

Goel U, Varshney S, Jain A, Maheshwari S, Shukla A (2018) Three dimensional path planning for UAVs in dynamic environment using glow-worm swarm optimization. Procedia Comput Sci 133:230–239

Zhang D, Duan H (2018) Social-class pigeon-inspired optimization and time stamp segmentation for multi-UAV cooperative path planning. Neurocomputing 313:229–246

Sun X, Pan S, Cai C, Chen Y, Chen J (2018) Unmanned aerial vehicle path planning based on improved intelligent water drop algorithm. In: 2018 eighth international conference on instrumentation & measurement, computer, communication and control (IMCCC), pp 867–872. IEEE

Muliawan IW, Ma’Sum MA, Alfiany N, Jatmiko W (2019) UAV path planning for autonomous spraying task at salak plantation based on the severity of plant disease. In: 2019 IEEE international conference on cybernetics and computational intelligence (CyberneticsCom), pp 109–113. IEEE

Dewangan RK, Shukla A, Godfrey WW (2019) Three dimensional path planning using grey wolf optimizer for UAVs. Appl Intell 49(6):2201–2217

Cai Y, Zhao H, Li M, Huang H (2019) 3d real-time path planning based on cognitive behavior optimization algorithm for UAV with tlp model. Clust Comput 22(2):5089–5098

Zhang C, Chenxi H, Feng J, Liu Z, Zhou Y, Zhang Z (2019) A self-heuristic ant-based method for path planning of unmanned aerial vehicle in complex 3-d space with dense u-type obstacles. IEEE Access 7:150775–150791

Wang X, Zhao H, Han T, Zhou H, Li C (2019) A grey wolf optimizer using gaussian estimation of distribution and its application in the multi-UAV multi-target urban tracking problem. Appl Soft Comput 78:240–260

Zhang S, Luo Q, Zhou Y (2017) Hybrid grey wolf optimizer using elite opposition-based learning strategy and simplex method. Int J Comput Intell Appl 16(02):1750012

Heidari AA, Pahlavani P (2017) An efficient modified grey wolf optimizer with lévy flight for optimization tasks. Appl Soft Comput 60:115–134

Gupta S, Deep K (2019) A novel random walk grey wolf optimizer. Swarm Evol Comput 44:101–112

Viktorin A, Pluhacek M, Senkerik R (2016) Success-history based adaptive differential evolution algorithm with multi-chaotic framework for parent selection performance on cec2014 benchmark set. In: 2016 IEEE congress on evolutionary computation (CEC), pp 4797–4803. IEEE

Chen X, Tianfield H, Mei C, Wenli D, Liu G (2017) Biogeography-based learning particle swarm optimization. Soft Comput 21(24):7519–7541

Ghambari S, Rahati A (2018) An improved artificial bee colony algorithm and its application to reliability optimization problems. Appl Soft Comput 62:736–767

Liu C, Fan L (2016) A hybrid evolutionary algorithm based on tissue membrane systems and cma-es for solving numerical optimization problems. Knowl-Based Syst 105:38–47

Yue L, Chen H (2019) Unmanned vehicle path planning using a novel ant colony algorithm. EURASIP J Wirel Commun Netw 2019(1):136

Li B, Qi X, Baoguo Yu, Liu L (2019) Trajectory planning for UAV based on improved aco algorithm. IEEE Access 8:2995–3006

Luo Q, Wang H, Zheng Y, He J (2020) Research on path planning of mobile robot based on improved ant colony algorithm. Neural Comput Appl 32(6):1555–1566

Shikai Shao Yu, Peng CH, Yun D (2020) Efficient path planning for UAV formation via comprehensively improved particle swarm optimization. ISA Trans 97:415–430

Tian D, Shi Z (2018) Mpso: Modified particle swarm optimization and its applications. Swarm Evol Comput 41:49–68

Mohamed E, Alaa T (2018) Hassanien Aboul Ella (2018) Bezier curve based path planning in a dynamic field using modified genetic algorithm. J Comput Sci 25:339–350

Yang LIU, Zhang X, Zhang Yu, Xiangmin GUAN (2019) Collision free 4d path planning for multiple UAVs based on spatial refined voting mechanism and pso approach. Chin J Aeronaut 32(6):1504–1519

Mahanti A, Bagchi A (1985) And/or graph heuristic search methods. J ACM (JACM) 32(1):28–51

Yang Z, Fang Z, Li P (2016) Bio-inspired collision-free 4d trajectory generation for UAVs using tau strategy. J Bionic Eng 13(1):84–97

Yang L, Guo J, Liu Y (2020) Three-dimensional UAV cooperative path planning based on the mp-cgwo algorithm. Int J Innov Comput Inf Control 16:991–1006

Phung MD, Phuc Ha Q (2021) Safety-enhanced UAV path planning with spherical vector-based particle swarm optimization. Appl Soft Comput 107:107376

Fu Y, Ding M, Zhou C, Cai C, Sun Y (2009) Path planning for UAV based on quantum-behaved particle swarm optimization. In: MIPPR 2009: medical imaging, parallel processing of images, and optimization techniques, vol 7497, p 74970B. International Society for Optics and Photonics

Wei-Min Z, Shao-Jun L, Feng Q (2008) \(\theta\) -pso: a new strategy of particle swarm optimization. J Zhejiang Univ Sci A 9(6):786–790

Zhou X, Gao F, Fang X, Lan Z (2021) Improved bat algorithm for UAV path planning in three-dimensional space. IEEE Access 9:20100–20116

Pan J-S, Dao T-K, Kuo M-Y, Horng, M-F, et al. (2014) Hybrid bat algorithm with artificial bee colony. In: Intelligent data analysis and its applications, vol II, pp 45–55. Springer,

Wang G, Guo L, Duan H, Liu L, Wang H (2012) A bat algorithm with mutation for ucav path planning. The Sci World J

Hu ZH (2011) Research on some key techniques of UAV path planning based on intelligent optimization algorithm. Nanjing University of Aeronautics and Astronautics, Nanjing, China

Lei L, Shiru Q (2012) Path planning for unmanned air vehicles using an improved artificial bee colony algorithm. In: Proceedings of the 31st Chinese control conference, pp 2486–2491. IEEE

Chen Y, Jianqiao Yu, Mei Y, Wang Y, Xiaolong S (2016) Modified central force optimization (mcfo) algorithm for 3d UAV path planning. Neurocomputing 171:878–888

Formato RA (2008) Central force optimization: a new nature inspired computational framework for multidimensional search and optimization. In: Nature inspired cooperative strategies for optimization (NICSO 2007), pp 221–238. Springer

Zabinsky ZB, et al (2009) Random search algorithms. Department of Industrial and Systems Engineering, University of Washington, USA

Kumar P, Garg S, Singh A, Batra S, Kumar N, You I (2018) Mvo-based 2-d path planning scheme for providing quality of service in UAV environment. IEEE Internet Things J 5(3):1698–1707

Mirjalili S (2016) Dragonfly algorithm: a new meta-heuristic optimization technique for solving single-objective, discrete, and multi-objective problems. Neural Comput Appl 27(4):1053–1073

Mirjalili S (2015) Moth-flame optimization algorithm: a novel nature-inspired heuristic paradigm. Knowl-Based Syst 89:228–249

Jain G, Yadav G, Prakash D, Shukla A, Tiwari R (2019) Mvo-based path planning scheme with coordination of UAVs in 3-d environment. J Comput Sci 37:101016

Yaoming ZHOU, Yu SU, Anhuan XIE, Lingyu KONG (2021) A newly bio-inspired path planning algorithm for autonomous obstacle avoidance of UAV. Chin J Aeronaut

Chen Y, Pi D, Yue X (2021) Neighborhood global learning based flower pollination algorithm and its application to unmanned aerial vehicle path planning. Expert Syst Appl 170:114505

Yang X-S (2012) Flower pollination algorithm for global optimization. In: International conference on unconventional computing and natural computation, pp 240–249. Springer

Singh D, Singh U, Salgotra R (2018) An extended version of flower pollination algorithm. Arab J Sci Eng 43(12)

Rao R (2016) Jaya: a simple and new optimization algorithm for solving constrained and unconstrained optimization problems. Int J Ind Eng Comput 7(1):19–34

Rashedi E, Nezamabadi-Pour H, Saryazdi S (2009) Gsa: a gravitational search algorithm. Inf Sci 179(13):2232–2248

Askarzadeh A, Rezazadeh A (2011) An innovative global harmony search algorithm for parameter identification of a pem fuel cell model. IEEE Trans Ind Electron 59(9):3473–3480

Mirjalili S, Zaiton MHS (2010) A new hybrid psogsa algorithm for function optimization. In: 2010 international conference on computer and information application, pp 374–377. IEEE

Alihodzic A (2016) Fireworks algorithm with new feasibility-rules in solving UAV path planning. In: 2016 3rd international conference on soft computing & machine intelligence (ISCMI), pp 53–57. IEEE

Yang X-S (2010) A new metaheuristic bat-inspired algorithm. In: Nature inspired cooperative strategies for optimization (NICSO 2010), pp 65–74. Springer

Gandomi AH, Yang X-S, Alavi AH (2013) Cuckoo search algorithm: a metaheuristic approach to solve structural optimization problems. Eng Comput 29(1):17–35

Wu J, Yi J, Gao L, Li X (2017) Cooperative path planning of multiple UAVs based on ph curves and harmony search algorithm. In: 2017 IEEE 21St international conference on computer supported cooperative work in design (CSCWD), pp 540–544. IEEE

Binol H, Bulut E, Akkaya K, Guvenc I (2018) Time optimal multi-UAV path planning for gathering its data from roadside units. In: 2018 IEEE 88th Vehicular Technol Conf (VTC-Fall), pp 1–5. IEEE

Nawaz M, Emory Enscore E Jr, Ham I (1983) A heuristic algorithm for the m-machine, n-job flow-shop sequencing problem. Omega 11(1):91–95

Liu H, Zhang P, Bin H, Moore P (2015) A novel approach to task assignment in a cooperative multi-agent design system. Appl Intell 43(1):162–175

Poongothai M, Rajeswari A (2016) A hybrid ant colony tabu search algorithm for solving task assignment problem in heterogeneous processors. In: Proceedings of the international conference on soft computing systems, pp 1–11. Springer

Abdullahi M, Ngadi MA et al (2016) Symbiotic organism search optimization based task scheduling in cloud computing environment. Futur Gener Comput Syst 56:640–650

Bourgault F, Furukawa T, Durrant-Whyte HF (2003) Optimal search for a lost target in a bayesian world. In: Field and service robotics, pp 209–222. Springer

Waharte S, Trigoni N (2010) Supporting search and rescue operations with UAVs. In: 2010 international conference on emerging security technologies, pp 142–147. IEEE

Lo C-C, Yu S-W (2015) A two-phased evolutionary approach for intelligent task assignment & scheduling. In: 2015 11th international conference on natural computation (ICNC), pp 1092–1097. IEEE

Yao P, Wang H, Ji H (2017) Gaussian mixture model and receding horizon control for multiple UAV search in complex environment. Nonlinear Dyn 88(2):903–919

Storn R, Price K (1997) Differential evolution-a simple and efficient heuristic for global optimization over continuous spaces. J Global Optim 11(4):341–359

Deb K, Pratap A, Agarwal S, Meyarivan TAMT (2002) A fast and elitist multiobjective genetic algorithm: Nsga-ii. IEEE Trans Evol Comput 6(2):182–197

Zadeh LA (1996) Fuzzy sets. In: Fuzzy sets, fuzzy logic, and fuzzy systems: selected papers by Lotfi A Zadeh, pp 394–432. World Scientific

Zhao J, Wang L (2011) Center based genetic algorithm and its application to the stiffness equivalence of the aircraft wing. Expert Syst Appl 38(5):6254–6261

Sun J, Feng B, Xu W (2004) Particle swarm optimization with particles having quantum behavior. In: Proceedings of the 2004 congress on evolutionary computation (IEEE Cat. No. 04TH8753), vol 1, pp 325–331. IEEE

Yang X-S (2009) Firefly algorithms for multimodal optimization. In: International symposium on stochastic algorithms, pp 169–178. Springer,

Karaboga D (2005) An idea based on honey bee swarm for numerical optimization. Technical report, Technical report-tr06, Erciyes university, engineering faculty, computer

Mirjalili S (2015) The ant lion optimizer. Adv Eng Softw 83:80–98

He S, Wu QH, Wen JY, Saunders JR, Paton RC (2004) A particle swarm optimizer with passive congregation. Biosystems 78(1–3):135–147

Clerc M, Kennedy J (2002) The particle swarm-explosion, stability, and convergence in a multidimensional complex space. IEEE Trans Evol Comput 6(1):58–73

Mirjalili S, Lewis A (2016) The whale optimization algorithm. Adv Eng Softw 95:51–67

Krishnanand KN, Ghose D (2009) Glowworm swarm optimization for simultaneous capture of multiple local optima of multimodal functions. Swarm Intell 3(2):87–124

Shah-Hosseini H (2009) The intelligent water drops algorithm: a nature-inspired swarm-based optimization algorithm. Int J Bio-inspired Comput 1(1–2):71–79

Zhu W, Duan H (2014) Chaotic predator-prey biogeography-based optimization approach for ucav path planning. Aerosp Sci Technol 32(1):153–161

Mirjalili S (2016) Sca: a sine cosine algorithm for solving optimization problems. Knowl-Based Syst 96:120–133

Li M, Zhao H, Weng X, Han T (2016) Cognitive behavior optimization algorithm for solving optimization problems. Appl Soft Comput 39:199–222

Nikolos IK, Zografos ES, Brintaki AN (2007) UAV path planning using evolutionary algorithms. In: Innovations in intelligent machines-1, pp 77–111. Springer

Wu J, Shin S, Kim C-G, Kim S-D (2017) Effective lazy training method for deep q-network in obstacle avoidance and path planning. In: 2017 IEEE international conference on systems, man, and cybernetics (SMC), pp 1799–1804. IEEE

Yan C, Xiang X, Wang C (2019) Towards real-time path planning through deep reinforcement learning for a UAV in dynamic environments. J Intell Robot Syst 1–13

Shiri H, Park J, Bennis M (2020) Remote UAV online path planning via neural network based opportunistic control. IEEE Wirel Commun Lett

Chen Y, Zu W, Fan G, Chang H (2014) Unmanned aircraft vehicle path planning based on svm algorithm. In: Foundations and practical applications of cognitive systems and information processing, pp 705–714. Springer

Yoo J, Kim HJ, Johansson KH (2017) Path planning for remotely controlled UAVs using gaussian process filter. In: 2017 17th international conference on control, automation and systems (ICCAS), pp 477–482. IEEE

Carron A, Todescato M, Carli R, Schenato L, Pillonetto G (2016) Machine learning meets kalman filtering. In: 2016 IEEE 55th conference on decision and control (CDC), pp 4594–4599. IEEE

Koo KM, Lee KR, Cho SR, Joe I (2018) A UAV path planning method using polynomial regression for remote sensor data collection. In: Advances in computer science and ubiquitous computing, pp 428–433. Springer

Radmanesh R, Kumar M, French D, Casbeer D (2020) Towards a pde-based large-scale decentralized solution for path planning of UAVs in shared airspace. Aerosp Sci Technol pp 105965

Ragi S, Chong EKP (2013) UAV path planning in a dynamic environment via partially observable markov decision process. IEEE Trans Aerosp Electron Syst 49(4):2397–2412

Zhang B, Liu W, Mao Z, Liu J, Shen L (2014) Cooperative and geometric learning algorithm (cgla) for path planning of UAVs with limited information. Automatica 50(3):809–820

Shan-Jie W, Zheng Z, Cai K (2011) Real-time path planning for unmanned aerial vehicles using behavior coordination and virtual goal. Control Theory Appl 28(1):131–136

Watkins CJCH, Dayan P (1992) Q-learning. Mach Learn 8(3–4):279–292

Yijing Z, Zheng Z, Xiaoyi Z, Yang L (2017) Q learning algorithm based UAV path learning and obstacle avoidence approach. In: 2017 36th Chinese control conference (CCC), pp 3397–3402. IEEE

Challita U, Saad W, Bettstetter C (2018) Deep reinforcement learning for interference-aware path planning of cellular-connected UAVs. In 2018 IEEE international conference on communications (ICC), pp 1–7. IEEE

Luo W, Tang Q, Fu C, Eberhard P (2018) Deep-sarsa based multi-UAV path planning and obstacle avoidance in a dynamic environment. In: International conference on sensing and imaging, pp 102–111. Springer

Yan C, Xiang X (2018) A path planning algorithm for UAV based on improved q-learning. In: 2018 2nd international conference on robotics and automation sciences (ICRAS), pp 1–5. IEEE

Zhang T, Huo X, Chen S, Yang B, Zhang G (2018) Hybrid path planning of a quadrotor UAV based on q-learning algorithm. In: 2018 37th Chinese control conference (CCC), pp 5415–5419. IEEE

Xie R, Meng Z, Zhou Y, Ma Y, Zhe W (2020) Heuristic q-learning based on experience replay for three-dimensional path planning of the unmanned aerial vehicle. Sci Prog 103(1):0036850419879024

Xie R, Meng Z, Wang L, Li H, Wang K, Zhe W (2021) Unmanned aerial vehicle path planning algorithm based on deep reinforcement learning in large-scale and dynamic environments. IEEE Access 9:24884–24900

Mnih V, Kavukcuoglu K, Silver D, Graves A, Antonoglou I, Wierstra D, Riedmiller M (2013) Playing atari with deep reinforcement learning. arXiv:1312.5602

Hausknecht M, Stone P (2015) Deep recurrent q-learning for partially observable mdps. In: 2015 aaai fall symposium series

Cui Z, Wang Y (2021) UAV path planning based on multi-layer reinforcement learning technique. IEEE Access 9:59486–59497

Pierre DM, Zakaria N, Pal AJ (2012) Self-organizing map approach to determining compromised solutions for multi-objective UAV path planning. In: 2012 12th international conference on control automation robotics and vision (ICARCV), pp 995–1000. IEEE

Choi Y, Jimenez H, Mavris DN (2017) Two-layer obstacle collision avoidance with machine learning for more energy-efficient unmanned aircraft trajectories. Robot Auton Syst 98:158–173

Ester M, Kriegel H-P, Sander J, Xiaowei X et al (1996) A density-based algorithm for discovering clusters in large spatial databases with noise. In Kdd 96:226–231

Mnih V, Kavukcuoglu K, Silver D, Rusu AA, Veness J, Bellemare MG, Graves A, Riedmiller M, Fidjeland AK, Ostrovski G et al (2015) Human-level control through deep reinforcement learning. Nature 518(7540):529–533

Chen X, Chen X (2014) The UAV dynamic path planning algorithm research based on voronoi diagram. In: The 26th chinese control and decision conference (2014 ccdc), pp 1069–1071. IEEE

Zhang D, Xu Y, Yao X (2018) An improved path planning algorithm for unmanned aerial vehicle based on RRT-connect. In: 2018 37th Chinese control conference (CCC), pp 4854–4858. IEEE

Wang H, Sun Z, Li D, Jin Q (2019) An improved RRT based 3-d path planning algorithm for UAV. In: 2019 Chinese control and decision conference (CCDC), pp 5514–5519. IEEE

Shen Hong, Li Ping (2020) Unmanned aerial vehicle (UAV) path planning based on improved pre-planning artificial potential field method. In 2020 Chinese Control And Decision Conference (CCDC) , pages 2727–2732. IEEE

Debnath SK, Omar R, Bagchi S, Nafea M, Naha RK, Sabudin EN (2020) Energy efficient elliptical concave visibility graph algorithm for unmanned aerial vehicle in an obstacle-rich environment. In: 2020 IEEE international conference on automatic control and intelligent systems (I2CACIS), pp 129–134. IEEE

Latip NBA, Omar R, Debnath SK (2017) Optimal path planning using equilateral spaces oriented visibility graph method. Int J Electr Comput Eng 7(6):3046

Chandler P, Rasmussen S, Pachter M (2000) UAV cooperative path planning. In AIAA guidance, navigation, and control conference and exhibit, p 4370

Yan F, Zhuang Y, Xiao J (2012) 3d prm based real-time path planning for UAV in complex environment. In: 2012 IEEE international conference on robotics and biomimetics (ROBIO), pp 1135–1140. IEEE

Xue Qian, Cheng Peng, Cheng Nong (2014) Offline path planning and online replanning of UAVs in complex terrain. In Proceedings of 2014 IEEE Chinese Guidance, Navigation and Control Conference , pages 2287–2292. IEEE

Ahmad Z, Ullah F, Tran C, Lee S (2017) Efficient energy flight path planning algorithm using 3-d visibility roadmap for small unmanned aerial vehicle. Int J Aerosp Eng

Naazare M, Ramos D, Wildt J, Schulz D (2019) Application of graph-based path planning for UAVs to avoid restricted areas. In: 2019 IEEE international symposium on safety, security, and rescue robotics (SSRR), pp 139–144. IEEE

Yaohong Q, Zhang Y, Zhang Y (2018) A global path planning algorithm for fixed-wing UAVs. J Intell Robot Syst 91(3–4):691–707

Pehlivanoglu YV (2012) A new vibrational genetic algorithm enhanced with a voronoi diagram for path planning of autonomous UAV. Aerosp Sci Technol 16(1):47–55

Pehlivanoglu YV, Baysal O, Hacioglu A (2007) Path planning for autonomous UAV via vibrational genetic algorithm. Aircraft Eng Aerosp Technol

Michalewicz Z, Michalewicz Z (1996) Genetic algorithms+ data structures= evolution programs. Springer, New York

Book   MATH   Google Scholar  

da Arantes M, da Arantes J, Toledo CFM, Williams BC (2016) A hybrid multi-population genetic algorithm for UAV path planning. In: Proceedings of the genetic and evolutionary computation conference 2016, pp 853–860. ACM

Blackmore L, Ono M, Williams BC (2011) Chance-constrained optimal path planning with obstacles. IEEE Trans Rob 27(6):1080–1094

Bliek1ú C, Bonami P, Lodi A (2014) Solving mixed-integer quadratic programming problems with ibm-cplex: a progress report. In: Proceedings of the twenty-sixth RAMP symposium, pp 16–17

Girija S, Joshi A (2019) Fast hybrid pso-apf algorithm for path planning in obstacle rich environment. IFAC-PapersOnLine 52(29):25–30

Roberge V, Tarbouchi M, Allaire F (2014) Parallel hybrid metaheuristic on shared memory system for real-time UAV path planning. Int J Comput Intell Appl 13(02):1450008

Ghambari S, Idoumghar L, Jourdan L, Lepagnot J (2019) An improved tlbo algorithm for solving UAV path planning problem. In: 2019 IEEE symposium series on computational intelligence (SSCI), pp 2261–2268. IEEE

Rao RV, Savsani VJ, Vakharia DP (2011) Teaching–learning-based optimization: a novel method for constrained mechanical design optimization problems. Comput Aided Des 43(3):303–315

Ali ZA, Zhangang H, Zhengru D (2020) Path planning of multiple UAVs using mmaco and de algorithm in dynamic environment. Meas Control 0020294020915727

Ge F, Li K, Han Y, Xu W, et al (2020) Path planning of UAV for oilfield inspections in a three-dimensional dynamic environment with moving obstacles based on an improved pigeon-inspired optimization algorithm. Appl Intell 1–18

Yan Y, Liang Y, Zhang H, Zhang W, Feng H, Wang B, Liao Q (2019) A two-stage optimization method for unmanned aerial vehicle inspection of an oil and gas pipeline network. Pet Sci 16(2):458–468

Phung MD, Quach CH, Dinh TH, Ha Q (2017) Enhanced discrete particle swarm optimization path planning for UAV vision-based surface inspection. Autom Constr 81:25–33

Wang G-G, Chu HCE, Mirjalili S (2016) Three-dimensional path planning for ucav using an improved bat algorithm. Aerosp Sci Technol 49:231–238

Zhang B, Duan H (2015) Three-dimensional path planning for uninhabited combat aerial vehicle based on predator-prey pigeon-inspired optimization in dynamic environment. IEEE/ACM Trans Comput Biol Bioinf 14(1):97–107

Das PK, Behera HS, Panigrahi BK (2016) A hybridization of an improved particle swarm optimization and gravitational search algorithm for multi-robot path planning. Swarm Evol Comput 28:14–28

Zhang T, Duan H (2017) A modified consensus algorithm for multi-UAV formations based on pigeon-inspired optimization with a slow diving strategy. J Intell Syst (in China) 12(4):570–581

Qu Chengzhi, Gai Wendong, Zhang Jing, Zhong Maiying (2020) A novel hybrid grey wolf optimizer algorithm for unmanned aerial vehicle (UAV) path planning. Knowledge-Based Systems, pp 105530

Van Laarhoven Peter JM, Aarts Emile HL (1987) Simulated annealing. In: Simulated annealing: theory and applications, pp 7–15. Springer

Cheng M-Y, Prayogo D (2014) Symbiotic organisms search: a new metaheuristic optimization algorithm. Comput Struct 139:98–112

Chengzhi Q, Gai W, Zhong M, Zhang J (2020) A novel reinforcement learning based grey wolf optimizer algorithm for unmanned aerial vehicles (UAVs) path planning. Appl Soft Comput 89:106099

Long W, Jiao J, Liang X, Tang M (2018) An exploration-enhanced grey wolf optimizer to solve high-dimensional numerical optimization. Eng Appl Artif Intell 68:63–80

Long W, Jiao J, Liang X, Tang M (2018) Inspired grey wolf optimizer for solving large-scale function optimization problems. Appl Math Model 60:112–126

Kumar V, Kumar D (2017) An astrophysics-inspired grey wolf algorithm for numerical optimization and its application to engineering design problems. Adv Eng Softw 112:231–254

Pan Y, Yang Y, Li W (2021) A deep learning trained by genetic algorithm to improve the efficiency of path planning for data collection with multi-UAV. IEEE Access 9:7994–8005

Mirjalili S, Mirjalili SM, Lewis A (2014) Grey wolf optimizer. Adv Eng Softw 69:46–61

Download references

Acknowledgements

This work is supported by the Directorate General for Scientific Research and Technological Development (DG-RSDT) of Algeria; and the “ADI 2021” project funded by the IDEX Paris-Saclay, ANR-11-IDEX-0003-02.

Author information

Authors and affiliations.

Laboratoire Ingénierie des Systèmes et Télécommunications, Université M’Hamed Bougara, Avenue de l’Indépendence, 35000, Boumerdes, Algeria

Amylia Ait Saadi & Yassine Meraihi

LISV Laboratory, University of Paris-Saclay, 10-12 Avenue of Europe, 78140, Velizy, France

Amylia Ait Saadi & Amar Ramdane-Cherif

ECE Paris School of Engineering, 37 quai de Grenelle, 75015, Paris, France

Assia Soukane

Laboratoire de Méthodes de Conception de Systèmes, Ecole nationale Supérieure d’Informatique, Algiers, Algeria

Asma Benmessaoud Gabis

Centre for Artificial Intelligence Research and Optimisation, Torrens University Australia, Fortitude Valley, Brisbane, Fortitude Valley, QLD, 4006, Australia

Seyedali Mirjalili

YFL (Yonsei Frontier Lab), Yonsei University, Seoul, Korea

You can also search for this author in PubMed   Google Scholar

Corresponding author

Correspondence to Yassine Meraihi .

Ethics declarations

Conflict of interest.

The authors declare that there is no conflict of interest with any person(s) or Organization(s).

Additional information

Publisher's note.

Springer Nature remains neutral with regard to jurisdictional claims in published maps and institutional affiliations.

A: Appendix

In the present appendix, we gather in a table the set of acronyms used in this paper and their meanings.

Acronym

Explanation

ABC

Artificial Bee Colony

ACO

Ant Colony Optimization

AGASA

Self Adaptive Genetic Simulated Annealing algorithm

APF

Artificial Potential Field

APF-IRP

Artificial Potential Field Improved Rolling Plan

AGOA

Adaptive Grasshopper Optimization Algorithm

aHJB

Hamilton Jacobi Bellman

ALO

Ant Lion Optimizer

ARE

Adaptive and Random Exploration

A*

A-Star

AS-N

Ant Colony Optimization with punitive measures

AT-PP

Average Throughput Path planning

ASTS

Ant System Tabu Search

BA

Bat Algorithm

BAA*

Bidirectional Adaptive A-star

BBO

Biogeography Based Optimization

BLP

Bi-Level Programming

BS

Base Station

CBGA

Center Based Genetic Algorithm

CBPSO

Chaos Based initialization Particle Swarm Optimization

CC-RRT

Chance Constraint Rapidly-exploring Random Tree

CFO

Central Force Optimization

CGLA

Cooperative and Geometric Learning Algorithm

CIPSO

Comprehensively Particle Swarm Optimization

CPSO

Constrained Particle Swarm Optimization

CS

Cuckoo Search

DA

Dragonfly Algorithm

DAALO

Dynamic Adaptive Ant Lion Optimizer

DBSCAN

Density Based Spatial Clustering of Application with Noise

DDRRT

Dynamic Domain Rapidly-exploring Random Tree

DE

Differential Evolution

Deep RL ESN

Deep Reinforcement Learning Echo State Network

Deep Sarsa

Deep State action reward state action

DELC

Differential Evolution with Level Comparison

DPSO

Discrete Particle Swarm Optimization

DQN

Deep Q Network

DRL

Deep Reinforcement Learning

D3QN

Dueling Double Deep Q Networks

Dubins SAS

Dubins Sparse A-Star

EC VG

Elliptical Concave Visibility Graph

\(\epsilon\)DE

Constrained Differential Evolution

EEGWO

Exploration Enhanced Grey Wolf Optimizer

ESOVG

Equilateral Space Oriented Visibility Graph

ePFC

Extended Potential Field Controller

EPF-RRT

Environmental Potential Field Rapidly-exploring Random Tree

FA

Firefly Algorithm

FA-DE

Fuzzy Adaptive Differential Evolution

FBCRI

Feedback Based CRI

FDFR

First Detect First Reserve

FOA

Fruit fly Optimization Algorithm

FVF

Fuzzy Virtual Force

FWA

Firework Algorithm

GA

Genetic Algorithm

GA-LRO

Genetic Algorithm-Local Rolling Optimization

GBPSO

Global Best Particle Swarm Optimization

GEDGWO

Gaussian Estimation of Distribution Grey Wolf Optimizer

GH

Greedy Heuristic

GLS

Guided Local Search

GNSS

Global Navigation Satellite System

GP

Gaussian Process

GP-RRT

Gaussian Process Rapidly-exploring Random Tree

GSO

Glowworm Swarm Optimization

GTSP

Generalized Traveling Salesman Problem

GWO

Grey Wolf Optimizer

HDDRRT

Heuristic Dynamic Domain Rapidly-exploring Random Tree

HGA

Hybrid Genetic Algorithm

HPF

Hierarchical Potential Field

HR-MAGA

Hierarchical Recursive Multi Agent Genetic Algorithm

HSGWO-MSOS

Hybrid Simplified Grey Wolf Optimizer-Modified Symbiotic Organism Search

HVFA

Hybrid Virtual Force A* search

IABC

Improved Artificial Bee Colony

IBA

Intelligent BAT Algorithm

ICA

Imperialist Competitive Algorithm

IFFO

Improved Fruit fly Optimization

IGWO

Improved Grey Wolf Optimizer

IITD

Improved Intelligent Water Drop algorithm

ITD

Intelligent Water Drop algorithm

IPS

Improved Path Smoothing

IRRT

Improved Rapidly-exploring Random Tree

IRRT*

Informed Rapidly-exploring Random Tree-Star

IWOA

Improved Whale Optimization Algorithm

IRRTC

Improved Rapidly-exploring Random Tree Connect

LCPSO

Linear varying Coefficient Particle Swarm Optimization

LEVG

Layered Essential Visibility Graph

LKH

Lin Kernighan

LRTA-Star

Learning Real Time A-star

LVPSO

Linear varying maximum Velocity Particle Swarm Optimization

MACO

Modified Ant Colony Optimization

MCFO

Modified Central Force Optimization

mDELC

improved Differential Evolution with Level Comparison

MFO

Moth Flame Optimization

MFOA

Multi-swarm Fruit fly Optimization Algorithm

MGA

Modified Genetic Algorithm

MGOA

Modified Grey Wolf Algorithm

mHJB

Opportunistic Hamilton Jacobi Bellman

MHS

Modified Harmony Search

MILP

Mixed Integer Linear Programming

MMACO-DE

Maximum Minimum Ant Colony Optimization Differential Evolution

MMAS

Maximum Minimum Ant System

MPC

Model Predictive Control

MP-CGWO

Multi Population-Chaotic Grey Wolf Optimizer

MPFM

Modified Potential Field Method

MPGA

Multi-Population Genetic Algorithm

MT-PP

Maximum Throughput Path planning

mVD

Modified Voronoi Diagram

mVGA

Multi-frequency Vibrational Genetic Algorithm

mVGA\(^v\)

Multi-frequency Vibrational Genetic Algorithm with voronoi

MVO

Multi-Verse Optimizer

MWPS

Modified Wolf Packet Search

NBO

Nominal Belief-state Optimization

NFZ-DDRRT

No-Fly Zone Dynamic Domain Rapidly-exploring Random Tree

NSGA

Non-dominated Sorting Genetic Algorithm

NBGA

Neighborhood Based Genetic Algorithm

OGCA

Obstacle-free Graph Construction Algorithm

OGSA

Obstacle-free Graph Search Algorithm

oHJB

Opportunistic Hamilton Jacobi Bellman

OPP

Optimal Path Planning

PDE

Partial Differential Equation

PH

Pythagorean Hodograph

PIO

Pigeon Inspired Optimization

PIOFOA

Pigeon Inspired Optimization Fruit fly Optimization Algorithm

P-MAGA

Path planning Multi-Agent Genetic Algorithm

PMPSO

Position Mutation Particle Swarm Optimization

POMDP

Partially Observable Markov Decision Process

PPPIO

Predator Prey Pigeon Inspired Optimization

PRM

Probabilistic Road Map

PSO

Particle Swarm Optimization

PSO-APF

Particle Swarm Optimization-Artificial Potential Field

PSO-GA

Particle Swarm Optimization -Genetic Algorithm

PSOGSA

Particle Swarm Optimization Gravitational Search Algorithm

PSOPC

Particle Swarm Optimizer with Passive Congregation

QoS

Quality of Service

QPSO

Quantum Particle Swarm Optimization

RBF-ANN

Radial Basis Functions Artificial Neural Networks

RGA

Regular Genetic Algorithm

RGV

Reduced Visibility Graph

RHC

Receding Horizon Control

RLGWO

Reinforcement learning Grey Wolf Optimizer

RRT

Rapidly-exploring Random Tree

RRTC

Rapidly-exploring Random Tree Connect

RRT*

Rapidly-exploring Random Tree-Star

RRT* G

Rapidly-exploring Random Tree-Star Goal

RRT* GL

RRT Goal Limit

RRT* L

Rapidly-exploring Random Tree-Star Limit

RS

Random Search

RSU

Road Site Unit

RVW

Rendez-Vous Waypoints

Sarsa

State action reward state action

SA

Simulated Annealing algorithm

SADE

Self Adaptive Differential Evolution

SAS

Sparse A* Search

SCA

Sine Cosine Algorithm

SCPIO

Social Class Pigeon Inspired Optimization

SDPIO

Slow Diving Pigeon Inspired Optimization

SH

Short Horizon algorithm

SHA

Self Heuristic Ant

SHC

Short Horizon Cooperative algorithm

SICQ

Simultaneous Inform and Connect with Quality of service

SIC+

Simultaneous Inform and Connect following Quality of service

SOM

Self Organisation Map

SOMR

Surface Of Minimum Risk

SOS

Symbiotic Organism Search

SVM

Support Vector Machine

TADDRRT

Threat Assessment based Dynamic Domain Rapidly-exploring Random Tree

TARRT*

Threat Assessment based RRT* Rapidly-exploring Random Tree-Star

\(\theta\)-MAFOA

\(\theta\)-Mutation Adaptation Fruit Fly Optimization Algorithm

\(\theta\)-QPSO

Phase-encoded Quantum Particle Swarm Optimization algorithm

\(\theta\)-PSO

Phase-encoded Particle Swarm Optimization algorithm

TLBO

Teaching Learning Based Optimization

TLP-COA

Tri Level Programming Cognitive behavior Optimization Algorithm

TSP

Traveling Salesman Problem

UAV

Unmanned Aerial Vehicle

UGV

Unmanned Ground Vehicle

VD

Voronoi Diagram

VGA

Vibrational Genetic Algorithm

VPB-RRT

Variable Probability based bidirectional Rapidly-exploring Random Tree

WOA

Whale Optimization Algorithm

WPS

Wolf Packet Search

Rights and permissions

Reprints and permissions

About this article

Ait Saadi, A., Soukane, A., Meraihi, Y. et al. UAV Path Planning Using Optimization Approaches: A Survey. Arch Computat Methods Eng 29 , 4233–4284 (2022). https://doi.org/10.1007/s11831-022-09742-7

Download citation

Received : 30 January 2021

Accepted : 21 March 2022

Published : 18 April 2022

Issue Date : October 2022

DOI : https://doi.org/10.1007/s11831-022-09742-7

Share this article

Anyone you share the following link with will be able to read this content:

Sorry, a shareable link is not currently available for this article.

Provided by the Springer Nature SharedIt content-sharing initiative

  • Find a journal
  • Publish with us
  • Track your research

IMAGES

  1. (PDF) Optimal UAV path planning in a 3D threat environment by using

    a literature review of uav 3d path planning

  2. A Review on Viewpoints and Path-planning for UAV-based 3D

    a literature review of uav 3d path planning

  3. 3D Path Planning for UAV

    a literature review of uav 3d path planning

  4. (PDF) 3D Path Planning for Multiple UAVs for Maximum Information

    a literature review of uav 3d path planning

  5. Typical UAV path planning model. (a) contains both mobile threats and

    a literature review of uav 3d path planning

  6. (PDF) Path Planning Strategies for UAVS in 3D Environments

    a literature review of uav 3d path planning

COMMENTS

  1. A literature review of UAV 3D path planning

    A literature review of UAV 3D path planning. Abstract: 3D path planning of unmanned aerial vehicle (UAV) targets at finding an optimal and collision free path in a 3D cluttered environment while taking into account the geometric, physical and temporal constraints. Although a lot of works have been done to solve UAV 3D path planning problem ...

  2. A literature review of UAV 3D path planning

    Abstract. 3D path planning of unmanned aerial vehicle (UAV) targets at finding an optimal and collision free path in a 3D cluttered environment while taking into account the geometric, physical and temporal constraints. Although a lot of works have been done to solve UAV 3D path planning problem, there lacks a comprehensive survey on this topic ...

  3. A literature review of UAV 3D path planning

    A literature review of UAV 3D path planning. This paper analyses the most successful UAV 3D path planning algorithms that developed in recent years and classifies them into five categories, sampling-based algorithms, node-based algorithm, mathematical model based algorithms, Bio-inspired algorithms, and multi-fusion based algorithms.

  4. APPA-3D: an autonomous 3D path planning algorithm for UAVs in ...

    Yang L, Qi JT, Xiao JZ, et al. A literature review of UAV 3D path planning. Proc of the 11th World Congress on Intelligent Control and Automation. (IEEE, 2015).

  5. Path planning techniques for unmanned aerial vehicles: A review

    By using the techniques of path planning, not only an optimal and collision-free path can be discovered but also it minimizes the path length, travel time and energy consumption. So, to gain knowledge of various path planning techniques for UAVs, we presented a comprehensive survey by exploring the existing articles from different angles.

  6. Research on Unmanned Aerial Vehicle Path Planning

    The Classification of UAV Path-Planning Algorithm. The rest of this paper is organized as follows. Section 2 introduces the execution process and path-planning model. The algorithm-level UAV path panning classification is given in Section 3. Section 4 classifies and analyses path planning at the functional level.

  7. A Review on Viewpoints and Path Planning for UAV-Based 3-D

    A Review on Viewpoints and Path Planning for UAV-Based 3-D Reconstruction Abstract: Unmanned aerial vehicles (UAVs) are widely used platforms to carry data capturing sensors for various applications. The reason for this success can be found in many aspects: the high maneuverability of the UAVs, the capability of performing autonomous data ...

  8. A literature review of UAV 3D path planning

    Abstract: 3D path planning of unmanned aerial vehicle (UAV) targets at finding an optimal and collision free path in a 3D cluttered environment while taking into account the geometric, physical and temporal constraints. Although a lot of works have been done to solve UAV 3D path planning problem, there lacks a comprehensive survey on this topic, let alone the recently published works that ...

  9. Future Internet

    In this regard, this paper presents a systematic review of the 3D path-planning techniques during the last four years, and it offers valuable insights and comprehensive analysis of existing path-planning solutions in UAVs operating in a 3D environment helping researchers, academics, and professionals involved in UAV technology, wireless ...

  10. 3D path planning, routing algorithms and routing protocols for unmanned

    3D path planning, routing algorithms and routing protocols for unmanned air vehicles: a review - Author: Samia Ben Amarat, Peng Zong ... research questions are also proposed in this work and answered in discussion according to the presented literature review.,The research has found that conventional and node-based algorithms are a popular ...

  11. Title: A Review on Viewpoints and Path-planning for UAV-based 3D

    This review paper investigates a wide range of model-free and model-based algorithms for viewpoint and path planning for 3D reconstruction of large-scale objects. The analyzed approaches are limited to those that employ a single-UAV as a data capturing platform for outdoor 3D reconstruction purposes. In addition to discussing the evaluation ...

  12. UAV Path Planning in Three-Dimensional Complex Environments

    UAV path planning algorithms are more maturely developed in two-dimensional environments [1,2,3], and many path planning methods with collision elimination have been proposed in the field of UAVs.In the literature [], the Dijkstra-based global search algorithm solution model is proposed for the problem of fast planning of optimal paths for intelligent vehicles, which makes it better adaptable ...

  13. (PDF) 3D path planning, routing algorithms and routing protocols for

    Purpose -This paper aims to present a comprehensive review in major research areas of unmanned air vehicles (UAVs) navigation, i.e. three. degree-of-freedom (3D) path planning, routing algorithm ...

  14. Overview of Research on 3D Path Planning Methods for Rotor UAV

    With the continuous development of UAV technology, autonomous path planning methods suitable for UAVs are also evolving. In complex environments, UAVs not only need to consider the dynamics and time constraints, but also find the best and collision-free path. Although many researchers have conducted research on UAV path planning, there is a lack of comprehensive investigation and intuitive ...

  15. PDF A Literature Review of UAV 3D Path Planning

    This paper analyses the most successful UAV 3D path planning algorithms that developed in recent years. This paper classifies the UAV 3D path planning methods into five categories, sampling-based ...

  16. An Improved Algorithm of UAV 3D Path Planning

    Abstract. Path planning is the key of UAV autonomous flight. In order to improve the efficiency of UAV path planning in 3D complex environment, an improved path planning algorithm is proposed in this paper. First of all, in terms of map construction, aiming at the problem that sampling points cannot cover narrow free space in the traditional ...

  17. (PDF) A Review on Viewpoints and Path-planning for UAV-based 3D

    In robotics, view and path planning is a research focus. of many studies on 3D r econstruction to make the robots explore and reconstruct unknown environments more. competently (Chen et al., 2011 ...

  18. 3D path planning, routing algorithms and routing

    A brief detail and updated literature review are provided about each aforementioned category. After the detailed literature review, a comprehensive discussion is also provided according to the performance evaluation criteria mentioned in the next section. ... presented a literature survey on UAV three degree-of-freedom (3D) path planning ...

  19. A Systematic Literature Review (SLR) on Autonomous Path Planning of

    UAVs have been contributing substantially to multi-disciplinary research and around 70% of the articles have been published in just about the last five years, with an exponential increase. Primarily, while exploring the literature from the scientific databases for various aspects within the autonomous UAV path planning, such as type and configuration of UAVs, the complexity of their ...

  20. Connectivity-Aware 3D UAV Path Design With Deep ...

    In this paper, we study the three-dimensional (3D) path planning problem for cellular-connected unmanned aerial vehicle (UAV) taking into account the impact of 3D antenna radiation patterns. The cellular-connected UAV has a mission to travel from an initial location to a destination. In this process, there is a trade-off between the flight time and the expected communication outages duration ...

  21. Analyses and Comparisons of UAV Path Planning Algorithms in Three

    Path planning for unmanned aerial vehicle (UAV) is a crucial problem especially in complicated three-dimensional (3D) city environments. Until recently, several algorithms have been proposed to realize the UAV operations in 3D city environment, but the existing algorithms only focus on the ideal conditions, including known obstacles and deterministic UAV parameters. However, the complicated ...

  22. UAV Path Planning Using Optimization Approaches: A Survey

    Yang L, Qi J, Xiao J, Yong X (2014) A literature review of UAV 3d path planning. In: Proceeding of the 11th world congress on intelligent control and automation, pp. 2376-2381. IEEE. Pandey P, Shukla A, Tiwari R (2017) Aerial path planning using meta-heuristics: a survey. In: 2017 second international conference on electrical, computer and ...

  23. A Literature Review of UAV 3D Path Planning

    This document summarizes a literature review on UAV 3D path planning algorithms. It categorizes path planning methods into five categories: sampling-based algorithms, node-based algorithms, mathematical model based algorithms, bio-inspired algorithms, and multi-fusion based algorithms. For each category, it provides analysis and comparison of representative algorithms. It also discusses ...