Next Article in Journal
Mapping Stratigraphy and Artifact Distribution with Unmanned Aerial Vehicle-Based Three-Dimensional Models—A Case Study from the Post Research Area in Northwestern Texas, USA
Previous Article in Journal
Lightweight UAV Small Target Detection and Perception Based on Improved YOLOv8-E
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Novel Energy-Aware 3D UAV Path Planning and Collision Avoidance Using Receding Horizon and Optimization-Based Control

Computer Engineering Department, Interdisciplinary Research Center of Smart Mobility and Logistics, King Fahd University of Petroleum and Minerals, Dhahran 31261, Saudi Arabia
*
Author to whom correspondence should be addressed.
Drones 2024, 8(11), 682; https://doi.org/10.3390/drones8110682
Submission received: 10 September 2024 / Revised: 22 October 2024 / Accepted: 15 November 2024 / Published: 19 November 2024

Abstract

:
Unmanned Aerial Vehicles (UAVs) have gained significant popularity in recent years thanks to their agility, mobility, and cost-effectiveness. However, UAV navigation presents several challenges, particularly in path planning, which requires determining an optimal route while avoiding obstacles and adhering to various constraints. Another critical challenge is the limited flight time imposed by the onboard battery. This paper introduces a novel approach for energy-efficient three-dimensional online path planning for UAV formations operating in complex environments. We formulate the path planning problem as a minimization optimization problem, and employ Mixed-Integer Linear Programming (MILP) to achieve optimal solutions. The cost function is designed to minimize energy consumption while considering the inter-collision and intra-collision avoidance constraints within a limited detection range. To achieve this, an optimization approach incorporating Receding Horizon Control (RHC) is applied. The entire path is divided into segments or sub-paths, with constraints used to avoid collisions with obstacles and other members of the fleet. The proposed optimization approach enables fast navigation through dense environments and ensures a collision-free path for all UAVs. A path-smoothing strategy is proposed to further reduce energy consumption caused by sharp turns. The results demonstrate the effectiveness and accuracy of the proposed approach in dense environments with high risk of collision. We compared our proposed approach against recent works, and the results illustrate that the proposed approach outperforms others in terms of UAV formation, number of collisions, and partial path generation time.

1. Introduction

Thanks to technological advancements, Unmanned Aerial Vehicles (UAVs) have acquired considerable attention. UAVs provide many notable features, including additional degrees of freedom and flexible deployment [1]. Consequently, they have been utilized in various applications in military and commercial applications, including traffic policing and control, area coverage, aerial surveillance, disaster management, precision agriculture, and search-and-rescue operations [2,3,4,5]. However, many of these applications exceed the capabilities of single UAVs due to limited sensing range, communication bandwidth, and energy constraints [6].
The use of multiple UAVs offers significant advantages such as reducing operational time and improving the robustness of path planning. However, this benefit comes with increased complexity due to the need to consider numerous constraints in path planning [7].
In this case, the demands of more sophisticated tasks often require a sophisticated path planning approach in order for UAVs to accomplish their tasks efficiently and safely. To meet the growing complexity of such applications, the development of strong robustness and high parallelism algorithms and technologies in multiple UAVs is necessary in order to enable real-time decision-making, obstacle avoidance, and path optimization, ensuring that UAVs can navigate dynamic environments effectively [8,9].
Path planning is a critical component of UAV operations and is essential for the successful execution of missions [10]. It involves identifying the optimal route for navigating towards a destination and efficiently achieving the specified objectives [11]. Path planning offers several advantages, including reduced need for human intervention, improved time and cost efficiency, optimized resource usage, and enhanced data collection and analysis capabilities. As a result, it is a valuable tool across a wide range of applications, from environmental monitoring and search and rescue to industrial automation and agriculture. However, solving the multiple-UAV path planning problem is computationally challenging, as it is classified as NP-hard [12,13]. For this reason, developing an effective strategy for multi-UAV path planning becomes particularly challenging in large-scale environments [14,15].
Currently, providing UAVs with the ability to plan collision-free paths in real time while navigating through unknown environments remains a difficult task. These environments pose difficulties because the UAVs lack information about their surroundings and because conditions are subject to constant change. Therefore, UAVs must possess the capability to perceive their environment, make decisions, and take appropriate actions while also being able to explore and acquire knowledge. Consequently, it is important to develop a methodology that can autonomously navigate and plan paths in unknown environments [16,17].
The commonly used mathematical formulation for UAV path planning problem is typically expressed as an optimization problem in which the objective functions include energy consumption, minimum delivery cost and maximum overall customer satisfaction [18], path length, and any required constraints. The next step involves using optimization calculations to determine the optimal values of these functions. Various mathematical programming algorithms, including Nonlinear Programming (NP) [19], Mixed-Integer Programming (MIP) [20], Markov decision processes [21], and Dynamic Programming (DP) [22], are commonly used in this context. These approaches have been shown to outperform approximate solution strategies based on Particle Swarm Optimization (PSO), Genetic Algorithms (GAs), and Ant Colony (AC) algorithms.
MILP can be used to address problems with multiple tasks and constraints, including UAV path planning problem. Such problems can be represented as an MILP model, highlighting the flexibility of MILP optimization in effectively addressing the complexities of UAV path planning. Various constraints have been effectively addressed using MILP in diverse applications [23,24,25,26,27]. For instance, exact optimization methods such as branch and bound and dynamic programming represent effective techniques for handling the path planning problem by developing MILP formulations and solving the problem in a short interval and within the UAV’s Field of View (FoV).
For online path planning, Receding Horizon Control (RHC) offers significant advantages in incorporating mobility and environmental constraints such as obstacles as well as constraints arising from formation relationships such as changing formation shapes. Furthermore, RHC enables a suitable level of cognitive ability through frequent replanning and adaptation to dynamic environments [28].
Despite advancements in UAV path planning, several critical challenges remain unresolved, particularly in dynamic and obstacle-dense environments. While some approaches offer solutions for path planning, they often fail to sufficiently address energy consumption, which is a vital factor for UAVs with limited battery capacity during long missions. Additionally, real-time path adjustments in highly dynamic environments remain a significant hurdle, as many existing algorithms either lack the ability to adapt in real-time or require excessive computational resources. Moreover, although various methods provide basic collision avoidance, they frequently fall short in ensuring safety, especially in environments with unpredictable moving obstacles. This is particularly problematic in densely populated areas, where collisions are difficult to avoid without precise real-time adjustment.
This research paper focuses on the development of a novel approach for guiding a fleet of UAVs through an obstacle-filled environment. The proposed approach tackles the problem of path planning by utilizing MILP, which determines the energy-efficient waypoints for UAVs. Then, the CPLEX solver is applied to obtain the exact solution for the MILP formulation. The concept of a dynamic finite horizon is implemented to solve the MILP formulation within a local spatial region that continuously updates as the UAVs progress along their paths. To minimize energy consumption, a cost function is proposed that incorporates problem constraints. The UAVs aim to reach the desired destinations while minimizing their energy consumption. The constraints of maintaining collision avoidance are imposed on UAVs throughout the entire flight duration to ensure navigation from the initial point to the final points while minimizing the cost function. Notably, we apply the energy model from [29], which was derived from real experiments that considered different maneuvering activities such as horizontal flight, vertical flight, hovering in place, turning.
The contributions of this paper are listed below:
  • We present an energy-aware path planning algorithm for multiple UAVs that incorporates collision avoidance for obstacles and between UAVs. The concept of a dynamic finite horizon is implemented to solve the MILP formulation within a local spatial region, continuously updating the UAVs’ locations as they progress along their respective paths.
  • The constraints for the path planning problem are derived and thoroughly analyzed with the aim of minimizing overall energy consumption. An MILP-based formulation is then developed to determine the optimal trajectories for all UAVs, guiding them from their starting locations to their destinations while adhering to all specified constraints.
  • We propose a safety strategy to guarantee collision avoidance in dense and highly dynamic environments.
  • A smoothing strategy is applied to the generated paths to enable smoother turns, thereby reducing energy consumption.
The rest of this paper is structured as follows: Section 2 provides a literature review; in Section 3, we introduce our proposed energy-efficient UAV path planning approach addressing collision avoidance, present the MILP-based problem formulation, and include a detailed discussion and analysis of the optimization problem alongside our proposed path smoothing strategy; Section 4 presents the results and corresponding analysis; finally, our conclusions are provided in Section 5.

2. Literature Review

Currently, real-time online UAV path planning in unknown environments with collision avoidance is a challenging task. These environments pose a challenge because the UAVs lack information about their surroundings and the conditions are prone to constant changes. Therefore, the UAVs need to be able to perceive their environment, make decisions, and take appropriate actions while also being able to explore and acquire knowledge. Consequently, it is important to develop a methodology that allows UAVs autonomously navigate and plan paths in unknown environments. A number of previous works have addressed UAV path planning. This section reviews some of the literature on UAV path planning.
The work in [30] presented an algorithm that combines model predictive control and a genetic algorithm to enable cooperative searching of unknown areas by multiple UAVs. By incorporating the strengths of both genetic algorithms and MPC, this algorithm aims to overcome the issue of local optima. The genetic algorithm provides flexibility and exploration capabilities, while MPC contributes predictive abilities that enhance the overall search performance in unknown environments. However, employing a genetic algorithm for online path planning is often impractical, as the time-intensive nature of GAs can hinder real-time decision-making and responsiveness in dynamic environments.
In [31], the authors proposed a trajectory planner for cooperative UAVs using B-spline curves, potential fields, and differential evolution to avoid collisions with obstacles and generate smooth trajectories in both known and unknown static environments. However, as this approach is restricted to static environment, it cannot be applied in dynamic contexts.
The work introduced in [32] proposed formation control of mobile robots combining model predictive control and particle swarm optimization. The aim was to achieve stable and collision-free formation control while reducing computational complexity. However, it was only applied in a 2D environment. Moreover, employing particle swarm optimization for online path planning is often impractical due its time-intensive operation, which can hinder real-time decision-making and responsiveness in dynamic environments.
The work described in [33] allows for the maintenance of formations with varying shapes over time. However, it is restricted to flat environments with no obstacles, and its testing was limited to simple circular trajectories.
In [34], the authors proposed a planning and control framework for UAV formation using the A* algorithm. In [35], the A* algorithm was replaced with PSO and spline-path planning, resulting in better paths. However, this approach is primarily adapted to 2D scenarios, and offers limited guidance for extension to 3D environments. Moreover, employing particle swarm optimization for online path planning is often time-intensive, which can hinder real-time decision-making and responsiveness in dynamic environments. In [36], A* was replaced by the Fast Marching Method (FMM) in a practical maritime environment. However, as this method is primarily adapted to 2D scenarios, it offers limited guidance for extension to 3D environments.
The work in [37] proposed the Multi-Strategy Improved Sand Cat Swarm Optimization Algorithm as an improved approach to Sand Cat Swarm Optimization for UAV trajectory planning, addressing the limitations of existing algorithms and demonstrating its effectiveness through experimental results.
The work in [38] proposed utilizing turn angles for safe navigation and avoiding collisions among multiple collaborating robots. The paths were optimized to minimize energy consumption and mission duration while avoiding collisions. However, this approach is primarily adapted to 2D scenarios, and offers limited guidance for extension to 3D environments.
In [39], the UAV path optimization problem was formulated via MILP and solved using the CPLEX solver. In [40], the UAV path planning problem was formulated as a maximization optimization problem based on MILP, with target tracking performance as the goal to be maximized. In [27], an MILP formulation was used to address the maximization of coverage and monitoring time to ensure continuous monitoring by UAVs at any given time.
The work in [41] proposed a lightweight real-time path planning method for UAVs based on reinforcement learning. The goal of was to solve UAV path planning in complex urban environments while addressing constraints such as limited computational resources and real-time responsiveness.
In [42], the use of reinforcement learning in path planning for autonomous UAVs operating Beyond Visual Line-of-Sight (BVLOS) in dynamic environments was explored. This study aimed to develop a navigation system allowing UAVs to autonomously navigate through unknown environments while avoiding obstacles. The authors utilized the Advantage Actor–Critic (A2C) algorithm, which is a model-free RL method, to guide the UAV from a starting point to a target using input from limited sensors while avoiding collisions.
The authors of [43] introduced a dynamically constructed graph that limits agents to local planning actions. Although this can enhance path exploration, the approach cannot be applied to real robots due to challenges related to localization and perception uncertainties.
The study in [44] combined a traditional collision avoidance technique with a Deep Reinforcement Learning (DRL) approach to enable effective long-term trajectory planning in the presence of unknown obstacles.
Although there have been many notable works in the literature regarding collision avoidance and path planning for UAVs, some of these studies focus only on single UAVs, while others primarily focus on avoiding static obstacles in 2D environments and neglect 3D environments. Furthermore, many works that consider both static and dynamic obstacles deal with only simple scenarios involving very light obstruction in large environments where the probability of a collision is very low. Such approaches cannot be apply in complex and highly dense environments. Although reinforcement learning approaches have introduced online path navigation in real time, they demand significant training time and face scalability challenges in resource-constrained environments. Moreover, most existing works do not consider energy consumption in the context of formation flight, which is crucial for long-duration UAV operations. In contrast, our method is explicitly designed to minimize energy consumption through the proposed MILP formulation, allowing us to simultaneously optimize not just for collision avoidance but also for energy-efficient UAV operation.
Thus, to address the aforementioned limitations of existing research, we propose an online energy-aware path planning strategy for formation flight that allows UAVs to operate effectively even in highly dense and dynamic environments while ensuring collision-free paths for the UAV formation and simultaneously minimizing energy consumption.

3. Description of Energy-Aware Trajectory Planning for UAVs

The objective of our proposed path planning technique is to reduce energy consumption while ensuring collision avoidance. The approach proposed in this study offers a promising solution for achieving energy-efficient operation and extending the flight duration of UAVs. The concept behind the RHC method is to create a moving time window at each sampling interval, solve the the path planning problem to obtain the optimal solution within that window, and then shift the window forward based on a predefined time step. Its real-time capabilities and optimization provide significant advantages in an online path planning. Moreover, a finite horizon can be employed to restrict the area around the UAV. This finite horizon is designed to be sufficiently large to allow the UAV to maneuver and avoid collisions while keeping the computation time manageable. The duration required for collision avoidance depends on the UAV’s velocity and the predicted collision position. Figure 1 shows a schematic diagram of a UAV path through an environment filled by obstacles. In the figure, the horizon is defined by the UAV’s FoV (the square area).
The specific procedure for each UAV is described in Algorithm 1, which has the following steps:
  • Step 1: At sampling time t 0 , initialize the UAVs and environment information and construct the rolling time window T w . The environment information involves the size of segment for which paths and obstacles are to be planned.
  • Step 2: Decompose the segment area represented by each UAV’s FoV into cells. Then, formulate the path planning within the segment as a minimization optimization problem based on an MILP and apply the optimization objective function for minimum energy consumption.
  • Step 3: Solve the problem using an optimization solver (CPLEX solver) and find the optimal path that minimizes energy consumption while meeting all constraints.
  • Step 4: Smooth the generated path and update the UAV locations and information on the environment.
  • Step 5: In the next sampling, repeat Steps 2–4 until the destination is reached.
Algorithm 1: Energy-Aware UAV Path Planning Algorithm
Drones 08 00682 i001
Figure 2 illustrates the the proposed approach with a block diagram. The following subsections explain the different parts of the proposed approach in detail.
The different symbols used in this study are defined in Table 1.

3.1. Collision Avoidance Module

To avoid obstacles, we consider a safety margin around the obstacle, as in [45,46]. The obstacle constraints can be represented by penalizing the path by a high value if it passes through obstacles. This module is responsible for formulating the constraints related to collisions with obstacles as well as with other members of the UAV fleet. The module is integrated into the MILP formulation while enforcing constraints to guarantee safe navigation. A safety margin around each obstacle ensures that the UAVs maintain minimum safe distance from obstacles while navigating. This module penalizes any path that collides with obstacles, effectively steering the UAVs away from obstacles. The constraint for obstacle avoidance is mathematically expressed by the problem constraints in Equation (1)e.
This module also handles collisions between UAVs operating in the same space. To prevent UAVs from approaching each other too closely, the module enforces a minimum separation distance S D m i n between any two UAVs. This ensures that the UAV fleet operates safely in a coordinated manner without risking inter-UAV collisions. The constraint for UAV-to-UAV collision avoidance is mathematically expressed by the problem constraints in Equation (1)d.

3.2. MILP Solution Module

This module receives the objective and constraints, then formulates the problem through the following parts.

3.2.1. Segment Area Decomposition

The given segment area is decomposed to generate all possible waypoints using the region decomposition technique. The required waypoints are incorporated into the MILP formulation as constraints. The path planning problem is then formulated as a minimization problem with the aim of reducing energy consumption as much as possible. It has to be stressed that the endpoint within a segment is the closest point to the actual destination. Finally, the problem is solved using the CPLEX solver and the collision-free path is generated. For more information about the segmentation process, we refer the reader to [46].

3.2.2. MILP-Based Formulation

The objective is to navigate through a dense environment in order to deliver the UAVs to the destination safely and with high energy efficiency.
Let N p be the number of possible locations in the segment defined by the UAV’s FoV; in addition, N o b s indicates the number of obstacles, N d refers to the number of UAVs, Eu represents the available energy for UAV u, and E i j denotes the energy used to travel from position i to position j.
The decision variables of the target path planning problem are inspired by the classical MILP formulation. The collision decision variable O C i j is the cost of collision with obstacles, and can be written as follows:
O C i j = i n f if the path from p o s i t i o n i and p o s i t i o n j collides with obstacle , 0 O t h e r w i s e .
The decision variable x i j can be written as follows:
x i j = 1 if a UAV moves from p o s i t i o n i to p o s i t i o n j , 0 O t h e r w i s e .
For the intermediate decision variable, y i is an additional variable indicating whether position i is visited or not, and can be written as follows:
y i = 1 if l o c a t i o n i is visited , 0 O t h e r w i s e .
The aim of these constraints is to provide a collision-free path that safely delivers the UAVs to the destination. The objective function considers both path planning and collision avoidance.
In light of this definition, we formulate the following optimization problem for minimizing flight energy consumption by optimizing the path of the UAVs while considering the given constraints:
min Energy ObjFun = i = 1 N p j = 2 , i j N p ( E ij x ij + OC ij x ij ) s . t . ( a ) : x s m i n x n x s m a x , n N p , ( b ) : y s m i n y n y s m a x , n N p , ( c ) : z m i n z n z m a x , n N p , ( d ) : U i U j 2 S D m i n , i , j N d . ( e ) : U i O b s j 2 M a r g i n , i N d , j N o b s . ( f ) : j = 1 N p x i j 1 , i N p , ( g ) : j = 1 N p x 1 j = j = 1 N p x j g = 1 ( h ) : j = 1 N p E i j j = 1 N p E j i = 0 , i [ 2 N p ] . ( i ) : i = 1 N p j = 1 N p E i j x i j E u . ( j ) : i = 1 N p j = 1 N p { x j i x i k y i } , k [ 2 N p ] , ( k ) : x i j , y i [ 0 , 1 ] , i , j N p .
The constraints in Equation (1)a, Equation (1)b, and Equation (1)c represent the allowed range for the UAV in its FoV, where x s m i n and x s m a x , y s m i n and y s m a x , and z m i n and z m a x are the minimum and maximum values of x n , y n , and z n , respectively. The constraint in Equation (1)d ensures collision avoidance, where S D m i n is the minimum allowed distance among UAVs. The constraint in Equation (1)e ensures collision avoidance with obstacles, where Margin is the margin around obstacles. The constraint in Equation (1)f ensures that a maximum of only one link exists from location i to location j. The constraint in Equation (1)g ensures that there is only one start and one end location for each UAV. The constraint in Equation (1)h ensures that the flying energy from location i to location j is the same as the flying energy from location j to location i. The constraint in Equation (1)i seeks to ensure that the flying energy from location i to location j is sufficient. This constraint enables the UAV to return to a base station for recharging when its energy consumption is not sufficient to complete the mission. The constraint in Equation (1)j is the intermediate location constraint indicating whether a location i is in the waypoints of the path. Finally, the constraint in Equation (1)k ensures that x and y are binary variables.
To summarize the above steps, the path planning problem is formulated via MILP and solved using the CPLEX solver.
  • Problem Formulation: The UAV path planning problem is formulated as a Mixed-Integer Linear Programming (MILP) problem with the aim of minimizing energy consumption while ensuring collision avoidance. The objective function and constraints are defined to ensure that the UAVs remain within their operational boundaries and avoid obstacles.
  • Segment Decomposition: The entire path is broken into smaller segments based on the FoV of the UAVs. To reduce computational complexity, each segment is optimized separately.
  • Optimization Solution: The MILP problem is solved for each segment using the CPLEX solver. The solver computes the optimal path that minimizes energy consumption while satisfying all constraints.
  • Receding Horizon Control (RHC): This process is repeated iteratively for each new segment as the UAV progresses, enabling real-time path planning adjustments in response to changes in the environment.

3.3. Safety Ensurance Approach

In some cases, certain constraints may not be achievable due to complex environmental conditions. For instance, there may be no available waypoints to follow within the UAV’s FoV, making horizontal flight impossible and collision avoidance challenging. In such scenarios, the proposed Safety Ensurance Approach (SEA) allows the UAV to fly vertically and bypass incoming obstacles, ensuring safe and collision-free UAV operation.

3.4. Smoothing Strategy

The path generated by the proposed algorithm consists of waypoints; however, the path segments connecting these waypoints are composed of linear segments, making it challenging for a specific UAV to track them smoothly. Furthermore, making turns consumes a significant amount of energy for a UAV. Therefore, it is necessary to enhance the path by making it smoother in order to ensure suitability for the UAV. The primary objective is to generate an energy efficient path that adheres to the maximum curvature constraint of the UAV. To achieve this objective, we apply a quadratic Bezer curves to the generated segments, smoothing them out and reducing the impact of turns on energy consumption. Figure 3 shows the control points and provides a schematic representation of the path-smoothing strategy.

4. Results and Simulations

To assess the effectiveness of our proposed strategy in efficiently avoiding obstacles while minimizing energy consumption, we conducted a simulation using the Matlab tool (https://www.mathworks.com/products/matlab.html, accessed on 14 November 2024). The optimization feature of the proposed formulation allows for fast convergence, which makes it suitable for handling dense environments characterized by large number of static and dynamic obstacles. In this scenario, the UAVs need to navigate quickly and safely around multiple obstacles. To account for such high-density environments, we used the following parameter settings:
  • Environment: We considered two scenarios; in the first, the environment involved nine static obstacles distributed across a 100 m by 100 m area, while in the second fifteen static obstacles were distributed across a 100 m by 300 m area.
  • Dynamic obstacles: Fifteen dynamic obstacles moving at random speeds and in random direction were considered.
  • UAV fleet: The formation involved five UAVs flying from starting points to destination points.
  • Maximum elevation: The UAVs flew at an altitude of 50 m, and the maximum altitude was restricted 120 m, which was the maximum height of the obstacles.
  • Safety distance: A safe distance of 5 m was maintained among the UAVs.
  • UAV speed: The maximum allowed UAV speed was 10 m/s.
To demonstrate the effectiveness of the proposed approach, the simulation considered different scenarios involving various obstacles. In addition, we examined the influence of the obstacles on energy consumption by simulations involving only static obstacles and simulations including both static and dynamic obstacles. The simulations were executed on a PC with an Intel Core i7 CPU and 16 GB of memory.

4.1. UAV Path Planning Performance

This subsection describes the results of our tests on the ability of proposed approach to safely deliver UAVs to the destination.

4.1.1. Static Environment Scenario

We considered both 2D and 3D scenarios. The 2D scenario focused on static obstacles with different 2D views of the UAV paths. The UAVs flew from the starting position to the destination following the generated energy-efficient and collision-free path. The results are illustrated in Figure 4. The figure shows narrow passages, especially in scenarios 3, 4, 5, and 6. The aim of these scenarios was to test the ability of the UAVs to navigate through such narrow passages using our proposed approach. It can be easily observed that our approach successfully generates collision-free paths in all scenarios.
In the 3D scenario, the obstacles were randomly generated throughout the environment, creating narrow passages for the UAVs to navigate. We considered a 3D environment with static obstacles. First, we tested the ability of the SEA to avoid obstacles in an environment in which there was no passage for the UAV to navigate; the results are illustrated in Figure 5. The UAVs flew vertically to efficiently avoid collision with obstacles and arrived safely at the destination. Next, we considered two scenarios with a swarm of five UAVs flying from starting points to destinations in a dense environment involving obstacles with narrow passages. These two scenarios were considered to show the effect of obstacles on energy consumption, which is discussed further in Section 4.2. The results of the paths for the 2D and 3D scenarios are shown in Figure 6 and Figure 7. In each scenario, UAVs faced different obstacles in their paths. Figure 6a,b (for scenario 1) and Figure 7a,b (for scenario 2) demonstrate the significant advantages of the proposed approach in generating efficient paths for all UAVs. Our proposed approach efficiently avoids obstacles by maneuvering around them or enabling vertical flight when no horizontal path is available. As an example, UAV3 tries to avoid obstacles in its path; however, there is no horizontal path available. The SEA enables UAV3 to fly vertically and avoid the obstacles, while the other UAVs have a chance to avoid the obstacles by flying horizontally around them.

4.1.2. Dynamic Environment Scenario

To further test the proposed approach, we considered a highly dense environment with both static and dynamic obstacles, including fifteen static obstacles and fifteen dynamic obstacles. The dynamic obstacles moved at random directions and with random speeds. To show the effectiveness of the proposed approach in avoiding dynamic obstacles, we recorded the minimum distance between the UAVs and the obstacles. The results are exhibited in Figure 8, where the X-axes represent the margins around the obstacles and the Y-axes represent the minimum distance from UAVs to dynamic obstacles. It can be observed that the minimum distance is always greater than the margin, proving that no collisions occurred with dynamic obstacles.

4.2. Energy Consumption Performance

One of the most important metrics for assessing the algorithm’s performance is energy consumption. It illustrates how the algorithm can produce a collision-free path while consuming the least amount of energy. Without loss of generality, we divide the energy over the required optimal energy when a UAV travels the shortest path from its starting point to its destination at its maximum speed. We simulated a variety of environmental conditions, including both static and dynamic environments. Figure 6c shows the normalized average energy consumed for the mission in the static situation. Notably, different levels of energy consumption are depicted with the variations in the obstacles along the path from the starting point to the destination.
Figure 7c presents an additional static environment scenario that demonstrates variations in UAV energy consumption influenced by diverse environmental constraints. Notably, UAVs 1 and 5 exhibit minimal energy consumption due to fewer obstacles in their direct path from start to end. The UAVs can efficiently navigate, bypassing obstacles easily without the need to fly vertically or make a longer turn around obstacles. Conversely, the presence of numerous barriers between the starting and ending points of UAVs 2, 3, and 4 requires them to enable SEA in order to avoid flying through the obstacles, which consumes additional energy.
To study the effectiveness of the proposed smoothing approach on energy consumption, we applied a smoothing strategy to the generated paths and compared the results with those of the non-smoothed paths. The normalized energy consumption was recorded with and without the smoothing approach. The results depicted in Figure 6c and Figure 7c clearly show that the paths with smoothing exhibit lower energy consumption and improved the performance. A notable improvement in energy consumption is evident. The reason behind this improvement is that sharp turns require the UAV to decelerate and accelerate, which consumes additional energy. The smoothing approach mitigates the effect of these sharp turns, leading to reduced energy consumption.

4.3. Effect of Obstacles on Energy Performance

Obstacles can obstruct the flight path of the UAV. To navigate around these obstacles, UAVs may need to change their flight trajectory, which often requires increased power consumption as the system must works harder to maneuver, leading to higher energy consumption. In this subsection, we study the effect of obstacles on energy consumption. We considered a static environment with fifteen static obstacles as well as a dynamic environment with fifteen static obstacles and fifteen dynamic obstacles. For each scenario, we recorded the average normalized energy for 30 runs. Figure 9 depicts the results for the static and dynamic environments. As Figure 9 illustrates, less energy is consumed in the static environment than in the dynamic one. This is because the UAVs rarely fly in the z-direction in a static environment. In the dynamic environment, more energy is required to avoid moving obstacles that can suddenly appear in front of the UAVs and force them to make decisions such as flying vertically to avoid collisions. As a result, there is an increase in overall energy consumption.

4.4. Comparison with Other Approaches

To validate our proposed approach, we compared it against the strategies presented in [45,47]. The comparison involved three significant parameter metrics: UAV formation, total collisions with obstacles (NoCs), and time needed to generate a partial path, i.e., duration time (DT). The comparison was conducted over 30 iterations and had a maximum speed of 10 mps.
It must be stressed that the proposed algorithm generated collision-free paths and provided the shortest duration time (DT). In this particular scenario, we consider a densely static and dynamic obstacles environment. Table 2 summarizes the UAV formations, NoCs, and DT. The table also shows the number of collisions in static and dynamic environments in the second and fifth columns, respectively.
The results reveal that every method effectively generates safe paths with zero collisions in the static environment. However, the approach from [47] produces ten collisions in the dense environment, while the proposed approach and the approach from [45] both achieve zero collisions. Notably, the proposed algorithm outperforms the approach presented in [47] in terms of UAV formation and scenario duration time (DT). The proposed approach effectively handles drone-to-drone collision avoidance, ensuring the safety of the entire UAV fleet. Furthermore, it also outperforms the work from [45] in terms of the time required for path generation within the UAV FoV. The reason for this is the simplicity of our linear optimization based on an MILP formulation and solved by CPLEX compared to the nonlinear optimization solved by SQP in [45].

5. Conclusions

In this study, a three-dimensional energy-efficient online path planning approach for UAVs is proposed based on Mixed-Integer Linear Programming (MILP) and path smoothing. The proposed approach aims to reduce energy consumption by smoothing paths and minimizing the impact of sharp turns. The proposed approach effectively addresses the path planning problem by formulating it as an MILP problem and incorporating a cost function that minimizes energy consumption while considering terrain obstacle avoidance. By utilizing a receding horizon control and optimization strategy, the path is divided into segments with collision avoidance constraints. The proposed safety ensurance approach allows UAVs to fly vertically in order to guarantee safe delivery to the destination. We evaluated the impact of obstacles on path generation and energy consumption, finding that the proposed approach enables fast and accurate navigation in dense environments while ensuring collision-free paths. The results obtained from implementation of our approach demonstrate its effectiveness and accuracy in complex environments with high risk of collisions. We compared our proposed approach against recent works, with the results illustrating that it outperforms other approaches in terms of number of collisions, time required for partial path generation, and UAV formation.
In future work, we aim to allow UAVs to learn from the environment using a reinforcement learning approach and to optimize the tradeoff between energy efficiency and computational requirements in real time.

Author Contributions

Conceptualization, G.A. and T.S.; methodology and Software, G.A. and T.S.; writing—original draft preparation, G.A.; formal analysis, writing—review and editing G.A. and T.S.; investigation. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by Project Number INML2421 under the interdisciplinary center of smart mobility and logistics at King Fahd University of Petroleum and Minerals.

Data Availability Statement

The original contributions presented in the study are included in the article, further inquiries can be directed to the corresponding author.

Acknowledgments

This work was supported by King Fahd University of Petroleum and Minerals and the Interdisciplinary Center for Smart Mobility and Logistics at King Fahd University of Petroleum and Minerals (grant number [INML2421]).

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Zuo, Y.; Tharmarasa, R.; Jassemi-Zargani, R.; Kashyap, N.; Thiyagalingam, J.; Kirubarajan, T.T. MILP formulation for aircraft path planning in persistent surveillance. IEEE Trans. Aerosp. Electron. Syst. 2020, 56, 3796–3811. [Google Scholar] [CrossRef]
  2. Majeed, A.; Hwang, S.O. A multi-objective coverage path planning algorithm for UAVs to cover spatially distributed regions in urban environments. Aerospace 2021, 8, 343. [Google Scholar] [CrossRef]
  3. Alabsari, N.; Saif, A.W.A.; El-Ferik, S.; Duffua, S.; Derbel, N. Cooperative Flight Control of a Fleet of Quadrotors Using Fractional Sliding Mode with Potential Field Algorithms. IEEE Access 2024, 12, 24525–24543. [Google Scholar] [CrossRef]
  4. Ahmed, G.A.; Sheltami, T.R.; Mahmoud, A.S.; Imran, M.; Shoaib, M. A Novel Collaborative IoD-Assisted VANET Approach for Coverage Area Maximization. IEEE Access 2021, 9, 61211–61223. [Google Scholar] [CrossRef]
  5. Imran, I.H.; Alyazidi, N.M.; Eltayeb, A.; Ahmed, G. Robust Adaptive Fault-Tolerant Control of Quadrotor Unmanned Aerial Vehicles. Mathematics 2024, 12, 1767. [Google Scholar] [CrossRef]
  6. Cabreira, T.M.; Di Franco, C.; Ferreira, P.R.; Buttazzo, G.C. Energy-aware spiral coverage path planning for uav photogrammetric applications. IEEE Robot. Autom. Lett. 2018, 3, 3662–3668. [Google Scholar] [CrossRef]
  7. Ahmed, G.; Sheltami, T.; Mahmoud, A.; Yasar, A. IoD swarms collision avoidance via improved particle swarm optimization. Transp. Res. Part Policy Pract. 2020, 142, 260–278. [Google Scholar] [CrossRef]
  8. Chen, J.; Zhang, Y.; Wu, L.; You, T.; Ning, X. An adaptive clustering-based algorithm for automatic path planning of heterogeneous UAVs. IEEE Trans. Intell. Transp. Syst. 2021, 23, 16842–16853. [Google Scholar] [CrossRef]
  9. Ahmed, G.A.; Sheltami, T.R.O.; Mahmoud, A.S.; Yasar, A. 3D Simulation Model for IoD-to-Vehicles Communication in IoD-assisted VANET. Front. Built Environ. 2023, 9, 1287373. [Google Scholar] [CrossRef]
  10. Yavari, M.; Gupta, K.; Mehrandezh, M. Interleaved Predictive Control and Planning for an Unmanned Aerial Manipulator with on-the-Fly Rapid Re-Planning in Unknown Environments. IEEE Trans. Autom. Sci. Eng. 2022, 20, 1690–1705. [Google Scholar] [CrossRef]
  11. Ahmed, G.; Sheltami, T. A Safety System For Maximizing Operated UAVs Capacity Under Regulation Constraints. IEEE Access 2023, 11, 139069–139081. [Google Scholar] [CrossRef]
  12. Ng, K.; Sancho, N. Regional surveillance of disjoint rectangles: A travelling salesman formulation. J. Oper. Res. Soc. 2009, 60, 215–220. [Google Scholar] [CrossRef]
  13. Sheltami, T.; Ahmed, G.; Yasar, A. An Optimization Approach of IoD Deployment for Optimal Coverage Based on Radio Frequency Model. CMES-Comput. Model. Eng. Sci. 2024. [Google Scholar] [CrossRef]
  14. Xu, W.; Zhang, T.; Mu, X.; Liu, Y.; Wang, Y. Trajectory Planning and Resource Allocation for Multi-UAV Cooperative Computation. IEEE Trans. Commun. 2024, 72, 4305–4318. [Google Scholar] [CrossRef]
  15. Lyu, L.; Jiang, H.; Yang, F. Improved Dung Beetle Optimizer Algorithm with Multi-Strategy for global optimization and UAV 3D path planning. IEEE Access 2024, 12, 69240–69257. [Google Scholar] [CrossRef]
  16. AlMania, Z.; Sheltami, T.; Ahmed, G.; Mahmoud, A.; Barnawi, A. Energy-Efficient Online Path Planning for Internet of Drones Using Reinforcement Learning. J. Sens. Actuator Netw. 2024, 13, 50. [Google Scholar] [CrossRef]
  17. Ahmed, G.; Sheltami, T.; Mahmoud, A. Energy-Efficient Multi-UAV Multi-Region Coverage Path Planning Approach. Arab. J. Sci. Eng. 2024, 49, 13185–13202. [Google Scholar] [CrossRef]
  18. Lu, F.; Jiang, R.; Bi, H.; Gao, Z. Order Distribution and Routing Optimization for Takeout Delivery under Drone–Rider Joint Delivery Mode. J. Theor. Appl. Electron. Commer. Res. 2024, 19, 774–796. [Google Scholar] [CrossRef]
  19. Karatas, T.; Bullo, F. Randomized searches and nonlinear programming in trajectory planning. In Proceedings of the 40th IEEE Conference on Decision and Control (Cat. No. 01CH37228), Orlando, FL, USA, 4–7 December 2001; Volume 5, pp. 5032–5037. [Google Scholar]
  20. Chaudhry, A.; Misovec, K.; D’Andrea, R. Low observability path planning for an unmanned air vehicle using mixed integer linear programming. In Proceedings of the 2004 43rd IEEE Conference on Decision and Control (CDC)(IEEE Cat. No. 04CH37601), Nassau, Bahamas, 14–17 December 2004; Volume 4, pp. 3823–3829. [Google Scholar]
  21. Ragi, S.; Chong, E.K. UAV path planning in a dynamic environment via partially observable Markov decision process. IEEE Trans. Aerosp. Electron. Syst. 2013, 49, 2397–2412. [Google Scholar] [CrossRef]
  22. Mokrane, A.; BRAHAM, A.C.; Cherki, B. UAV path planning based on dynamic programming algorithm on photogrammetric DEMs. In Proceedings of the 2020 International Conference on Electrical Engineering (ICEE), Istanbul, Turkey, 25–27 September 2020; pp. 1–5. [Google Scholar]
  23. Alidaee, B.; Wang, H.; Landram, F. A note on integer programming formulations of the real-time optimal scheduling and flight path selection of UAVs. IEEE Trans. Control. Syst. Technol. 2009, 17, 839–843. [Google Scholar] [CrossRef]
  24. Song, B.D.; Kim, J.; Kim, J.; Park, H.; Morrison, J.R.; Shim, D.H. Persistent UAV service: An improved scheduling formulation and prototypes of system components. J. Intell. Robot. Syst. 2014, 74, 221–232. [Google Scholar] [CrossRef]
  25. Nigam, N.; Bieniawski, S.; Kroo, I.; Vian, J. Control of multiple UAVs for persistent surveillance: Algorithm and flight test results. IEEE Trans. Control. Syst. Technol. 2011, 20, 1236–1251. [Google Scholar] [CrossRef]
  26. Shen, Y.; Fan, G. RHC Method Based 2D-equal-step Path Generation for UAV Swarm Online Cooperative Path Planning in Dynamic Mission Environment. In Proceedings of the 2023 3rd International Conference on Artificial Intelligence, Automation and Algorithms, Beijing, China, 21–23 July 2023; pp. 1–9. [Google Scholar]
  27. Song, B.D.; Kim, J.; Morrison, J.R. Rolling horizon path planning of an autonomous system of UAVs for persistent cooperative service: MILP formulation and efficient heuristics. J. Intell. Robot. Syst. 2016, 84, 241–258. [Google Scholar] [CrossRef]
  28. Luo, J.; Tian, Y.; Wang, Z. Research on Unmanned Aerial Vehicle Path Planning. Drones 2024, 8, 51. [Google Scholar] [CrossRef]
  29. Di Franco, C.; Buttazzo, G. Coverage path planning for UAVs photogrammetry with energy and resolution constraints. J. Intell. Robot. Syst. 2016, 83, 445–462. [Google Scholar] [CrossRef]
  30. Tian, J.; Zheng, Y.; Zhu, H.; Shen, L. A MPC and genetic algorithm based approach for multiple UAVs cooperative search. In Proceedings of the Computational Intelligence and Security: International Conference, CIS 2005, Xi’an, China, 15–19 December 2005; Proceedings Part I. Springer: Berlin/Heidelberg, Germany, 2005; pp. 399–404. [Google Scholar]
  31. Nikolos, I.; Tsourveloudis, N.; Valavanis, K. Evolutionary algorithm based path planning for multiple UAV cooperation. In Advances in Unmanned Aerial Vehicles: State of the Art and the Road to Autonomy; Springer: Berlin/Heidelberg, Germany, 2007; pp. 309–340. [Google Scholar]
  32. Lee, S.M.; Myung, H. Receding horizon particle swarm optimisation-based formation control with collision avoidance for non-holonomic mobile robots. IET Control Theory Appl. 2015, 9, 2075–2083. [Google Scholar] [CrossRef]
  33. Ribeiro, T.T.; Ferrari, R.; Santos, J.; Conceição, A.G. Formation control of mobile robots using decentralized nonlinear model predictive control. In Proceedings of the 2013 IEEE/ASME International Conference on Advanced Intelligent Mechatronics, Wollongong, Australia, 9–12 July 2013; pp. 32–37. [Google Scholar]
  34. Hao, Y.; Agrawal, S.K. Planning and control of UGV formations in a dynamic environment: A practical framework with experiments. Robot. Auton. Syst. 2005, 51, 101–110. [Google Scholar] [CrossRef]
  35. Saska, M.; Spurnỳ, V.; Vonásek, V. Predictive control and stabilization of nonholonomic formations with integrated spline-path planning. Robot. Auton. Syst. 2016, 75, 379–397. [Google Scholar] [CrossRef]
  36. Liu, Y.; Bucknall, R. The angle guidance path planning algorithms for unmanned surface vehicle formations by using the fast marching method. Appl. Ocean. Res. 2016, 59, 327–344. [Google Scholar] [CrossRef]
  37. Liu, L.; Lu, Y.; Yang, B.; Yang, L.; Zhao, J.; Chen, Y.; Li, L. Research on a Multi-Strategy Improved Sand Cat Swarm Optimization Algorithm for Three-Dimensional UAV Trajectory Path Planning. World Electr. Veh. J. 2024, 15, 244. [Google Scholar] [CrossRef]
  38. Rodríguez, F.; Díaz-Báñez, J.; Fabila-Monroy, R.; Caraballo, L.; Capitán, J. Collision-free path planning for multiple robots using efficient turn-angle assignment. Robot. Auton. Syst. 2024, 177, 104698. [Google Scholar] [CrossRef]
  39. Bellingham, J.S.; Tillerson, M.; Alighanbari, M.; How, J.P. Cooperative path planning for multiple UAVs in dynamic and uncertain environments. In Proceedings of the 41st IEEE Conference on Decision and Control, Las Vegas, NV, USA, 10–13 December 2002; Volume 3, pp. 2816–2822. [Google Scholar]
  40. Ragi, S.; Mittelmann, H.D. Mixed-integer nonlinear programming formulation of a UAV path optimization problem. In Proceedings of the 2017 American Control Conference (ACC), Seattle, WA, USA, 24–26 May 2017; pp. 406–411. [Google Scholar]
  41. Xi, M.; Dai, H.; He, J.; Li, W.; Wen, J.; Xiao, S.; Yang, J. A lightweight reinforcement learning-based real-time path planning method for unmanned aerial vehicles. IEEE Internet Things J. 2024, 11, 21061–21071. [Google Scholar] [CrossRef]
  42. Chronis, C.; Anagnostopoulos, G.; Politi, E.; Garyfallou, A.; Varlamis, I.; Dimitrakopoulos, G. Path planning of autonomous UAVs using reinforcement learning. In Proceedings of the Journal of Physics: Conference Series: 12th EASN International Conference on “Innovation in Aviation & Space for Opening New Horizons”, Barcelona, Spain, 18–21 October 2022; IOP Publishing: Bristol, UK, 2023; Volume 2526, p. 012088. [Google Scholar]
  43. Vashisth, A.; Ruckin, J.; Magistri, F.; Stachniss, C.; Popovic, M. Deep reinforcement learning with dynamic graphs for adaptive informative path planning. IEEE Robot. Autom. Lett. 2024, 9, 7747–7754. [Google Scholar] [CrossRef]
  44. Zhang, S.; Li, Y.; Ye, F.; Geng, X.; Zhou, Z.; Shi, T. A hybrid human-in-the-loop deep reinforcement learning method for UAV motion planning for long trajectories with unpredictable obstacles. Drones 2023, 7, 311. [Google Scholar] [CrossRef]
  45. Ahmed, G.; Sheltami, T.; Deriche, M.; Yasar, A. An energy efficient IoD static and dynamic collision avoidance approach based on gradient optimization. Hoc Netw. 2021, 118, 102519. [Google Scholar] [CrossRef]
  46. Ahmed, G.; Sheltami, T.; Mahmoud, A.; Yasar, A. Energy-Efficient UAVs Coverage Path Planning Approach. CMES-Comput. Model. Eng. Sci. 2023, 136, 3239–3263. [Google Scholar] [CrossRef]
  47. Ingersoll, B.T.; Ingersoll, J.K.; DeFranco, P.; Ning, A. UAV path-planning using Bezier curves and a receding horizon approach. In Proceedings of the Aiaa Modeling and Simulation Technologies Conference, Washington, DC, USA, 13–17 June 2016; p. 3675. [Google Scholar]
Figure 1. Path planning diagram of RHC.
Figure 1. Path planning diagram of RHC.
Drones 08 00682 g001
Figure 2. Block diagram of the proposed energy-efficient path planning approach.
Figure 2. Block diagram of the proposed energy-efficient path planning approach.
Drones 08 00682 g002
Figure 3. Path smoothing strategy.
Figure 3. Path smoothing strategy.
Drones 08 00682 g003
Figure 4. Two-dimensional view of UAV paths for different scenarios.
Figure 4. Two-dimensional view of UAV paths for different scenarios.
Drones 08 00682 g004
Figure 5. Three-dimensional view of UAV path planning, showing the effectiveness of the proposed SEA.
Figure 5. Three-dimensional view of UAV path planning, showing the effectiveness of the proposed SEA.
Drones 08 00682 g005
Figure 6. Two- and three-dimensional views of UAV path planning and normalized energy consumption for scenario 1: (a) two-dimensional view, (b) three-dimensional view, and (c) normalized energy consumption.
Figure 6. Two- and three-dimensional views of UAV path planning and normalized energy consumption for scenario 1: (a) two-dimensional view, (b) three-dimensional view, and (c) normalized energy consumption.
Drones 08 00682 g006
Figure 7. Two- and three-dimensional views of UAV path planning and normalized energy consumption for scenario 2: (a) two-dimensional view, (b) three-dimensional view, and (c) normalized energy consumption.
Figure 7. Two- and three-dimensional views of UAV path planning and normalized energy consumption for scenario 2: (a) two-dimensional view, (b) three-dimensional view, and (c) normalized energy consumption.
Drones 08 00682 g007
Figure 8. Minimum distance from UAVs to dynamic obstacles during different missions.
Figure 8. Minimum distance from UAVs to dynamic obstacles during different missions.
Drones 08 00682 g008
Figure 9. Average normalized energy consumption over 30 runs for two different obstacle configurations: fifteen static obstacles, and fifteen static obstacles plus fifteen dynamic obstacles.
Figure 9. Average normalized energy consumption over 30 runs for two different obstacle configurations: fifteen static obstacles, and fifteen static obstacles plus fifteen dynamic obstacles.
Drones 08 00682 g009
Table 1. Symbol definitions.
Table 1. Symbol definitions.
SymbolDescription
N p Number of possible locations in the segment defined by the UAV’s FoV
x s min , x s max Represent the x-boundary of the segment within the UAV’s FoV
y s min , y s max Represent the y-boundary of the segment within the UAV’s FoV
S D min Minimum safety distance from obstacles
N d Number of UAVs
N obs Number of obstacles
E u Available energy for UAV u
E i j Energy used to travel from position i to position j
M D T O Minimum distance to dynamic obstacles
D T Duration time to generate a partial path within the UAV’s FoV
N o C s Number of collisions during the mission
Table 2. Comparison of the time required to generate partial paths, number of collisions, and UAV formation results between our proposed approach and the approaches in [45,47].
Table 2. Comparison of the time required to generate partial paths, number of collisions, and UAV formation results between our proposed approach and the approaches in [45,47].
ApproachStatic EnvironmentDense Environment
NoC DT (ms) UAVs Formation NoC DT (ms) UAVs Formation
Proposed00255.8YES00301.88YES
[45]00288.16YES00447.4YES
[47]00261.9NO10362.68NO
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

Ahmed, G.; Sheltami, T. Novel Energy-Aware 3D UAV Path Planning and Collision Avoidance Using Receding Horizon and Optimization-Based Control. Drones 2024, 8, 682. https://doi.org/10.3390/drones8110682

AMA Style

Ahmed G, Sheltami T. Novel Energy-Aware 3D UAV Path Planning and Collision Avoidance Using Receding Horizon and Optimization-Based Control. Drones. 2024; 8(11):682. https://doi.org/10.3390/drones8110682

Chicago/Turabian Style

Ahmed, Gamil, and Tarek Sheltami. 2024. "Novel Energy-Aware 3D UAV Path Planning and Collision Avoidance Using Receding Horizon and Optimization-Based Control" Drones 8, no. 11: 682. https://doi.org/10.3390/drones8110682

APA Style

Ahmed, G., & Sheltami, T. (2024). Novel Energy-Aware 3D UAV Path Planning and Collision Avoidance Using Receding Horizon and Optimization-Based Control. Drones, 8(11), 682. https://doi.org/10.3390/drones8110682

Article Metrics

Back to TopTop