Next Article in Journal
HDP-TSRRT*: A Time–Space Cooperative Path Planning Algorithm for Multiple UAVs
Next Article in Special Issue
Designing Ultrahigh Frequency Motor Rotor Position Search Coils for Electric Propulsion in Drones
Previous Article in Journal
Modeling and Simulation of an Octorotor UAV with Manipulator Arm
Previous Article in Special Issue
Proposals of Processes and Organizational Preventive Measures against Malfunctioning of Drones and User Negligence
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Review

Path Planning for Autonomous Drones: Challenges and Future Directions

Department of Computer Science, The University of Western Ontario, London, ON N6A5B7, Canada
*
Author to whom correspondence should be addressed.
Drones 2023, 7(3), 169; https://doi.org/10.3390/drones7030169
Submission received: 28 November 2022 / Revised: 23 February 2023 / Accepted: 23 February 2023 / Published: 28 February 2023
(This article belongs to the Special Issue Drones: Opportunities and Challenges)

Abstract

:
Unmanned aerial vehicles (UAV), or drones, have gained a lot of popularity over the last decade. The use of autonomous drones appears to be a viable and low-cost solution to problems in many applications. Path planning capabilities are essential for autonomous control systems. An autonomous drone must be able to rapidly compute feasible and energy-efficient paths to avoid collisions. In this study, we review two key aspects of path planning: environmental representation and path generation techniques. Common path planning techniques are analyzed, and their key limitations are highlighted. Finally, we review thirty-five highly cited publications to identify current trends in drone path planning research. We then use these results to identify factors that need to be addressed in future studies in order to develop a practical path planner for autonomous drones.

1. Introduction

Unmanned aerial vehicles (UAV), commonly referred to as drones, are defined as aerial vehicles that operate without the need for an onboard human pilot. According to the Federal Aviation Administration, there will be 835,000 commercial drones registered in the United States of America by 2025, about twice the number of commercial drones registered in 2020 [1]. Moreover, Morgan Stanley’s base case forecasts indicate that the autonomous urban aircraft industry (including drone delivery, flying taxis, military drones, and industrial worker drones) will be worth USD 1.5 trillion by 2040. Drones are particularly beneficial since they can perform high-risk missions without endangering human lives. Since drones are a safer alternative to manned military aircraft, they have been widely used for defence. However, due to advancements in technology and decreases in drones’ production costs, there has been a lot of interest in developing drones for commercial applications. The versatility of drones makes them ideal for surveillance, precision agriculture, search and rescue missions, inspections, and goods delivery. There have been extensive reviews into the advancements of the use of drones for agricultural [2] and logistical applications [3].
Over the last decade, many logistics companies, such as Amazon, United Parcel Service, and DHL, have been looking for alternative approaches to reduce the costs of last-mile deliveries. The use of autonomous drones can be very beneficial, especially since companies are consistently looking to deliver packages faster. Amazon [4] has announced that it is developing a hybrid drone with the ability to travel 15 miles to deliver packages under five pounds. However, there are many challenges with the use of drones for commercial applications. Generating energy-efficient paths has been a major area of research for such applications. For example, in some studies such as [5], the authors suggest generating a path along a public transportation network for drone delivery.
Although drones can be controlled by an operator at a ground control station, developing drones with high levels of autonomy makes them very useful for completing tasks that must be performed beyond the visual line of sight. There are many challenges involved in the development of a control system for autonomous drones. Several factors, including decision-making capabilities, path planning, trajectory generation, and fault-tolerant redundant management (in the instance of disturbances and failures), are required for drones to navigate autonomously [6]. To achieve this, drones must have the ability to sense and perceive its environment and compute a path using onboard computers and sensors. Additionally, flight navigation controlled by an onboard computer reduces the frequency with which an operator needs to interact with a drone, thus limiting the opportunity for human errors.
Many path planning algorithms have been suggested in the literature. The objective of this review is to summarize common methods suggested for drones to navigate an environment and path planning algorithms suggested for drones to compute an optimal or near-optimal path. We highlight key limitations with existing algorithms and some of the work being performed to overcome these limitations. Although much progress has been made in the field of path planning for drones, further work is required to develop a robust path planner. From a review of recent studies, we identify key factors that need to be considered in a study in order to develop a practical path planner for commercial applications.
The paper is organized as follows: In Section 2, we review the different types of drones that are available. Section 3 describes the current limitations of drones. Section 4 describes the drone path planning problem. Section 5 outlines some of the current drone path planning solutions in the literature, and in Section 6, an analysis is performed to determine future directions. Finally, we draw conclusions in Section 7.

2. Drone Classification

Generally, there are three major categories in which drones can be classified under: rotary-wing, fixed-wing, and flapping-wing drones. Each drone design has their own benefits and disadvantages [7]. For the purposes of this review, we are interested in looking at how these drone types affect drone path planning and navigation; therefore, we focus primarily on drone maneuverability and endurance.
Many studies model multi-rotor drones, such as quadcopters, for path planning applications due to their vertical takeoff and landing capabilities, high maneuverability, and hovering capabilities [8,9,10]. The maneuverability of drones makes multi-rotor drones suitable for tasks such as surveillance and search and rescue [11]. However, the main issue with rotary-wing drones is their limited flight time. Compared to flapping-wing and fixed-wing drones, rotary-wing drones rank the worst in flight endurance but best in maneuverability [12].
Even though fixed-wing drones have better battery performance than multi-rotor drones, they have many kinematic and dynamic constraints that need to be considered for practical applications. Moreover, it has been shown that rotary-wing drones are less susceptible to air turbulence than fixed-wing drones of similar dimensions [13]. However, in rural areas, fixed-wing drones have proven to be reliable for delivery applications. The drone delivery company Zipline has been using fixed-wing drones to deliver blood in Rwanda and Ghana. Takeoff and landing are a challenge with fixed-wing drones, but they can be valuable for rapid long-distance deliveries. Moreover, compared to rotary-wing drones, fixed-wing drones have been shown to cause less vibration during drone flight in real-world delivery applications [14].
Flapping-wing systems, which are inspired by birds, have potential benefits over rotary-wing and fixed-wing drones. The flapping process generates less friction drag, which increases a drone’s speed and ability to maintain speed in harsh wind conditions [15]. Therefore, flapping-wing drones can navigate longer distances than rotary-wing drones and do not have as many dynamic constraints as fixed-wing drones [12]. However, there are many design challenges which affect the stability of this type of drones [7]. To benefit from the endurance of fixed-wing drones and the maneuverability of rotary-wing drones, hybrid models, such as tilt-rotor drones, have been more recently proposed for drone delivery applications [4]. Tilt-rotor drones have vertical takeoff and landing capabilities and can cruise at high speeds. However, there are design challenges related to transitioning between vertical and horizontal configurations [4]. Moreover, in real-world experiments, these hybrid drones have also been shown to have stability issues [16].
A detailed review of the different types of drones and design challenges can be found in [7]. More recently, reconfigurable drones have been gaining attention [17]. These drones adapt configurations during their flight to minimize the energy consumed by them. Such designs can be beneficial when trying to navigate in crowded and narrow spaces and can greatly improve the trajectory planning of drones.

3. Current Challenges

Apart from current regulations that prohibit drones’ operation beyond the visual line of sight, safety concerns in instances of mechanical failure, and drone navigation in a GPS-denied environment [18], there are other limitations that need to be considered when developing a practical path planning algorithm. In this section, we go over four major limitations: the limited battery capacity of drones, onboard computational capabilities of drones, extreme weather conditions, and dynamic environments.

3.1. Energy Constraints

Although rotary-wing drones are highly maneuverable and versatile, they are still limited in terms of endurance. Thus, a single rotary-wing drone cannot be used for missions requiring long flight distances. Many factors can affect the battery performance of drones. Many maneuvers, such as hovering, horizontal and vertical movements, payload, speed, and flying in the wind direction, can impact drones’ battery performance at varying levels [19]. In many studies, it is often assumed that drones can navigate through a computed path on a single charge. However, in practical settings, drones may often need to stop and recharge in order to navigate to their destination.
Improvements have been made to reduce the energy consumption of drones. The overall weight of rotary-wing drones has been reduced by using carbon-fiber airframes. There have also been improvements in brushless direct-current motors’ power-to-weight ratios, which contributes significantly to energy consumption [20]. Since there are weight constraints to drones, additional batteries or batteries with larger capacities cannot be placed on a drone to improve its endurance. In [21], it has been shown that there is an optimal value of mass on a rotorcraft. Increasing a drone’s weight after such a point begins to reduce the drone’s endurance and causes the drone to become unstable.

3.2. Onboard Computational Capabilities

For many tasks, such as autonomous navigation, vision processing, localization of a drone, and mapping of the environment, the onboard computer requires high processing power and battery capacity. However, due to weight restrictions, onboard computers placed on drones have limited resources and onboard computational power. There have been many studies dedicated toward developing a lightweight fault-tolerable computing platform for drones [22]. Many complex three-dimensional (3D) path planning algorithms and image processing algorithms cannot be processed directly onboard since they require high computational power. For example, in [11], the authors performing a pilot drone search and rescue operation with thermal cameras noted that they could not use a simple machine learning algorithm onboard due to computational limitations. Moreover, since the environment is continually changing, drones must rapidly compute a path to avoid a collision. Although an optimal solution in terms of path length is desirable to improve battery performance, such approaches often require heavy computations and a lot of time, which is not feasible for drones. Although technological advances are being made and drones are now able to handle more complex tasks through the use of onboard graphical processing units [23], the limited computational power should still be considered when developing path planning algorithms for drones.

3.3. Weather Conditions

An important factor to consider for drone path planning is the potential for navigating under extreme weather conditions. Although there are many improvements being made in the design of drones to make them more durable for such conditions [17], environments with precipitation, fog, and severe wind can have an adverse effect on a drone’s endurance, visibility, and sensors for navigation and collision avoidance [24]. Recently, there have been a few studies that have proposed solutions for such weather conditions. Some studies have proposed solutions where drones can evaluate risk and avoid regions that may have severe weather conditions when generating a path [25]. Others, such as in [26], suggest using the Euler method to perform a numerical analysis to predict the trajectory of drones under different kinds of wind conditions. In [27], the authors suggest tilting a drone based on different wind directions can significantly help reduce the deviation of the camera on the drone when tracking the movement of a ground object. Finally, for vision-based path planning algorithms which rely on cameras to avoid obstacles, fog can severely reduce visibility [28].

3.4. Dynamic Environments

Collision avoidance in environments that are consistently changing has been a challenge for path planning for ground, underwater, and aerial vehicles [29]. It is nearly impossible to obtain information about the entire environment prior to the takeoff of a drone. There can be stationary or moving objects that are placed after takeoff, which hinders the drone’s flight path. One area of research has been on developing better hardware to detect obstacles. There has been research focused on adding different types of sensors, such as LiDAR and ultrasonic sensors [30], to better detect obstacles during flight. Other studies have focused on how to incorporate such sensor data to avoid obstacles in real time. For example, in [8], the authors proposed using a Gaussian process occupancy map to predict the probability of there being a collision along the path using the sensor data that have been collected. Based on that information, the algorithm decides potential waypoints to include during its path generation. More recently, there have been more learning-based algorithms that have been suggested for navigation in dynamic environments [31,32,33,34]. These techniques generally do not need prior information about the environment to generate a path. They learn from prior actions taken by a drone to determine how to navigate in an unknown environment. Another recent challenge is coordinating multiple drones that are navigating in an unknown environment and ensuring that the drones do not collide with one another [35].

4. Drone Path Planning Problem

Although path planning has been extensively studied, there has yet to be a practical solution that addresses the energy constraints and onboard computational limitations of drones. To successfully deploy drones for commercial applications, drones must be able to avoid collisions and navigate to their destination efficiently. Therefore, we focus on analyzing various path planning techniques and provide insights into areas that need to be addressed when developing a path planning algorithm. Research into the path planning problem for drones has been growing since 2000. The number of published proceeding papers and articles related to path planning in the Web of Science database has been growing exponentially since 2000 (Figure 1). The majority of all published drone studies in the Web of Science Core Collection between 2000 and 2022 are related to the path planning problem. Computing the shortest path between two points in a 3D environment with polyhedral objects is NP-hard [36]. Thus, most drone path planning algorithms use heuristics and metaheuristics to generate a near-optimal path.
In this paper, the drone path planning problem refers to generating a minimum-cost and collision-free path between the start and the destination point. In many studies, the objective is to minimize total path length. However, some studies also minimize flight time [20], flight altitude [37], and drone speed [38].
Path planning algorithms can be categorized as either offline path planners or online (real-time) path planners. Offline path planners compute a path for a drone prior to takeoff. Thus, these path planners require information about the environment in advance. Information regarding obstacles and no-fly zones are made available to these path planners to generate an accurate path. An advantage of offline path planners is that they are able to employ models of drone dynamics to ensure that the path is feasible. However, these types of algorithms are not able to respond to changes in the environment dynamically. The environment is continually changing. Moving obstacles, such as birds, wind, and other aircraft, may hinder the original path, and a robust path planner must be able to re-compute a new path to avoid such obstacles.
Online path planners utilize sensor data to detect obstacles and, therefore, react to changes in the environment. However, online path planners are often not able to ensure that near-optimal paths are generated. Some online path planners function by generating an initial feasible path and modifying their path as dynamic obstacles are detected [8]. Other online path planners utilize probability functions to generate a path as new information regarding the environment becomes available [9]. Depending on the specific use case, one of these approaches may be beneficial over the other. For example, in drone delivery applications, the first approach would allow a drone to travel a relatively shorter overall distance than the second approach. However, in target tracking applications, pre-defined paths cannot be utilized. Therefore, a path planner must incrementally generate a path.

5. Path Planning Algorithms

In this section, we review algorithms that have been proposed in the literature for path planning. Path planning generally involves three main tasks: mapping the environment, applying an algorithm to generate an optimal path, and smoothing the path to make it feasible.

5.1. Environmental Representation

Before searching for a path, the search space must be mapped for an algorithm to understand the location of obstacles. Figure 2 summarizes some of the most commonly used techniques to represent an environment. Cell decomposition techniques have been extensively used in many studies [39,40,41]. An environment can be divided into a uniform grid (Figure 2a) with fixed-size cells or voxels to simplify the task of computing paths. Any cell containing a portion of an obstacle is marked as occluded, and any cell without an obstacle is marked as free. However, even if a small part of a particular cell contains an obstacle, the entire cell is marked as being occluded with these approaches. Although such approaches can determine whether there is a solution for any given input, in a finite amount of time, these approaches require a large amount of memory. They cannot function in real time to solve problems.
To mitigate the computationally intensive process of cell decomposition techniques, some studies have designed solutions using adaptive cell decomposition techniques [43], which limit the number of voxels used to generate a path. Adaptive cell decomposition techniques, such as quadtrees (Figure 2b), have been proposed to represent obstacle information accurately. There are more voxels (smaller in size) when close to an obstacle and fewer (larger in size) voxels when away from an obstacle. A modified adaptive cell decomposition method for 3D environments is suggested in [44], which reduces the amount of memory required to compute a path by continuously dividing a cell until the voxel size has reached a predefined fixed value. However, this approach may require a large amount of time in cluttered environments. More recently, in [45], the authors use a layered graph to effectively store the coordinates of obstacles. Since the number of layers created to store environmental information can be controlled, the amount of memory required to represent an environment can be bounded.
Voronoi diagrams (Figure 2d) have also been used to model an environment. This method involves partitioning a plane with a set of objects into convex polygons, where each polygon contains a single object. Any point in each polygon is closer to the object in its polygon than any other objects. Moreover, each point on the edge of the Voronoi diagram is equidistant from its two nearest neighbors. However, using the edges of a Voronoi diagram to generate a path may lead to sub-optimal solutions. Voronoi diagrams are often used to compute a path away from a threat or radar [46]. In recent studies, Voronoi diagrams have been constructed to improve the quality of path generated by other algorithms. For example, in [47], Voronoi diagrams were constructed to increase the convergence rate of a genetic algorithm by selecting members on the Voronoi vertices to be part of the initial population.
Visibility graphs can also be used to represent a search space. Visibility graphs function by adding nodes corresponding to the vertices of obstacles into a graph. Nodes in the graph are connected by an edge if the edge connecting the two nodes lie in an obstacle-free region (Figure 2c). Visibility graphs have been used extensively in 2D path planning because of their simplicity and because they can be used to compute global shortest paths for a point [48]. However, a large amount of time and memory is needed to generate visibility graphs in 3D, and only near-optimal solutions can be generated when only considering obstacle vertices. To address this issue, some studies have constructed reduced visibility graphs by using only a subset of obstacles in the environment [49,50,51,52]. Algorithms based on bounded energy space [50] and approximation with visibility line [51] reduce the number of obstacles by only considering obstacles in the straight path from the start to the destination point. However, such approaches can generate poor solutions (roughly 8% larger than the optimal path) and cannot guarantee that a solution will be found in complex environments with many obstacles [51]. Moreover, these algorithms have a high time complexity [52]. Other studies have transformed a 3D space into a 2D space to reduce the complexity of the problem [53,54]. Although there are limitations with using this approach for cluttered environments, in use cases where there are only a few obstacles, visibility graphs have been proven to be beneficial [55].

5.2. Path Generation

Many studies attempt to reduce the three-dimensional path planning problem to two dimensions [41,56]. By limiting the maneuvers of a drone to a horizontal plane (at a fixed altitude), the complexity of the problem can be significantly reduced, and algorithms proposed for other ground vehicles can be directly applied to drones. However, there are many benefits in utilizing the vertical translational movement of drones. One particular benefit is obstacle avoidance and navigation.
Many shortest-path algorithms have been suggested for drone path planning. After modeling the environment, Dijkstra’s algorithm [54,56] has been suggested to generate the shortest path for drones. Dijkstra’s algorithm determines the shortest paths from the start point to all vertices in a graph by iteratively traversing through all nodes and updating the distances to adjacent nodes. Although the implementation of Dijkstra’s algorithm can be optimized to perform quickly, in large environments where there are a lot of vertices in the graph, the A* algorithm is often desired. Since the A* algorithm focuses on searching for the shortest path toward the destination point, as opposed to the shortest path to every vertex in the graph, it has often been used for drone path planning [57,58]. As opposed to Dijkstra’s algorithm, the A* algorithm uses a heuristic h(u) when calculating the cost of a particular vertex in the graph. As long as the value of h(u) is lower than or equal to the actual distance of u to the destination point, the heuristic is considered admissible and can compute an optimal path. However, if the distance from u to the destination point is overestimated, then the A* algorithm cannot guarantee that an optimal solution will be computed. The value of h(u) can have an impact on the time complexity of the algorithm. Variations of the A* algorithm, such as the D* algorithm [40] and Theta* [57], have also been proposed for online path planning; however, such approaches may be slower than the A* algorithm due to the increase in the number of calculations.
Sampling-based path planning algorithms have been extensively studied due to their low computational complexity and ability to solve complex high-dimensional problems. Probabilistic road maps (PRMs) and rapidly exploring random trees (RRTs) [59] are common sampling-based path planning algorithms that compute a path using a set of randomly chosen points from the configuration space. PRMs can be inefficient when obstacle geometry is not known beforehand [60]. The original RRT algorithm generates solutions very rapidly in dynamic environments; however, its solutions are not optimal. The RRT* algorithm [61] was later proposed to improve the RRT algorithm by using nearest neighbors to refine the overall path. The RRT* algorithm has been proven to be asymptotically optimal. Thus, the cost of the path will almost surely converge to the optimum. However, the convergence rate at which the algorithm reaches the optimal solution is very slow. Although the RRT* algorithm can compute optimal paths, the slow convergence rate makes it unsuitable for real-time applications, such as drone path planning. Many variants of the RRT and RRT* algorithms have been proposed to improve the rate at which these algorithms converge to an optimal solution [60,61]. RRT- and RRT*-based solutions have been commonly proposed for drone path planning [8,9,10,62,63,64]. Many studies use RRTs for online path planning where sensors are used to detect either stationary or moving obstacles, and RRTs are used since they are effective at re-planning paths [8,9,10]. Other studies have attempted to integrate RRTs with other path planning techniques, such as potential fields [62] and particle swarm optimization [63]. Some studies target fixed-wing drones and only sample points that satisfy a minimum turning radius [64]. A limitation with attempting to generate an optimal path with RRT-based approaches is that if a path does not exist (there is no solution), the algorithm may run infinitely.
Artificial potential fields have also been proposed for path planning in 3D environments [38,62,65]. A gravitational field of attraction is placed around the destination, and repulsive forces are placed around the obstacles. The combination of potentials creates a force field, which is then used to guide the drone toward the destination while avoiding the obstacles. A major issue with potential fields is that they can easily converge to a local minimum due to location, geometry of obstacles, and large environments. Once a drone is trapped at a local minimum, it can no longer reach its destination point. Moreover, artificial potential fields cannot guarantee that the resulting path is optimal [38]. Several approaches have been proposed to solve these issues. In [38], the problem is converted into an optimization problem and solved using an optimal control method to successfully move a vehicle out of traps. In [66], a pre-determined or randomly selected guided point is introduced to allow a UAV to continue searching for the destination when it reaches a local minimum. Artificial potential fields have been demonstrated on a network of micro-drones to successfully avoid obstacles while maintaining formation [62].
Many metaheuristic algorithms based on biological models have also been proposed as solutions to the path planning problem. Genetic algorithms [67,68,69], ant colony optimization (ACO) [70,71,72], particle swarm optimization (PSO) [63,73], fruit fly optimization [74,75], wolf pack search [76], and differential evolution [37] are all examples of such evolutionary algorithms, which use bio-inspired properties for optimization. Figure 3 depicts the general structure of an evolutionary algorithm. Generally, in evolutionary algorithms, the initial population is randomly generated. In the case of genetic algorithms, solutions are altered (mutated) such that the fittest solution, based on an objective function, is chosen for the next generation. In other algorithms such as PSO, the particles’ positions in the environment are updated based on their individual best known position and the population’s best known position.
A limitation with genetic algorithms is that they can be computationally expensive. However, implementing a genetic algorithm on field-programmable gate arrays (FPGA) and GPUs has been shown to quickly generate feasible solutions in small environments [67,68]. Another major limitation with evolutionary algorithms in general is premature convergence. To overcome this issue, increasing the diversity of the population through periodic mutation applications has resulted in fast convergence for genetic algorithms [69]. Moreover, combining PSO with an adaptive decision operator has helped overcome premature convergence [73]. This improved PSO is able to generate solutions that are superior to the original genetic algorithm, PSO, and firefly algorithms. To resolve the local minimum and premature convergence in ACO algorithms, adding a disturbance by applying a particular chaos factor has shown to work [72]. The use of multiple colonies that communicate with each other [47] has also been shown to improve the quality of the solution generated by an ACO algorithm.
More recently, learning-based methods have been suggested for drone path planning [31,32]. Reinforcement learning can be used to make sequential decisions. Thus, information about the environment does not necessarily need to be made available [32]. When discussing reinforcement learning, an agent makes a decision based on current and past experiences. The objective is to maximize the reward value and learn an optimal policy quickly. A policy refers to the agent’s actions. In other words, it determines how the agent reacts in different situations and which actions to take. An adaptive and random exploration approach based on Q-learning has been proposed for drones to navigate and avoid obstacles in real time [31]. During path planning, there is a learning module that derives a strategy for action by looking at historical data and action of a drone. In [32], the classical Q-learning algorithm is improved by adding an artificial potential field to avoid local minima, improve convergence rate, and navigate in dynamic environments. However, these approaches may be computationally expensive in large environments since environments are represented as grids.
The use of deep learning with reinforcement learning (DRL) has been gaining interest after much success in other applications, such as video games. DRL uses deep learning concepts with reinforcement learning to give an optimal solution based on its experiences [78]. A detailed description of deep learning, reinforcement learning, DRL, and various classifications of deep learning reinforcement can be found in [78]. There have been more map-less online solutions proposed using DRL for autonomous navigation. For example, in [34], the authors suggest fusing multiple sensory data using an end-to-end convolutional neural network to control the motion and direction of a drone. Although the drone is only navigating on a 2D plane, the simulation and implementation on a physical drone successfully show that the drone would be able to avoid obstacles in a dynamic environment. Deep deterministic policy gradient (DDPG) is another approach based on the actor–critic method. The actor in this scenario chooses an action to perform in a continuous space, and the critic evaluates the advantages and disadvantages of the current strategy. In [79], the authors use a DDPG-based approach where a UAV determines a trajectory to reach a dynamic destination within a continuous space. However, the drone only reaches its destination without colliding into an obstacle in 82% to 84% of the time.
Other approaches using control theory have also been suggested [71,80,81,82]. In [71], the authors suggest that a Markov decision process can be used to plan an energy-efficient path based on the uncertainty of a Gaussian distribution, which is used to determine the uncertainty in wind fields. Model predictive control (MPC) is another model used to control a drone’s path planning while satisfying a set of constraints. In [83], the authors use MPC for controlling the trajectory of a drone with respect to a reference trajectory. MPC has been shown to generate trajectories for drones using limited computational resources. However, it does not scale well when there is a central MPC for an increasing number of drones [80]. In [82], the authors used a distributed MPC as part of an online planner to generate paths for a swarm of drones. The authors suggest offloading the path planning computation to computational units on the ground and using the distributed MPC to select a subset of the most relevant drone trajectories to be replanned.

6. Analysis

6.1. Analysis of Recent Studies

For this review, path planning papers were retrieved from the Web of Science database. Highly cited studies between 2010 and 2022 were investigated. Preference was given to more recent studies. Since we were mainly interested in path planning algorithms for commercial applications, we did not investigate coverage path planning algorithms or target tracking path planning algorithms. Coverage path planning algorithms are necessary for applications such as search and rescue and surveillance, which require a drone to compute the best path to traverse the entire environment. We analyzed 35 different studies and summarized the results in Table 1.
The critical review of drone path planning papers was based on the following criteria:
  • Dimension: Studies included the spatial dimension for which the path planning algorithm was proposed. The algorithm was either suggested for 2D or 3D environments.
  • Energy Constraints: Studies analyzed factors other than path length in their cost function. Various factors, such as payload, weight, wind, motor thrust, drone maneuvers, can affect the battery performance of drones [19].
  • Path Optimization: Flight trajectory is important, particularly for fixed-wing drones. Since fixed-wing drones have limited turning angles, often Dubins curves or Bezier curves are used to ensure the path is feasible. Path smoothening techniques have also been applied to rotary-wing drones to allow for continuous motion and prevent the drone from having to come to a complete stop.
  • Drone Type: Fixed-wing drones (F), rotary-wing drones (R), or the paper did not specify which type of drone the algorithm was intended for (N).
  • Path Planner: The algorithm was developed as an online path planner to compute paths in real time (ON) or as an offline path planner (OFF).
  • Obstacle Type: The algorithm can generate a path in an environment with stationary obstacles (ST) or moving obstacles (MV).
  • Environment Type: Type of environment used for testing. We defined a small-sized environment as having 0–50 obstacles (S), a medium-sized environment as having 51–500 obstacles (M), and a large-sized environment as having more than 500 obstacles (L).
  • Computer Simulations: Studies indicated whether computer simulations were used to validate the algorithm.
  • Drone Implementation: Studies indicated whether the algorithm was tested on physical drones in an indoor (I) or outdoor (O) setting.
  • Algorithm Category: We categorized the approach taken as either bio-inspired algorithm (BA), graph search (GS), learning algorithm (LA), other (OT), potential fields (PF), or sampling-based algorithm (SBA).

6.2. Future Directions

Although some of the proposed algorithms have great potential to be used as path planners for autonomous drones, limitations exist in terms of the quality of the solutions that they produce and the required computational resources. Many different factors need to be considered before an autonomous drone can use a path planner. In this section, we review current research trends and improvements that can be performed in the future to develop a robust path planner for drones.
Many path planning algorithms for ground vehicles have been applied to drones [29]. Initially, these algorithms were applied to drones by modeling the environment in two dimensions. However, as shown in Table 1, the majority of the studies (especially more recent studies) have developed 3D drone path planning solutions. Unlike ground vehicles, drones have the ability to navigate over objects. Consequently, path planners may be able to generate more optimal solutions. Moreover, not all 2D path planning algorithms can be easily applied in three dimensions. Three-dimensional path planning can be much more complex and requires more time to generate a solution [91].
The majority of the studies we reviewed optimized their path based on time or distance. Although the goal of a path planner should be to navigate a drone to its destination point as quickly as possible, as discussed earlier, different drone maneuvers, a drone’s payload, and its wind speed can all impact the drone’s battery performance at varying levels. Therefore, a drone may not have the battery capacity to navigate the generated paths based solely on optimizing distance and speed. To address this issue, some studies have developed a power consumption estimation model [92] to detect battery levels and re-route drones to a charging station when necessary. Some studies that we reviewed considered motor thrust [38] and wind energy [72] to improve the energy consumption of drones. In the future, it would be beneficial if studies consider the limited battery capacity of drones when developing algorithms. Different factors, such as changes in altitude or number of times a drone needs to alter its flight direction, can also be considered when developing a potential solution.
Previously, since path planning algorithms were developed for combat operations, many studies focused on developing solutions for fixed-wing drones. However, in recent years, many studies have been developing solutions for rotary-wing drones due to their maneuverability and ability to hover. Although the design of flapping-wing drones has been well studied, there have not been a lot of studies that use such drones for path planning experiments. The limited availability of flapping-wing drones and reconfigurable drones may also potentially be a reason for the limited number of studies using such designed drones. In the future, studies may benefit by using hybrid vertical take off and landing drones [17] for path planning. Such drones have the ability to hover when necessary and navigate longer distances than rotary-wing drones.
From the reviewed studies, the most commonly applied algorithms for the drone path planning problem are bio-inspired algorithms and sampling-based algorithms (particularly RRT-based approaches), as shown in Figure 4. Although many studies have previously used graph-search-based approaches, only limited studies have used such approaches for online path planning. This may be due to the high computational power requirements for such algorithms. More recently, especially for the online path planning problem, learning-based algorithms have shown moderate experimental success in dynamic environments. However, in the future, studies should focus on testing in environments with stationary and moving dynamic objects to simulate real-world conditions. From the reviewed studies, less than 20% of the studies considered moving objects when testing their algorithm, and the majority of the studies did not implement their solution on a physical drone and did not test in real-world conditions.
In cluttered urban environments where drones would navigate autonomously for commercial applications, there can be thousands of obstacles of varying sizes. In the majority of the studies that we reviewed, the proposed approach was only tested in small environments with fewer than 50 obstacles in their simulations. When testing the robustness of a path planner, obstacles should be placed randomly. Similar to the approach taken in [45], obstacles of varying widths and heights should be used to determine how long it takes for a path planner to generate a path and the overall quality of the path generated.
Trajectory generation is another area of research that has been gaining a lot of interest. Although we have reviewed multiple methods to generate a path, there are challenges in having a drone follow a computed flight path smoothly. For instance, Figure 5 shows the trajectories generated by four different flight control systems (FCS) for a quadrotor drone. As shown in the figure, different FCS can track the reference trajectory; however, when there is a disturbance (such as wind gusts), it can affect the controller’s ability maintain the drone’s position. The control problem involves generating a controller which can maintain the position and altitude of the drone, which is essential for deploying autonomous drones. Convergence time, ability to adapt to disturbances, and control precision are all required for a robust flight controller [93]. Proportional–integral–derivative (PID) controllers have been suggested for drone trajectory tracking [94]; however, they are sensitive to disturbances and nonlinear systems. Other studies have suggested using variable structure control to develop more robust controllers [93]. Computer simulations of the trajectory of a drone along the generated path can provide an idea of the effectiveness of a path planner; however, there may be challenges when trying to test it in the real world. In many of the studies, the details regarding the platform on which the simulation was run is not provided. Therefore, an algorithm may perform as expected when it has the available computational resources and power, but it may not be a feasible solution when applying it to a drone with fewer resources available. Although there are mathematical models that can be used to simulate the dynamics of drones, more studies in the future need to implement their algorithm on physical drones in real-world environments for validation. In some of the studies we reviewed, the algorithms were validated in indoor environments with a few obstacles [8] and in outdoor environments [34,66]. However, a drone does not generate smooth trajectories or is prone to disturbances. There has been some progress in developing a flight controller that can effectively reject disturbances [93]. However, further studies are required to determine flight controllers’ efficacy in navigating in complex, cluttered environments.
Lastly, from the reviewed studies, about half of the studies did not compare the effectiveness of their algorithm to another path planning algorithm. A detailed comparative study that compares multiple types of algorithms based on memory consumption, running time, and path cost is necessary. Moreover, a comparative analysis should include algorithms from multiple categories. In [96], the authors performed a comparative analysis of RRT-based path planning algorithms. In another recent comparative study, the authors compared a graph-search-based algorithm with a sampling-based algorithm [97]. However, a more comprehensive comparison with many more algorithms in a real-world setting is crucial to determine how viable a solution can be for practical purposes.
Recently, there have been a lot of studies focusing on utilizing groups of drones [35,83,98], especially for optimal coverage path planning algorithms. However, this also introduces other challenges, such as communication, task allocation, and control. In [81], the authors suggested having a network of drones complete portions of a task. The objective was to minimize the total distance travelled by the drones to address the energy limitation of these drones. However, this study did not focus on the simultaneous deployment of drones for tasks. The use of multiple drones can be beneficial for applications where a drone needs to navigate large areas. Examples include disaster recovery, traffic monitoring, and search and rescue operations. In the future, studies optimizing coverage path planning algorithms can focus on approaches to improve the simultaneous deployment of drones for tasks.
There are many other interconnected areas of research where improvements are required to use autonomous drones for commercial operations. In this review, we focus on path planning. However, privacy and security are a major concern during the autonomous navigation of drones [99]. As described in [99], many studies have focused on vulnerabilities in drone communication. Some studies have suggested a blockchain framework to secure data collection and communication within a drone network [98]. Moreover, communications between drones and between a drone and a ground station are also critical during missions. As shown in [100], cellularly connected drones can work together using a RL-based framework to generate an energy-efficient path and minimize the interference they cause on ground networks, as well as on their wireless transmission latency.

7. Conclusions

Developing a computationally inexpensive, efficient, and robust path planner for drones can be challenging. In this review, we explore various drone path planning algorithms in recent literature. We highlight the limitations of these commonly used path planning algorithms and explore some of the suggestions in the literature to overcome these issues. Moreover, we provide insight into various factors that should be considered when developing a path planner for autonomous drones in the future. For example, factors affecting the battery performance of drones, including payload, communication, and motor thrust, need to be considered when computing a path for an autonomous drone. Moreover, to make algorithms more practical for commercial applications, future studies should develop path planners that are able to dynamically respond to changes in 3D environments. Finally, although the majority of the reviewed studies validated their algorithm using computer simulations, future studies should implement and test their algorithm in realistic environments.

Author Contributions

Conceptualization, G.G. and A.H.; data curation, G.G.; visualization, G.G; writing—original draft preparation, G.G.; writing—review and editing, G.G and A.H.; supervision, A.H. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Institutional Review Board Statement

Not applicable.

Data Availability Statement

The data used to support the findings of this study are included in the article.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. FAA Aerospace Forecasts 2021–2041. Available online: https://www.faa.gov/data_research/aviation/aerospace_forecasts/media/Unmanned_Aircraft_Systems.pdf (accessed on 27 November 2022).
  2. Li, Y.; Liu, M.; Jiang, D. Application of Unmanned Aerial Vehicles in Logistics: A Literature Review. Sustainability 2022, 14, 14473. [Google Scholar] [CrossRef]
  3. Rejeb, A.; Abdollahi, A.; Rejeb, K.; Treiblmaier, H. Drones in agriculture: A review and bibliometric analysis. Comput. Electron. Agric. 2022, 198, 107017. [Google Scholar] [CrossRef]
  4. A Drone Program Taking Flight. Available online: https://blog.aboutamazon.com/transportation/a-drone-program-taking-flight (accessed on 27 November 2022).
  5. Huang, H.; Savkin, A.V.; Huang, C. Reliable Path Planning for Drone Delivery Using a Stochastic Time-Dependent Public Transportation Network. IEEE Trans. Intell. Transp. Syst. 2020, 22, 4941. [Google Scholar] [CrossRef]
  6. Boskovic, J.D.; Prasanth, R.; Mehra, R.K. A multilayer control architecture for unmanned aerial vehicles. In Proceedings of the 2002 American Control Conference, Anchorage, AK, USA, 8–10 May 2002; Volume 3, pp. 1825–1830. [Google Scholar]
  7. Hassanalian, M.; Abdelkefi, A. Classifications, applications, and design challenges of drones: A review. Prog. Aerosp. Sci. 2017, 91, 99–131. [Google Scholar] [CrossRef]
  8. Lin, Y.; Saripalli, S. Path planning using 3D Dubins Curve for Unmanned Aerial Vehicles. In Proceedings of the International Conference on Unmanned Aircraft Systems, Orlando, FL, USA, 27–30 May 2014; pp. 296–304. [Google Scholar]
  9. Yang, K.; Keat Gan, S.; Sukkarieh, S. A Gaussian process-based RRT planner for the exploration of an unknown and cluttered environment with a UAV. Adv. Robot. 2013, 27, 431–443. [Google Scholar] [CrossRef]
  10. Lin, Y.; Saripalli, S. Sampling-Based Path Planning for UAV Collision Avoidance. IEEE Trans. Intell. Transp. Syst. 2017, 18, 3179–3192. [Google Scholar] [CrossRef]
  11. Burke, C.; McWhirter, P.R.; Veitch-Michaelis, J.; McAree, O.; Pointon, H.A.G.; Wich, S.; Longmore, S. Requirements and Limitations of Thermal Drones for Effective Search and Rescue in Marine and Coastal Areas. Drones 2019, 3, 78. [Google Scholar] [CrossRef] [Green Version]
  12. Leutenegger, S.; Hurzeler, C.; Stowers, A.K.; Alexis, K.; Achtelik, M.W.; Lentink, D.; Oh, P.Y.; Siegwart, R. Flying Robots. Springer Handbook of Robotics; Springer: Berlin, Germany, 2016; pp. 623–670. [Google Scholar]
  13. Norouzi Ghazbi, S.; Aghli, Y.; Alimohammadi, M.; Akbari, A. Quadrotors unmanned aerial vehicles: A review. Int. J. Smart Sens. Intell. Syst. 2016, 9, 309–333. [Google Scholar]
  14. Oakey, A.; Waters, T.; Zhu, W.; Royall, P.G.; Cherrett, T.; Courtney, P.; Majoe, D.; Jelev, N. Quantifying the Effects of Vibration on Medicines in Transit Caused by Fixed-Wing and Multi-Copter Drones. Drones 2021, 5, 22. [Google Scholar] [CrossRef]
  15. Ma, H.; Song, B.; Pei, Y.; Chen, Z. Efficiency Change of Control Surface of a Biomimetic Wing Morphing UAV. IEEE Access 2020, 8, 45627–45640. [Google Scholar] [CrossRef]
  16. Okulski, M.; Ławryńczuk, M. A Small UAV Optimized for Efficient Long-Range and VTOL Missions: An Experimental Tandem-Wing Quadplane Drone. Appl. Sci. 2022, 12, 7059. [Google Scholar] [CrossRef]
  17. Derrouaoui, S.H.; Bouzid, Y.; Guiatni, M.; Dib, I. A Comprehensive Review on Reconfigurable Drones: Classification, Characteristics, Design and Control Technologies. Unmanned Syst. 2022, 10, 3–29. [Google Scholar] [CrossRef]
  18. Valenti, F.; Giaquinto, D.; Musto, L.; Zinelli, A.; Bertozzi, M.; Broggi, A. Enabling Computer Vision-Based Autonomous Navigation for Unmanned Aerial Vehicles in Cluttered GPS-Denied Environments. In Proceedings of the International Conference on Intelligent Transportation Systems, Maui, HI, USA, 4–7 November 2018; pp. 3886–3891. [Google Scholar]
  19. Abeywickrama, H.V.; Jayawickrama, B.A.; He, Y.; Dutkiewicz, E. Comprehensive Energy Consumption Model for Unmanned Aerial Vehicles, Based on Empirical Studies of Battery Performance. IEEE Access 2018, 6, 58383–58394. [Google Scholar] [CrossRef]
  20. Morbidi, F.; Cano, R.; Lara, D. Minimum-energy path generation for a quadrotor UAV. In Proceedings of the IEEE International Conference on Robotics and Automation, Stockholm, Sweden, 16–21 May 2016; pp. 1492–1498. [Google Scholar]
  21. Abdilla, A.; Richards, A.; Burrow, S. Power and endurance modelling of battery-powered rotorcraft. In Proceedings of the IEEE/RSJ International Conference on Intelligent Robots and Systems, Hamburg, Germany, 28 September–3 October 2015; pp. 675–680. [Google Scholar]
  22. Ahmed, F.; Jenihhin, M.A. Survey on UAV Computing Platforms: A Hardware Reliability Perspective. Sensors 2022, 22, 6286. [Google Scholar] [CrossRef] [PubMed]
  23. Oyuki Rojas-Perez, L.; Martinez-Carranza, J. On-board processing for autonomous drone racing: An overview. Integration 2021, 80, 46–59. [Google Scholar] [CrossRef]
  24. Roseman, C.A.; Argrow, B.M. Weather hazard risk quantification for sUAS safety risk management. J. Atmos. Oceanic Tech. 2020, 37, 1251. [Google Scholar] [CrossRef]
  25. Gianfelice, M.; Aboshosha, H. Real-time Wind Predictoins for Safe Drone Flights in Toronto. Results Eng. 2022, 15, 100534. [Google Scholar] [CrossRef]
  26. Hu, S.; Mayer, G. Three Dimensional Euler Solutions for Drone Delivery Trajectory Prediction under Extreme Environments. In Proceedings of the International Conference on Applied Mathematics, Modelling, and Intelligent Computing, Kunming, China, 25–27 March 2022; pp. 1–6. [Google Scholar]
  27. Jayaweera, H.M.P.C.; Hanoun, S. Path Planning of Unmanned Aerial Vehicles (UAVs) in Windy Environments. Drones 2022, 6, 101. [Google Scholar] [CrossRef]
  28. Lin, H.Y.; Peng, X.Z. Autonomous Quadrotor Navigation With Vision Based Obstacle Avoidance and Path Planning. IEEE Access 2021, 9, 102450–102459. [Google Scholar] [CrossRef]
  29. Cheng, C.; Sha, Q.; He, B.; Li, G. Path planning and obstacle avoidance for AUV: A review. Ocean. Eng. 2021, 235, 109355. [Google Scholar] [CrossRef]
  30. Singh, J.; Dhuheir, M.; Refaey, A.; Erbad, A.; Mohamed, A.; Guizani, M. Navigation and Obstacle Avoidance System in Unknown Environment. In Proceedings of the IEEE Canadian Conference on Electrical and Computer Engineering, London, ON, Canada, 30 August–2 September 2020; pp. 1–4. [Google Scholar]
  31. Yijing, Z.; Zheng, Z.; Xiaoyi, Z.; Yang, L. Q learning algorithm based UAV path learning and obstacle avoidence approach. In Proceedings of the Chinese Control Conference, Dalian, China, 26–28 July 2017; pp. 3397–3402. [Google Scholar]
  32. Yan, C.; Xiang, X. A Path Planning Algorithm for UAV Based on Improved Q-Learning. In Proceedings of the International Conference on Robotics and Automation Sciences, Wuhan, China, 23–25 June 2018; pp. 1–5. [Google Scholar]
  33. Hou, X.; Liu, F.; Wang, R.; Yu, Y. A UAV Dynamic Path Planning Algorithm. In Proceedings of the Youth Academic Annual Conference of Chinese Association of Automation, Zhanjiang, China, 16–18 October 2020; pp. 127–131. [Google Scholar]
  34. Doukhi, O.; Lee, D.J. Deep Reinforcement Learning for Autonomous Map-Less Navigation of a Flying Robot. IEEE Access 2022, 10, 82964–82976. [Google Scholar] [CrossRef]
  35. Wu, Y.; Low, K.H. An Adaptive Path Replanning Method for Coordinated Operations of Drone in Dynamic Urban Environments. IEEE Syst. J. 2021, 15, 4600–4611. [Google Scholar] [CrossRef]
  36. Canny, J.; Reif, J. New lower bound techniques for robot motion planning problems. In Proceedings of the 28th Annual Symposium on Foundations of Computer Science, Los Angeles, CA, USA, 12–14 October 1987; pp. 49–60. [Google Scholar]
  37. Zhang, X.Y.; Duan, H.B. An improved constrained differential evolution algorithm for unmanned aerial vehicle global route planning. Appl. Soft Comput. 2015, 26, 270–284. [Google Scholar] [CrossRef]
  38. Chen, Y.; Luo, G.; Mei, Y.; Yu, J.; Su, X. UAV Path Planning Using Artificial Potential Field Method Updated by Optimal Control Theory. Int. J. Syst. Sci. 2014, 47, 1407–1420. [Google Scholar] [CrossRef]
  39. Kim, H.; Jeong, J.; Kim, N.; Kang, B. A Study on 3D Optimal Path Planning for Quadcopter UAV Based on D* Lite. In Proceedings of the International Conference on Unmanned Aircraft Systems, Atlanta, GA, USA, 11–14 June 2019; pp. 787–793. [Google Scholar]
  40. Lv, Z.; Yang, L.; He, Y.; Liu, Z.; Han, Z. 3D environment modeling with height dimension reduction and path planning for UAV. In Proceedings of the International Conference on Modelling, Identification and Control, Kunming, China, 10–12 July 2017; pp. 734–739. [Google Scholar]
  41. Song, X.; Hu, S. 2D path planning with dubins-path-based A∗ algorithm for a fixed-wing UAV. In Proceedings of the IEEE International Conference on Control Science and Systems Engineering, Beijing, China, 17–19 August 2017; pp. 69–73. [Google Scholar]
  42. Souissi, O.; Benatitallah, R.; Duvivier, D.; Artiba, A.; Belanger, N.; Feyzeau, P. Path planning: A 2013 survey. In Proceedings of the International Conference on Industrial Engineering and Systems Management, Rabat, Morocco, 28–30 October 2013; pp. 1–8. [Google Scholar]
  43. Jung, D.; Tsiotras, P. Multiresolution on-line path planning for small unmanned aerial vehicles. In Proceedings of the American Control Conference, Seattle, WA, USA, 11–13 June 2008; pp. 2744–2749. [Google Scholar]
  44. Samaniego, F.; Sanchis, J.; García-Nieto, S.; Simarro, R. UAV motion planning and obstacle avoidance based on adaptive 3D cell decomposition: Continuous space vs discrete space. In Proceedings of the IEEE Second Ecuador Technical Chapters Meeting, Salinas, Ecuador, 16–20 October 2017; pp. 1–6. [Google Scholar]
  45. Chen, F.C.; Gugan, G.; Solis-Oba, R.; Haque, A. Simple and Efficient Algorithm for Drone Path Planning. In Proceedings of the International Conference on Communications, Montreal, QC, Canada, 14–18 June2021; pp. 1–6. [Google Scholar]
  46. Chen, X.; Chen, X. The UAV dynamic path planning algorithm research based on Voronoi diagram. In Proceedings of the Chinese Control and Decision Conference, Changsha, China, 31 May–2 June 2014; pp. 1069–1071. [Google Scholar]
  47. Cekmez, U.; Ozsiginan, M.; Sahingoz, O.K. Multi colony ant optimization for UAV path planning with obstacle avoidance. In Proceedings of the International Conference on Unmanned Aircraft Systems, Arlington, VA, USA, 7–10 June 2016; pp. 47–52. [Google Scholar]
  48. Jiang, K.; Seneviratne, L.D.; Earles, S.W.E. A Shortest Path Based Path Planning Algorithm for Nonholonomic Mobile Robots. J. Intell. Robot Syst. 1999, 24, 347–366. [Google Scholar] [CrossRef]
  49. Liu, Y.-H.; Arimoto, S. Path Planning Using a Tangent Graph for Mobile Robots Among Polygonal and Curved Obstacles: Communication. Int. J. Rob. Res. 1992, 11, 376–382. [Google Scholar] [CrossRef]
  50. Ahmad, Z.; Ullah, F.; Tran, C.; Lee, S. Efficient Energy Flight Path Planning Algorithm Using 3-D Visibility Roadmap for Small Unmanned Aerial Vehicle. Int. J. Aerosp. Eng. 2017, 2017, 2849745. [Google Scholar] [CrossRef] [Green Version]
  51. Frontera, G.; Martín, D.J.; Besada, J.A.; Gu, D. Approximate 3D Euclidean Shortest Paths for Unmanned Aircraft in Urban Environments. J. Intell. Robot Syst. 2017, 85, 353–368. [Google Scholar] [CrossRef]
  52. Majeed, A.; Lee, S. A Fast Global Flight Path Planning Algorithm Based on Space Circumscription and Sparse Visibility Graph for Unmanned Aerial Vehicle. Electronics 2018, 7, 375. [Google Scholar] [CrossRef] [Green Version]
  53. Huang, S.; Teo, R.S.H. Computationally Efficient Visibility Graph-Based Generation Of 3D Shortest Collision-Free Path Among Polyhedral Obstacles For Unmanned Aerial Vehicles. In Proceedings of the International Conference on Unmanned Aircraft Systems, Atlanta, GA, USA, 11–14 June 2019; pp. 1218–1223. [Google Scholar]
  54. Maini, P.; Sujit, P.B. Path planning for a UAV with kinematic constraints in the presence of polygonal obstacles. In Proceedings of the International Conference on Unmanned Aircraft Systems, Arlington, VA, USA, 7–10 June 2016; pp. 62–67. [Google Scholar]
  55. Naazare, M.; Ramos, D.; Wildt, J.; Schulz, D. Application of Graph-based Path Planning for UAVs to Avoid Restricted Areas. In Proceedings of the IEEE International Symposium on Safety, Security, and Rescue Robotics, Würzburg, Germany, 2–4 September 2019; pp. 139–144. [Google Scholar]
  56. Chow, N.; Gugan, G.; Haque, A. RADR: Routing for Autonomous Drones. In Proceedings of the International Wireless Communications & Mobile Computing Conference, Tangier, Morocco, 24–28 June 2019; pp. 1445–1450. [Google Scholar]
  57. De Filippis, L.; Guglieri, G.; Quagliotti, F. Path Planning Strategies for UAVS in 3D Environments. J. Intell. Robot Syst. 2012, 65, 247–264. [Google Scholar] [CrossRef]
  58. Yin, C.; Xiao, Z.; Cao, X.; Xi, X.; Yang, P.; Wu, D. Offline and Online Search: UAV Multiobjective Path Planning Under Dynamic Urban Environment. IEEE Internet Things J. 2018, 5, 546–558. [Google Scholar] [CrossRef]
  59. LaValle, S.M. Rapidly-exploring random trees: A new tool for path planning; TR 98-11; Computer Science Department, Iowa State University: Ames, IA, USA, 1998. [Google Scholar]
  60. Qureshi, A.H.; Ayaz, Y. Intelligent bidirectional rapidly-exploring random trees for optimal motion planning in complex cluttered environments. Rob. Auton. Syst. 2015, 68, 1–11. [Google Scholar] [CrossRef] [Green Version]
  61. Karaman, S.; Frazzoli, E. Sampling-based algorithms for optimal motion planning. Int. J. Reb. Res. 2011, 30, 846–894. [Google Scholar] [CrossRef] [Green Version]
  62. Yang, H.; Jia, Q.; Zhang, W. An Environmental Potential Field Based RRT Algorithm for UAV Path Planning. In Proceedings of the Chinese Control Conference, Wuhan, China, 25–27 July 2018; pp. 9922–9927. [Google Scholar]
  63. Wu, K.; Xi, T.; Wang, H. Real-time three-dimensional smooth path planning for unmanned aerial vehicles in completely unknown cluttered environments. In Proceedings of the TENCON, Penang, Malaysia, 5–8 November 2017; pp. 2017–2022. [Google Scholar]
  64. Lee, D.; Song, H.; Shim, D.H. Optimal path planning based on spline-RRT* for fixed-wing UAVs operating in three-dimensional environments. In Proceedings of the International Conference on Control, Automation and Systems, Seoul, Republic of Korea, 22–25 October 2014; pp. 835–839. [Google Scholar]
  65. Galvez, R.L.; Faelden, G.E.U.; Maningo, J.M.; Nakano, R.C.S.; Dadios, E.P.; Bandala, A.A.; Vicerra, R.R.P.; Fernando, A.H. Obstacle avoidance algorithm for swarm of quadrotor unmanned aerial vehicle using artificial potential fields. In Proceedings of the TENCON, Penang, Malaysia, 5–8 November 2017; pp. 2307–2312. [Google Scholar]
  66. Chen, X.; Zhang, J. The Three-Dimension Path Planning of UAV Based on Improved Artificial Potential Field in Dynamic Environment. In Proceedings of the International Conference on Intelligent Human-Machine Systems and Cybernetics, Hangzhou, China, 26–27 August 2013; pp. 144–147. [Google Scholar]
  67. Kok, J.; Gonzalez, L.F.; Kelson, N. FPGA Implementation of an Evolutionary Algorithm for Autonomous Unmanned Aerial Vehicle On-Board Path Planning. IEEE Trans. Evol. Comput. 2013, 17, 272–281. [Google Scholar] [CrossRef] [Green Version]
  68. Roberge, V.; Tarbouchi, M.; Labonté, G. Fast Genetic Algorithm Path Planner for Fixed-Wing Military UAV Using GPU. IEEE Trans. Aerosp. Electron. Syst. 2018, 54, 2105–2117. [Google Scholar] [CrossRef]
  69. Pehlivanoglu, Y.V. A new vibrational genetic algorithm enhanced with a voronoi diagram for path planning of autonomous uav. Aerosp. Sci. Technol. 2012, 16, 47–55. [Google Scholar] [CrossRef]
  70. Chen, J.; Ye, F.; Jiang, T. Path planning under obstacle-avoidance constraints based on ant colony optimization algorithm. In Proceedings of the International Conference on Communication Technology, Chengdu, China, 27–30 October 2017; pp. 1434–1438. [Google Scholar]
  71. Al-Sabban, W.H.; Gonzalez, L.F.; Smith, R.N. Wind-energy based path planning for Unmanned Aerial Vehicles using Markov Decision Processes. In Proceedings of the International Conference on Robotics and Automation, Karlsruhe, Germany, 6–10 May 2013; pp. 784–789. [Google Scholar]
  72. Zhang, D.; Xian, Y.; Li, J.; Lei, G.; Chang, Y. UAV Path Planning Based on Chaos Ant Colony Algorithm. In Proceedings of the International Conference on Computer Science and Mechanical Automation, Hangzhou, China, 23–25 October 2015; pp. 81–85. [Google Scholar]
  73. Liu, Y.; Zhang, X.; Guan, X.; Delahaye, D. Adaptive sensitivity decision based path planning algorithm for unmanned aerial vehicle with improved particle swarm optimization. Aerosp. Sci. Technol. 2016, 58, 92–102. [Google Scholar] [CrossRef]
  74. Zhang, X.; Lu, X.; Songmin, J.; Li, X. A novel phase angle-encoded fruit fly optimization algorithm with mutation adaptation mechanism applied to UAV path planning. Appl. Soft Comput. 2018, 70, 371–388. [Google Scholar] [CrossRef]
  75. Zhang, X.; Jia, S.; Li, X.; Jiam, M. Design of the fruit fly optimization algorithm based path planner for UAV in 3D environments. In Proceedings of the IEEE International Conference on Mechatronics and Automation, Takamatsu, Japan, 6–9 August 2017; pp. 381–386. [Google Scholar]
  76. Chen, Y.B.; Mei, Y.S.; Yu, J.Q.; Su, X.L.; Xu, N. Three-dimensional unmanned aerial vehicle path planning using modified wolf pack search algorithm. Neurocomputing 2017, 266, 445–457. [Google Scholar]
  77. Lyakhov, A.O.; Oganov, A.R.; Stokes, H.T.; Zhu, Q. New developments in evolutionary structure prediction algorithm USPEX. Comput. Phys. Commun. 2013, 184, 1172–1182. [Google Scholar] [CrossRef]
  78. Azar, A.T.; Koubaa, A.; Ali Mohamed, N.; Ibrahim, H.A.; Ibrahim, Z.F.; Kazim, M.; Ammar, A.; Benjdira, B.; Khamis, A.M.; Hameed, I.A.; et al. Drone Deep Reinforcement Learning: A Review. Electronics 2021, 10, 999. [Google Scholar] [CrossRef]
  79. Bouhamed, O.; Ghazzai, H.; Besbes, H.; Massoud, Y. Autonomous UAV Navigation: A DDPG-Based Deep Reinforcement Learning Approach. In Proceedings of the IEEE International Symposium on Circuits and Systems, Seville, Spain, 10–21 October 2020; pp. 1–5. [Google Scholar]
  80. Luis, C.E.; Schoellig, A.P. Trajectory generation for multiagent point-to-point transitions via distributed model predictive control. IEEE Robot. Autom. Lett. 2019, 4, 375–382. [Google Scholar] [CrossRef] [Green Version]
  81. Li, Y.; Liang, C. Energy-aware Trajectory Planning Model for Mission-oriented Drone Networks. In Proceedings of the IEEE International Systems Conference, Vancouver, BC, Canada, 15 April–15 May 2021; pp. 1–7. [Google Scholar]
  82. Grafe, A.; Eickhoff, J.; Trimpe, S. Event-triggered and distributed model predictive control for guaranteed collision avoidace in UAV swarms. IFAC Conf. Netw. Syst. 2022, 55, 79. [Google Scholar]
  83. Vinokursky, D.L.; Mezentseva, O.S.; Samoylov, P.V.; Ganshin, K.Y.; Baklanova, O.A. Model predictive control for path planning of UAV group. IOP Conf. Ser. Mater. Sci. 2021, 1155, 012092. [Google Scholar] [CrossRef]
  84. Wu, Y.; Low, K.H.; Pang, B.; Tan, Q. Swarm-Based 4D Path Planning For Drone Operations in Urban Environments. IEEE Trans. Veh. Technol. 2021, 70, 7464–7479. [Google Scholar] [CrossRef]
  85. Liu, G.; Shu, C.; Liang, Z.; Peng, B.; Cheng, L. A Modified Sparrow Search Algorithm with Application in 3d Route Planning for UAV. Sensors 2021, 21, 1224. [Google Scholar] [CrossRef]
  86. Penicka, R.; Meng, G.; Xu, Y.; Luo, H. A geometrical path planning method for unmanned aerial vehicle in 2D/3D complex environment. Intell. Serv. Robot. 2018, 11, 301–312. [Google Scholar]
  87. Tu, G.T.; Juang, J.G. Path Planning and Obstacle Avoidance Based on Reinforcement Learning for UAV Application. In Proceedings of the International Conference on System Science and Engineering, Ho Chi Minh City, Vietnam, 26–28 August 2021; pp. 352–355. [Google Scholar]
  88. Chen, Y.; Yu, J.; Mei, Y.; Wang, Y.; Su, X. Modified central force optimization (MCFO) algorithm for 3D UAV path planning. Neurocomputing 2016, 171, 878–888. [Google Scholar] [CrossRef]
  89. Dolicanin, E.; Fetahovic, I.; Tuba, E.; Capor-Hrosik, R.; Tuba, M. Unmanned Combat Aerial Vehicle Path Planning by Brain Storm Optimization Algorithm. Stud. Inform. Control 2018, 27, 15–24. [Google Scholar] [CrossRef]
  90. Penicka, R.; Scaramuzza, D. Minimum-Time Quadrotor Waypoint Flight in Cluttered Environments. IEEE Robot. Autom. Lett. 2022, 7, 5719–5726. [Google Scholar] [CrossRef]
  91. Pötter Neto, C.A.; de Carvalho Bertoli, G.; Saotome, O. 2D and 3D A* Algorithm Comparison for UAS Traffic Management Systems. In Proceedings of the International Conference on Unmanned Aircraft Systems, Athens, Greece, 9–12 June 2020; pp. 72–76. [Google Scholar]
  92. Alyassi, R.; Khonji, M.; Karapetyan, A.; Chau, S.C.K.; Elbassioni, K.; Tseng, C.M. Autonomous Recharging and Flight Mission Planning for Battery-Operated Autonomous Drones. IEEE Trans. Autom. Sci. Eng. 2022, 1–13. [Google Scholar] [CrossRef]
  93. Mechali, O.; Xu, L.; Xie, X.; Iqbal, J. Fixed-time nonlinear homogeneous sliding mode approach for robust tracking control of multirotor aircraft: Experimental validation. J. Frank. Inst. 2022, 359, 1971–2029. [Google Scholar] [CrossRef]
  94. Song, W.; Li, Z.; Xu, B.; Wang, S.; Meng, X. Research on Improved Control Algorithm of Quadrotor UAV based on Fuzzy PID. In Proceedings of the IEEE International Conference on Artificial Intelligence and Computer Applications, Shanghai, China, 28–30 November 2022; pp. 361–365. [Google Scholar]
  95. Mechali, O.; Iqbal, J.; Xie, X.; Xu, L.; Senouci, A. Robust Finite-Time Trajectory Tracking Control of Quadrotor Aircraft via Terminal Sliding Mode-Based Active Antidisturbance Approach: A PIL Experiment. Int. J. Aerosp. Eng. 2021, 2021, 5522379. [Google Scholar] [CrossRef]
  96. Gugan, G.; Haque, A. Towards the Development of a Robust Path Planner for Autonomous Drones. In Proceedings of the IEEE Vehicular Technology Conference, Antwerp, Belgium, 25–28 May 2020; pp. 1–6. [Google Scholar]
  97. Zammit, C.; Kampen, E.J.V. Comparison between A* and RRT Algorithms for 3D UAV Path Planning. Unmanned Systems. Unmanned Syst. 2022, 10, 129–146. [Google Scholar] [CrossRef]
  98. Kang, J.; Xiong, Z.; Niyato, D.; Xie, S.; Kim, D.I. Securing Data Sharing from the Sky: Integrating Blockchains into Drones in 5G and Beyond. IEEE Netw. 2021, 35, 78–85. [Google Scholar] [CrossRef]
  99. Hassija, V.; Chamola, V.; Agrawal, A.; Goyal, A.; Luong, N.C.; Niyato, D.; Yu, F.R.; Guizani, M. Fast, Reliable, and Secure Drone Communication: A Comprehensive Survey. IEEE Commun. Surv. 2021, 23, 2802–2832. [Google Scholar] [CrossRef]
  100. Challita, U.; Saad, W.; Bettstetter, C. Deep Reinforcement Learning for Interference-Aware Path Planning of Cellular-Connected UAVs. In Proceedings of the IEEE International Conference on Communications, Kansas City, MO, USA, 20–24 May 2018; pp. 1–7. [Google Scholar]
Figure 1. Drone path planning papers published between 2000 and 2022.
Figure 1. Drone path planning papers published between 2000 and 2022.
Drones 07 00169 g001
Figure 2. Representation of an environment [42]. Reproduced with permission.
Figure 2. Representation of an environment [42]. Reproduced with permission.
Drones 07 00169 g002
Figure 3. General structure of evolutionary algorithms [77]. Reproduced with permission.
Figure 3. General structure of evolutionary algorithms [77]. Reproduced with permission.
Drones 07 00169 g003
Figure 4. Algorithm types used in the reviewed articles.
Figure 4. Algorithm types used in the reviewed articles.
Drones 07 00169 g004
Figure 5. Trajectories generated by different flight control systems (FCS) [95].
Figure 5. Trajectories generated by different flight control systems (FCS) [95].
Drones 07 00169 g005
Table 1. Analysis of 35 published drone path planning papers.
Table 1. Analysis of 35 published drone path planning papers.
Ref3DEnergy ConstraintsPath OptimizationDrone Type (F/R/N)Path Planner (ON/OFF)Obstacle Type (MV/ST)Environment Type (S/M/L)Computer SimulationsPractical Implementation (I/O)Algorithm Category
[37]FOFFSTSBA
[47]ROFFSTSBA
[71]NOFFSTSBA
[69]FOFFSTSBA
[73]NOFFSTSBA
[74]NOFFSTSBA
[70]NOFFSTMBA
[75]NOFFSTSBA
[77]R + FOFFSTSBA
[76]NOFFSTSBA
[84]NOFFSTMBA
[85]NOFFSTSBA
[40]RONST/MVMGS
[57]NOFFSTSGS
[58]RONST/MVSGS
[86]NOFFSTSGS
[31]FONSTSLA
[32]NONSTSLA
[33]NONST/MVSLA
[34]RONSTSOLA
[87]RONSTSLA
[79]RONSTSLA
[72]FONSTSOT
[88]ROFFSTSOT
[89]FOFFSTSOT
[38]ROFFSTSPF
[66]ROFFSTSOPF
[8]RONST/MVSISBA
[9]RONSTMSBA
[10]RONMVSISBA
[64]FOFFSTSSBA
[63]NONSTMSBA
[62]NOFFSTMSBA
[35]NONST/MVMSBA
[90]ROFFSTMISBA
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Gugan, G.; Haque, A. Path Planning for Autonomous Drones: Challenges and Future Directions. Drones 2023, 7, 169. https://doi.org/10.3390/drones7030169

AMA Style

Gugan G, Haque A. Path Planning for Autonomous Drones: Challenges and Future Directions. Drones. 2023; 7(3):169. https://doi.org/10.3390/drones7030169

Chicago/Turabian Style

Gugan, Gopi, and Anwar Haque. 2023. "Path Planning for Autonomous Drones: Challenges and Future Directions" Drones 7, no. 3: 169. https://doi.org/10.3390/drones7030169

Article Metrics

Back to TopTop