Next Article in Journal
Toward the Intelligent, Safe Exploration of a Biomimetic Underwater Robot: Modeling, Planning, and Control
Next Article in Special Issue
Distributed State Estimation for Flapping-Wing Micro Air Vehicles with Information Fusion Correction
Previous Article in Journal
A Hierarchical Prediction Method for Pedestrian Head Injury in Intelligent Vehicle with Combined Active and Passive Safety System
Previous Article in Special Issue
An Angular Acceleration Based Looming Detector for Moving UAVs
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Multigene and Improved Anti-Collision RRT* Algorithms for Unmanned Aerial Vehicle Task Allocation and Route Planning in an Urban Air Mobility Scenario

School of Electronic and Information Engineering, Beihang University, 37 XueYuan Road, Haidian District, Beijing 100191, China
*
Author to whom correspondence should be addressed.
Biomimetics 2024, 9(3), 125; https://doi.org/10.3390/biomimetics9030125
Submission received: 9 January 2024 / Revised: 14 February 2024 / Accepted: 19 February 2024 / Published: 21 February 2024
(This article belongs to the Special Issue Bio-Inspired Design and Control of Unmanned Aerial Vehicles (UAVs))

Abstract

:
Compared to terrestrial transportation systems, the expansion of urban traffic into airspace can not only mitigate traffic congestion, but also foster establish eco-friendly transportation networks. Additionally, unmanned aerial vehicle (UAV) task allocation and trajectory planning are essential research topics for an Urban Air Mobility (UAM) scenario. However, heterogeneous tasks, temporary flight restriction zones, physical buildings, and environment prerequisites put forward challenges for the research. In this paper, multigene and improved anti-collision RRT* (IAC-RRT*) algorithms are proposed to address the challenge of task allocation and path planning problems in UAM scenarios by tailoring the chance of crossover and mutation. It is proved that multigene and IAC-RRT* algorithms can effectively minimize energy consumption and tasks’ completion duration of UAVs. Simulation results demonstrate that the strategy of this work surpasses traditional optimization algorithms, i.e., RRT algorithm and gene algorithm, in terms of numerical stability and convergence speed.

1. Introduction

Unmanned aerial vehicles (UAVs), also known as drones, have attracted lots of attention from the industry and academia, owing to their versatility, flexibility, and coordinated swarming capabilities [1]. UAVs are primarily categorized into two fixed-wing and rotary-wing UAVs [2]. Unlike fixed-wing UAVs, the latter can hover at fixed sites and vertically takeoff or land without runways or launchers. Therefore, the deployment and collaboration of rotary-wing UAVs offers a practical solution to alleviate congestion in ground transportation and delivery backlogs in urban environments [3]. In this context, Urban Air Mobility (UAM) scenario, demonstrated by Uber in [4], uses a type of rechargeable rotary-wing UAV called electric Verticals Take-Off and Landing (eVTOL) to balance the delivery of goods and passenger transport.
The industrial landscape of applying UAVs in the logistics and transportation sectors is also in progress. For instance, Walmart employed automated UAVs to deliver goods to customers in rural areas. DHL, one of Europe’s biggest mailing companies, tested a new automation UAV-based platform for providing services. Regarding aeronautical manufacturing enterprises, e.g., NASA, Uber, and Hyundai Motor have focused their attention on the architectural and technical challenges of integrating automated UAVs into UAM transportation systems [2]. A key technique challenge in UAM is the strategic deployment of UAVs for provision services. The procedures of UAV deployment can be mainly classified into route planning and task allocation [5].
In terms of task-allocation problems, collaboration among UAVs is crucial to reduce conflicts and enhance efficiency. Hao-Xiang et al. put forward a modified organism search algorithm to solve task assignment problems with multiple UAVs [6]. The work [7] proposed an adaptive genetic algorithm to assign multiple heterogeneous UAVs performing military tasks within a limited time. Randal et al. studied cooperative target assignments under enemy threats.
Mathematical models of previous works mainly include Mixed Integer Linear Programming (MILP), Multiple Traveling Salesman Programming (MTSP), Multiple Vehicle Routing Programming (MVRP) and Cooperative Multiple Task Assignment Programming (CMTAP) [8,9,10,11]. The MILP model is widely used in task assignment problems owing to its extensibility. However, the simple processes of MILP models are more suitable for small-scale problems. Additionally, the MTSP model does not consider the heterogeneity of tasks. Additionally, the MVRP model suits well time-constrained tasks, but does not refer to the flight dynamic performance of UAVs [12,13,14]. On the contrary, the CMTAP model is suitable for heterogeneous task assignments with multiple UAVs. Therefore, the CMTAP model of this work is built and studied for task assignment problems with multiple UAVs in a UAM scenario.
As for addressing the CMTAP model of task assignment problems, genetic algorithms are commonly used for their scalability, simplicity, and extensibility. However, the failure of a single UAV can cause deadlock in the genetic algorithm. Moreover, different task constraints for heterogeneous tasks can lead to the local existence of the solution. In this regard, the work improves and proposes the efficient and innovative multigene algorithm by designing customized selection and multipoint crossover for heterogeneous tasks. Specific details will be expanded in the following sections [15,16].
The main goal of the trajectory design of multiple UAVs is to improve energy efficiency and enhance the timeliness of the system. Huimin et al. optimized UAVs’ trajectory to minimize time-related performance [17]. They presented a novel framework to solve the realistic non-convex problem. The work [18] adopted the genetic algorithm and the particle swarm algorithm in optimizing the trajectories of UAVs. The simulation proves that the genetic algorithm performs better than the particle swarm algorithm [19].
According to route planning problems of multiple UAVs in previous works, an efficient path planning algorithm can improve the execution efficiency and robustness of the system. Therefore, reducing the obstacle avoidance system’s discovery time and path length is worthy of research. Hassan et al. proposed a novel hybrid form of the Dubins-simulated annealing (HDSA) optimization framework for emergency landing, which can plan the most suitable and admissible trajectory to the landing site in emergency flight conditions [20]. Dolgov et al. proposed the A* algorithm, a graph traversal algorithm, to find the optimal path in an obstacle avoidance system [21]. However, the computation load of each step increases fast with the growth of the complexity of the environment [22,23]. The rapidly exploring random tree (RRT) algorithm has the integrity of spatial search ability to fast and randomly sample in the map without pre-modeling [24]. However, the convergence speed of the RRT algorithm is low, and the smoothness of the generated path is poor due to the randomness of the search direction [25,26,27,28,29].
Previous works have improved and optimized the RRT algorithm to address its shortcomings in the efficiency of path planning. The RRT* algorithm proposed by Karaman et al. adopts two strategies, reselecting parent nodes and rewiring, to plan a near-optimal path, which may increase time cost [30]. Luo et al. proposed an informed RRT* algorithm based on Karaman’s work. The informed RRT* algorithm limits the sampling area to an ellipse to improve the speed of obtaining the asymptotic optimal path [31]. Kuffner et al. proposed the RRT Connect algorithm, which adds one more random tree with the target point as the root node [32,33]. Two random trees of the RRT Connect algorithm grow towards each other simultaneously [34].
Although scholars have performed a lot of previous work on improving the RRT* algorithm to solve route planning problems, there still exists poor adaptability to the UAM scenario, slow convergence speed in finding the target, and poor planning path quality [35,36]. To address the above shortcomings, this work proposes an improved anti-collision RRT* (IAC-RRT*) algorithm. First, the IAC-RRT* algorithm offers the map complexity evaluation strategy to calculate the corresponding map’s suitable step size and bias probability. The time switching factor is also used to adapt the UAM scenario. Moreover, the normal line between the source and the goal is introduced to ensure the random tree explores positively to the target point. Simulation results have demonstrated the IAC-RRT* algorithm can improve the effectiveness and quality of sampling points, leading to better planning path quality.
Overall, the main contributions of this paper are listed as follows:
  • To the best of our knowledge, we first study to minimize energy consumption in the context of heterogeneous task assignments for multiple UAVs in urban environments. This research not only tackles the task assignment problem but also considers charging requirements and diverse task types. Consequently, the task assignment problem constitutes a CMTAP model. To address this model, we propose a multigene algorithm by designing customized selection and multipoint crossover mechanisms to handle the heterogeneity of tasks.
  • This paper also proposes the IAC-RRT* algorithm to compute the route planning problems in the UAM scenario. A time-switching factor is proposed to adapt the airspace management regulations of the UAM scenario. Moreover, the normal line between the source and the goal is introduced to ensure the random tree explores positively to the target point. Compared to the RRT* algorithm, the novel route planning method works well in urban environments.
  • Simulation results indicate that the strategy of this work exhibits superior adaptability and efficiency than the traditional optimization algorithm, i.e., RRT* algorithm, and gene algorithm. This advancement marks a significant stride in optimizing UAV schedules within UAM scenarios.

2. Models and Methods

2.1. System Model

We consider a UAV-enabled task scheduling system in UAM scenarios with UAVs, u U = { 1 , 2 , , N u } , and tasks, s S = { 1 , 2 , , N s } , as shown in Figure 1, where U and S are sets of UAVs and tasks, respectively. Additionally, the number of UAVs and tasks are denoted as N u and N s . Each UAV has communication and navigation devices, allowing persistent real-time communication with the ground control center. Heterogeneous tasks, randomly generated and distributed in urban space, are divided into different classes according to the traffic demand, which will be discussed in the following subsection. N u UAVs cooperatively visit N s known task sites in clusters, and the IAC-RRT* algorithm is employed to optimize the trajectory of each UAV, thereby guaranteeing the minimization of flight paths while adhering to safety protocols.
The location of the s-th task point is denoted by coordinates ( x s , y s , h s ) , where s S . Similarly, the position of the u-th UAV at a given time t is denoted by ( x u t , y u t , h u t ) . Although tasks are heterogeneous, the mechanical energy consumption of UAVs during the task execution is not incorporated in the total energy consumption in subsequent problem formulations.

2.1.1. Heterogeneous Task Execution Model

As for UAV tasks, the k-th task generated at time t is denoted as
s l t ( k ) = { F l ( k ) , D l ( k ) , ( x ( k ) , y ( k ) , h ( k ) ) } ,
where l 1 , 2 , 3 represents different task types, and  F l ( k ) denotes the total number of UAVs are required to finish the k-th task, which is defined as
F l ( k ) = 1 , single UAV mission , { n | n 2 , n N + } , multi UAVs mission ,
where D l ( k ) represents the duration of completing the task, which remains consistent for tasks of identical type. And  ( x ( k ) , y ( k ) , h ( k ) ) is the position of a specific task s l t ( k ) . In this paper, UAV missions are divided into three typical types, each tailored to meet the demands of the UAM scenario.
Air taxi task I: This task type is denoted by l = 1 . As shown in Figure 1, there are N a air taxi tasks in the UAM scenario, e.g., UAV i transports loads in demand from one designated site T A 2 to another T G 2 . The subscripts of T A and T G are numbered sequentially. Additionally, this is the single-UAV mission type and F l = 1 . The air taxi task is marked in blue from the timeline of the left part of Figure 1.
Hover and monitor task II: This task type is denoted by l = 2 . Multi-cooperated UAVs can be used as effective tools to hover at fixed locations and monitor some specific applications in UAM scenarios, i.e., precision agriculture, smart traffic monitor. To mathematically measure the problem of this type, we define a general task type with multi-cooperated UAVs performing tasks, and thus F l 2 . Moreover, assigned UAVs cooperate and hover at task sites for a given length of time under unified control. Additionally, there are N h hover and monitor tasks in the task set T .
Recharge task III: This task type is denoted by l = 3 , and  F l = 1 . Considering the battery capacity and the flight endurance of rotary-wing UAVs, charging stations are established in specific urban areas. Drones with low battery status can autonomously navigate to these stations for recharging. It is worth noting that each UAV’s battery capacity is defined as C, with three operational modes to ensure drone safety.
The battery level restricts task types that UAVs can accept. Firstly, the i-th UAV can not take air taxi task I if its current battery level C i ( t ) is less than 0.4 C . Then, if the i-th UAV is in the middle of some task and its current battery level is less than 0.3 C , it will flee back to the charge station once it finishes the task. Lastly, the i-th UAV is forced to fly back to the charge station when its battery level is less than 0.2 C , regardless of whether it is in the middle of the task. However, if the UAV leaves its current task, this task will be judged as a failure. Therefore, task types taken by the i-th UAV with different battery levels are given as
s 1 ( k ) , s 2 ( k ) , 0.4 C C i ( t ) C , s 2 ( k ) , 0.3 C C i ( t ) 0.4 C , s 2 ( k ) , s 3 ( k ) , 0.2 C C i ( t ) 0.3 C , s 3 ( k ) C i ( t ) 0.2 C .
In (3), s 1 ( k ) , s 2 ( k ) , s 3 ( k ) are used to represent air taxi task I, hover and monitor task II and recharge task III.

2.1.2. Energy Consumption Model

This subsection illustrates the energy model for a UAV during a cruise. Within the specific scenario as shown in Figure 2, the analysis of energy consumption during UAV movements is divided into four distinct phases, contingent upon the UAV’s state of motion. We assume G V as the standard gravity of the UAV. The rotary-UAV’s thrust can be calculated as F V = ( G V ( a 1 ( V h o r cos ( α ) ) 2 + a 2 F V ) 2 + ( a 3 V h o r 2 ) 2 . V h o r and V h o r are horizontal speed and vertical speed, respectively. α is the directional angle between the next target location and its orientation to the next waypoint. Although the flight dynamics of UAVs are intricate, any flight maneuver executed by a UAV can be decomposed into horizontal and vertical components. When calculating the energy consumption of complex flight movements, it can be effectively represented by summing the energy expenditures of both horizontal and vertical flight motions.
(1) UAV horizontally flying regime: In this state, UAVs horizontally fly during its transit. Suppose the horizontal flight velocity remains constant at V t , and the consumption power P I ( V t ) for horizontal flight is expressed as [37]
P I ( V t ) = k 1 k 2 + a 4 F V 3 / 2 + a 3 V t 3 .
(2) UAV hovering regime: Similarly, the power consumption during UAV hovering P H is represented as [37]
P H = = k 1 k 2 + a 4 G v 3 / 2 ,
where charging stations are located at ground level, necessitating UAVs to ascend or descend for recharging or task execution.
(3) UAV vertically flying upward regime: By neglecting the acceleration and deceleration process, UAVs ascend or descend at a constant velocity V u . The ascending related power denoted by P A is calculated by [37]
P A ( V u ) = k 1 G v V u 2 + V u 2 2 + G v k 2 2 + a 4 G v 3 / 2 .
(4) UAV vertically flying downward regime: the descending related power denoted by P D with V u is formulated as [37]
P D ( V u ) = k 1 G V V u 2 + V u 2 2 + G v k 2 2 + a 4 G v 3 / 2 .
In (4)–(7), k 1 , k 2 , a 1 , a 2 , a 3 , and  a 4 are technical parameters of vehicles, independent of the UAV’s motion or environment factors. Therefore, the energy consumption analysis for the k-th flight of UAV i can be segmented into four components corresponding to the movement states. The total energy consumption of UAV i’s k-th flight, W i k , can be given as
W i k = 0 τ i k P i k ( t ) d t = k = 1 N j + 1 P I ( V t ) d j , i k V t H o r i z o n t a l f l i g h t + n = 1 N j P H τ i , j k , H H o v e r + P A ( V a ) H k V a A s c e n t + P D ( V d ) H k V d D e s c e n t ,
where N j is the total tasks that UAV i should finish in its k-th flight. d j , i k is the distance between the site of task j and its previous site. τ i k is the k-th total flight duration of UAV i. τ i , j k , H is the hovering duration at site of task j. H k is the sum of elevated height in its k-th flight. Additionally, V a and V d are the velocities of upward and downward flight, respectively.

2.2. Problem Formulation

2.2.1. Task Allocation Problems

The goal of task allocation is to achieve the optimal assignment of N s tasks to N u UAVs to maximize the overall reward. Additionally, the task list comprises N a air taxi tasks, N h hover and monitor tasks, which satisfies
N s = N a + N h ,
and each task is exclusively assigned to a specific vehicle during a single flight. Furthermore, each UAV can be assigned a maximum of L t tasks, subject to the condition
N s < N u · L t .
The global reward function is the summation of local rewards for each vehicle, which is determined by a function of the tasks assigned to each UAV. Optimization goals of time and energy consumption are studied separately. The time-oriented problem focuses on minimizing the time required to complete all tasks in an urban scenario, which can be mathematically represented as
P 1 : min i = 1 N u t i s . t . t i = p N s j N s S j p i × t j p i + p N s S p a i × t p a i f l i g h t t i m e b e t w e e n t a s k p o i n t s + j = 1 N s D j i × t j d d u r a t i o n o f t a s k j + i N u R E a i × t c c h a r g i n g d u r a t i o n D j i = 1 , if U A V i h a n d l e s t a s k j , 0 , otherwise S a k i = 1 , if U A V i h a n d l e s t a s k s a , j , 0 , otherwise , R E a i = 1 , if U A V i c h a r g e s a t s i t e a , 0 , otherwise
where t j d is the operation time of task j, which is uniform for all UAVs. t c denotes the fixed charging duration, t p a i signifies the flight duration between site p and a, and the charging station a. Constraints indicate that the operation time of a single UAV depends on whether the task is undertaken and which charging station is chosen.
The minimal power consumption problem is independent of the minimal time problem, as the power consumption of each vehicle determines the power consumption of completing all tasks in the system. According to Equations (4)–(8), the power consumption optimization problem of k-th flight can be represented by
P 2 : min i = 1 N u W i k s . t . i U , i N u , k N * ,
where k belongs to the set of positive integers N * , and represents any flight of UAV i.

2.2.2. Route Planning Problems

The goal of route planning in this paper is to find the path with the shortest distance from the initial task site to the final task site within a limited time while avoiding obstacles in the UAM Operating Environment (UOE). The UOE, a flexible airspace area, can be redefined and modified over time. For example, if the traffic patterns at a nearby airport change, the available UOE may be adjusted to avoid potential traffic conflicts. Changes in the available UOE are likely to occur several times daily and can be promptly detected by the ground control center. Taking into account the dynamic nature of the UOE, the cost function for distance, C l e n g t h , can be represented by the node i [38],
P 3 : min i = 1 N u C l e n g t h s . t . D p o i n t s = { i d | i d Discovered Points } , i d Q n + γ s t Q s t , γ s t = 1 , if normal traffic of UAM scenario , 0 , otherwise ,
where γ s t represents the time transformation factor, which can be utilized to indicate the available UOE over time. The depreciation of (13) aims to identify the minimal C l e n g t h encompassing the points i d discovered by the proposed algorithm within the available UOE. Q n , Q s t , and  Q o b are the general area, “flexible” area and obstacle area, respectively, where the “flexible” area can be controlled to switch by γ s t .

2.3. Proposed Algorithms

2.3.1. Multigene Algorithm for Task Allocation Problem

The initial step of the multigene algorithm involves the design of an encoding scheme that establishes connections between task sets, UAV sets, execution sequences, and assignment rules. Therefore, the proposed algorithm encodes the solution for (11) and (12) into a matrix form, also referred to as a chromosome, as shown in Figure 3. Each “gene” corresponds to a column with the matrix, representing a specific task assignment. In the first row of Figure 3, there are 10 tasks, comprising seven air taxi tasks labeled as 1–7, and three hover and monitor tasks labeled as 8–13. Additionally, No.8 and No.9 are associated with the same multi-vehicle task, necessitating the participation of two distinct vehicles. Rows two through six represent task type, execution order, UAV order number, execution time, and energy consumption.
The second step involves chromosome initialization, randomly generating N c h r o m encoding schemes. These N c h r o m initial chromosomes constitute the first generation of task allocation schemes. Subsequently, the initial set of chromosomes undergoes the iteration of crossover, mutation, and reinsertion until either the maximum number of iterations is reached or the optimal task allocation scheme is found. The processes mentioned above are outlined as follows.
Phase 1, crossover process: By employing roulette wheel selection, the selected chromosome randomly modifies segments of the gene sequence within its vicinity. The crossover probability P c varies depending on the task type and is defined as follows:
P c = P c ( l = 1 ) , l = 1 , N a 2 N h P c ( l = 1 ) , l = 2 ,
where P c ( l = 1 ) is set as a constant according to the simulation needs, N a and N h represent the numbers of air taxi tasks and hover and monitor tasks, respectively. Given that the hover and monitor task requires two different UAVs, the crossover probability P c matching with the quantitative proportion of two task types can improve the search efficiency of the multigene algorithm. Furthermore, a partially matched crossover method ensures that each gene occurs only once, as shown in Figure 4.
Phase 2, mutation process: In Figure 5, chromosome variation encompasses single-point mutation and hybrid mutation. The single-point mutation alters the UAV order number, while hybrid-point mutation modifies execution order. If the probability of single-point mutation and hybrid-point mutation set as a constant, P m , the risk of losing excellent individuals increases. Therefore, the probabilities of single-point mutation and hybrid-points mutation are customized for each scheme based on its fitness value, F, in comparison to the average fitness value, F ¯ , which are defined as
F = 1 i = 1 N u t i , F ¯ = 1 i = 1 N c h r o m F .
To accelerate the retention of superior schemes and the elimination of inferior schemes, the mutation probability of the current scheme is calculated as
P m = ( P m 1 P m 2 ) · ln ( A · F + B ) + P m 1 , F F ¯ , P m 1 , F < F ¯ ,
where P m , P m 1 , and  P m 2 represent the current, minimum, and maximum values of mutation probability. A and B are functions designed to balance the relationship between mutation probability and fitness function, which are defined as
A = e 1 e ( F ¯ F m a x ) ,
B = F ¯ e F m a x e ( F ¯ F m a x ) ,
where F, F m a x , and  F ¯ are the fitness function’s current, maximum, and average values. e is Euler constant. Specifically, when calculating the fitness function value F for the current assignment, if  F F ¯ , mutation probability should be set as the first case of (16). Otherwise, the mutation probability of the current scheme should be set to the maximum value of the mutation probability.
Phase 3, reinsertion process: The reinsertion process selects the chromosome with the best performance and inserts it into the next iteration. It ensures the subsequent generation maintains or improves upon the quality of the solution to the problem.
Overall, the process of the multigene algorithm has been organized and shown in Algorithm 1.
Algorithm 1 Multigene algorithm for solving task allocation problem
Input: 
  
   
U = { 1 , 2 , , N u } , S = { 1 , 2 , , N s } , N a , N h ;
Output: 
  
   
task allocation scheme with the highest F;
1:
Initialize N c h r o m schemes in initial chromosome;
2:
Calculate F of each scheme of the initial chromosome;
3:
Set F m a x and calculate F ¯ of the initial chromosome;
4:
G e = number of iterations;
5:
Set P c , P m , P m 1 , P m 2 ;
6:
while  i G e do
7:
   Crossover process in Phase 1;
8:
   Mutation Process in Phase 2;
9:
   Reinsertion Process in Phase 3;
10:
  Select the scheme with the highest F in this generation;
11:
   i = i + 1 ;
12:
end while
13:
Output the scheme with the highest F in the last generation.

2.3.2. Improved Anti-Collision RRT* (IAC-RRT*) Algorithm for Route Planning Problem

In this subsection, we proposed the IAC-RRT* algorithm, a robust and efficient algorithm for route planning designed to address the challenge of identifying feasible pathways within the UAM operation environment. The principles and concrete steps are as follows.
The first step involves map initialization and updating of task sites. The urban airspace area Q is divided into available area, Q n , “flexible” area, Q s t , obstacle area, Q o b in Section 2.2.2. And the “flexible” area is controlled to switch by γ s t ; the relationship is given as
Q = Q n + Q s t + Q o b ,
then the start-point, q s t a r t and the end-point, q e n d are positioned within the domains Q n or Q s t . The task is deemed unsuccessful if these points fall outside the accessible regions, represented as
q s t a r t , q e n d Q n Q s t .
Subsequently, a direct line connecting q s t a r t and q e n d is established, designated as the normal line R 1 , which aids in assessing exploration node efficiency.
The second step entails the construction of the tree structure. The algorithm explores the surrounding area with the radius R e from the root node q s t a r t and creates the newly found node q n e w . The search and explore principle can be given that the smaller the included angle, θ n e ( i ) , between the normal direction and explore direction, the higher the chance of the node, p n e ( i ) to be chosen.
p n e ( i ) = 1 π / θ n e ( i ) .
The algorithm determines whether the newly generated node q n e w belongs to Q n Q s t . If  q n e w Q o b , the node will be discarded at once. Otherwise, the time transformation factor γ s t will be used to determine whether the “feasible” area Q s t would allow flight action.
Then, IAC-RRT* algorithm reselects neighbor node q n e a r of q n e w within the radius of R, which is defined as
q n e a r { d i s ( q n e a r , q n e w ) < R } ,
By comparing the distance from q n e a r to q s t a r t and q n e w , the IAC-RRT* algorithm decides whether to change the parent node of q n e w .
min D n e w = d i s ( q s t a r t , q n e a r ) + d i s ( q n e a r , q n e w ) , s . t . q n e a r { d i s ( q n e a r , q n e w ) < R } ,
the optimal reselected neighbor, denoted as q n e a r * , becomes the new parent node of q n e w . The rewiring process aims to reduce the path length across the global tree nodes, i.e., calculating the distance D n e a r between each neighbor node and q n e w , and selecting the minimal distance to q s t a r t . The mathematical representation of the rewiring process is as follows:
min D n e a r = d i s ( q s t a r t , q n e a r ) , s . t . q n e a r { d i s ( q n e a r , q n e w ) < R } , q n e w { p a r e n t n o d e s o f q n e a r } ,
These steps are reiterated until the distance between the newly generated node q n e w and q e n d is less than R. IAC-RRT* algorithm is described in Algorithm 2.
Algorithm 2 IAC-RRT* algorithm for solving route planning problem
Input: 
  
   
Q n , Q s t , Q o b , q s t a r t , q e n d ,n iteration times;
Output: 
  
   
Route from q s t a r t to q e n d ;
1:
Search from q s t a r t ;
2:
while Iterate n times do
3:
   while  d i s ( q n e w , q e n d ) > R  do
4:
     Generate q n e w within the radius R;
5:
     if  q n e w Q o b  do
6:
        discard q n e w ;
7:
     else  q n e w Q n γ s t Q s t  do
8:
        reselect parent node for q n e w ;
9:
         min D n e w = d i s ( q s t a r t , q n e a r ) + d i s ( q n e a r , q n e w ) ;
10:
       rewire with q n e a r as the parent node;
11:
        min D n e a r = d i s ( q s t a r t , q n e a r ) ;
12:
     end if
13:
   end while
14:
   Backtrack along q n e w from q e n d to q s t a r t , i.e., find the route;
15:
   Select the route with minimal distance from each iteration;
16:
end while
17:
Output the selected route from q s t a r t to q e n d .

3. Results

To evaluate the performance of the multigene algorithm and IAC-RRT* algorithm, we conduct simulations and compare the results with a few traditional task allocation and route planning algorithms. For all simulations without particular illustration, the parameters are fixed: we set the number of UAVs to 4, the number of tasks to 10, the number of air taxi tasks to 7, and the number of hover and monitor tasks to 3. The details of the simulations are presented as follows.

3.1. Simulation Results of Multigene Algorithm

In this subsection, we employ the gene and ant colony algorithms as comparative benchmarks. To assess the convergence probability, a series of experiments are conducted to search the most energy-efficient and quickest task allocation schemes.
Figure 6 limits the maximum iterations to 100 to ensure consistent experimental conditions, thereby evaluating the search performance of the multigene algorithm. Figure 6a–c demonstrate that our method significantly surpasses the gene and ant colony algorithms regarding search speed and optimal search outcomes, focusing on energy consumption, distance, and completion time. This superiority is attributed to the multigene algorithm’s targeted crossover and mutation, unlike the random approach of the other algorithms. Thus, we yield that heterogeneity-oriented crossover and mutation enhance the chance of discovering the optimal solution.
Figure 7a depicts the relationship between the average system search time and the average number of simulation times. We can yield that with the increase in an average number of simulation times, the trend of average search time reveals no direct correlation. Additionally, the ant colony algorithm exhibits marginally inferior performance at lower simulation times. Figure 7b examines the association between average search time and the number of schemes of each iteration. A consistent trend is observed from Figure 7b. Given its superior search capabilities and outcomes, the extra search time invested in the multigene algorithm is deemed cost-effective.
Figure 8a,b present the system’s total energy consumption by varying tasks and UAV numbers. As depicted in Figure 8a, the number of UAVs is set to 10. Additionally, we also set 11 tasks with 7 single-UAV tasks and 2 multi-UAV tasks, 12 tasks with 8 single-UAV tasks and 2 multi-UAV tasks, 13 tasks with 7 single-UAV tasks and 3 multi-UAV tasks, and 14 tasks with 8 single-UAV tasks and 3 multi-UAV tasks. We can conclude that total energy consumption increases with the number of tasks. Compared to the single-UAV tasks, the multi-UAV tasks will cause more significant growth in energy consumption. It can be explained by inherent complexity of heterogeneous tasks.
Figure 8b shows the system’s energy consumption variation by changing the number of UAVs. We can see that increasing the number of UAVs can not permanently reduce energy consumption. Notably, excessive UAVs can lead to inefficiencies and increased energy use. An inadequate number of UAVs can cause extreme round trips from charging stations to task sites.
Figure 9 investigates the impact of crossover and mutation probabilities on the iterations required to identify the optimal scheme. We set schemes with system time under 6000   s as the optimal schemes. Figure 9a reveals an inverse relationship between crossover probability and required iterations, as a higher crossover probability enhances the chance of identifying more suitable task assignments. On the contrary, the iterations to find the optimal scheme vary with the likelihood of mutation Figure 9b. An increase in mutation probability risks losing excellent schemes, and an excessively low mutation probability may fail to generate sufficient options for optimal selection.
Figure 10 displays the UAV task schedule for an optimal task assignment. There are seven single-UAV tasks s 1 ( k ) and three multi-UAV tasks, color-coded for differentiation, s 2 ( 1 ) , s 2 ( 2 ) , s 2 ( 3 ) . It can be observed that the optimal scheme balances fairness and effectiveness. Each UAV is assigned a similar number of tasks. However, the UAV to finish particularly challenging or isolated tasks, i.e., UAV4, may undertake fewer additional tasks.

3.2. Simulation Results of IAC-RRT* Algorithm

This subsection explores the performance of the IAC-RRT* algorithm. We simulated 4 UAV-assisted route planning scenarios in an urban environment. The environmental map is modeled as a 2000 × 2000 × 100 m 3 cube, which is divided into available areas, Q n , “flexible” areas, Q s t , obstacle areas, Q o b . Flexible areas Q s t , modeled as green box regions, are controlled by a time-switching factor γ s t . Obstacles Q o b are modeled as randomly located hemispherical regions. All UAVs start and end at ( 0 , 0 , 5 ) . Task sites which have seven single-UAV tasks and three multi-UAV tasks are randomly distributed in Q n . The radius of exploration sets as 5 m . The RRT algorithm serves as a benchmark for comparison.
Figure 11 represents the searching time performance of three algorithms over different building densities. To test the obstacle avoidance performance of the IAC-RRT* algorithm, RRT and RRT* algorithms work as comparison groups [25]. Accordingly, the gap is not distinct at low building density because random search methods may not easily bump into obstacles. However, searching methods along the normal direction have better effects at high building densities. Additionally, simulation results prove that the IAC-RRT* algorithm performs better than the RRT algorithm and RRT* algorithm in a complex obstacle environment. Figure 12 portrays the IAC-RRT* algorithm’s route search process. Figure 12a depicts the initial single route of the IAC-RRT* algorithm by finishing three tasks. Consequently, Figure 12b defines the search process of the IAC-RRT* algorithm. It can be obtained that exploration detection of the search process prioritizes the normal line R 1 to increase the target discovery chance. Figure 12c depicts the final planned route for all vehicles of the IAC-RRT* algorithm. We can affirm the IAC-RRT* algorithm’s proficiency in task completion.
Figure 13 compares the system performance of the IAC-RRT* algorithm and RRT algorithm. Figure 13a shows the IAC-RRT* algorithm’s faster convergence time by 13 % compared to the RRT algorithm. Then, Figure 13b depicts the search distance performance of the IAC-RRT* algorithm. The variation in the number of average simulations between 5 and 15 owes to too few experiments. It can also be obtained that converge speed of the IAC-RRT* algorithm is quicker 12 % than the RRT algorithm. Figure 13c demonstrates times passing through Q s t of the IAC-RRT* algorithm and RRT algorithm. The time-switching factor γ s t reduces 85 % per cent passengers through Q s t . Remaining points occurs in Q s t of IAC-RRT* algorithm when γ s t = 1 .

4. Conclusions

In this paper, we propose the multigene algorithm and IAC-RRT* algorithm to solve UAV task allocation and route planning problems in the UAM scenario. Also, we studied the UAV power model and task model, and derived expressions of task allocation problems. Simulation results indicate that our algorithms have better numerical stability, which results in better solutions to the problem. The convergence speed of the proposed multigene algorithm is 20 percent faster than the traditional gene algorithm. Additionally, the IAC-RRT* algorithm can handle airspace control issues with robust performance. It can converge quicker 12 % than the RRT algorithm.

Author Contributions

Conceptualization and methodology, Q.Z. and H.F.; software and validation, H.F.; formal analysis and investigation, Q.Z. and H.F.; writing, H.F.; visualization, Y.L. 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 raw data supporting the conclusions of this article will be made available by the authors on request.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Hamid, M.; Ismail, G.; Kemal, A.; Selcuk, U.; Abdullah, K.; Adem, T. UAV-enabled intelligent transportation systems for the smart city: Applications and challenges. IEEE Commun. Mag. 2017, 5, 22–28. [Google Scholar]
  2. Cheng, L.; Wen, Q.; Yan, L.; Long, H.; Peng, W. Overview of traffic management of urban air mobility (UAM) with eVTOL aircraft. J. Traffic Transp. Eng. 2020, 5, 35–54. [Google Scholar]
  3. Andrey, G.; Young, I. Intelligent UAV in smart cities using IoT. In Proceedings of the 2016 16th International Conference on Control, Automation and Systems (ICCAS), Gyeongju, Republic of Korea, 16–19 October 2016; pp. 207–210. [Google Scholar]
  4. Jeff, H.; Nikhil, G. Fast-Forwarding to a Future of on-Demand Urban Air Transportation; Uber Elevator: San Francisco, CA, USA, 2016; pp. 23–26. [Google Scholar]
  5. Wan, Z.; Qing, M.; Paul, C. A heuristic distributed task allocation method for multivehicle multitask problems and its application to search and rescue scenario. IEEE Trans. Cybern. 2015, 4, 902–915. [Google Scholar]
  6. Hao, C.; Ying, N.; Yi, Y. Multi-UAV reconnaissance task assignment for heterogeneous targets based on modified symbiotic organisms search algorithm. Sensors 2019, 19, 734. [Google Scholar]
  7. Fang, Y.; Jie, C.; Yuan, T.; Tao, J. Cooperative task assignment of a heterogeneous multi-UAV system using an adaptive genetic algorithm. Electronics 2020, 9, 687. [Google Scholar]
  8. Oh, H.; Kim, S.; Tsourdos, A. Cooperative road-network search planning of multiple UAVs using Dubins paths. In Proceedings of the AIAA, Long Beach, CA, USA, 27–29 September 2011; p. 6386. [Google Scholar]
  9. Wang, C.; Mu, D.; Zhao, F. A parallel simulated annealing method for the vehicle routing problem with simultaneous pickup—Delivery and time window. Comput. Ind. Eng. 2015, 5, 111–122. [Google Scholar] [CrossRef]
  10. Arsie, A.; Savla, K.; Frazzoli, E. Efficient routing algorithms for multiple vehicles with no explicit communications. IEEE Trans. Autom. Control 2009, 10, 2302–2317. [Google Scholar] [CrossRef]
  11. Shima, T.; Rasmussen, S.J.; Sparks, A.G. Multiple task assignments for cooperating uninhabited aerial vehicles using genetic algorithms. Comput. Oper. Res. 2006, 11, 3252–3269. [Google Scholar] [CrossRef]
  12. Edison, E.; Shima, T. Integrated task assignment and path optimization for cooperating uninhabited aerial vehicles using genetic algorithms. Comput. Oper. Res. 2011, 1, 340–356. [Google Scholar] [CrossRef]
  13. Jia, Z.; Yu, J.; Ai, X. Cooperative multiple task assign- ment problem with stochastic velocities and time windows for heterogeneous unmanned aerial vehicles using a genetic algorithm. Aerosp. Sci. Technol. 2018, 6, 112–125. [Google Scholar] [CrossRef]
  14. Deng, Q.; Yu, J.; Wang, N. Cooperative task assignment of multiple heterogeneous unmanned aerial vehicles using a modified genetic algorithm with multi-type genes. Chin. J. Aeronaut. 2013, 5, 1238–1250. [Google Scholar] [CrossRef]
  15. Deng, Q.; Yu, J.; Mei, Y. Deadlock-free consecutive task assignment of multiple heterogeneous unmanned aerial vehicles. J. Aircr. 2014, 2, 596–605. [Google Scholar] [CrossRef]
  16. Upadhyay, S. Ratnoo, A. Smooth path planning for unmanned aerial vehicles with airspace restrictions. J. Guid. Control Dyn. 2017, 7, 1596–1612. [Google Scholar] [CrossRef]
  17. Hui, H.; Ke, X.; Gang, Q.; Qiang, N.; Ping, F.; Khaled, L. AoI-minimal trajectory planning and data collection in UAV-assisted wireless powered IoT networks. IEEE Internet Things 2021, 1, 1211–1223. [Google Scholar] [CrossRef]
  18. Vincent, R.; Mohammed, T.; Gilles, L. Comparison of parallel genetic algorithm and particle swarm optimization for real-time UAV path planning. IEEE Trans. Ind. Inform. 2013, 2, 132–141. [Google Scholar]
  19. Han, C.; Luc, B.; Jonathan, H. Path planning for autonomous vehicles in unknown semistructured environments. IEEE Trans. Robot. 2009, 8, 912–926. [Google Scholar]
  20. Haghighi, H.; Delahaye, D.; Asadi, D. Performance-based emergency landing trajectory planning applying meta-heuristic and Dubins paths. Appl. Soft Comput. 2022, 117, 108453. [Google Scholar] [CrossRef]
  21. Dolgov, D.; Thrun, S.; Montemerlo, M. Consensus-based decentralized auctions for robust task allocation. Int. J. Robot. Res. 2010, 5, 485–501. [Google Scholar] [CrossRef]
  22. Yang, M.L.; Li, N. Study on mobile robot path planning based on improved A* algorithm. Mech. Sci. Technol. Aerosp. Eng. 2022, 5, 795–800. [Google Scholar]
  23. Wang, D. Indoor mobile-robot path planning based on an improved A* algorithm. J. Tsinghua Univ. 2012, 8, 1085–1089. [Google Scholar]
  24. laValle, S.; Kuffner, J. Randomized kinodynamic planning. Int. J. Robot. Res. 2001, 5, 378–400. [Google Scholar] [CrossRef]
  25. Chen, Z.; Li, M.; Shao, X. Obstacle avoidance path planning of bridge crane based on improved RRT algorithm. J. Syst. Simul. 2021, 8, 1832–1838. [Google Scholar]
  26. Hsu, D.; Latombe, J.; Kurniawati, H. On the probabilistic foundations of probabilistic roadmap planning. Int. J. Robot. Res. 2006, 7, 83–97. [Google Scholar] [CrossRef]
  27. Liu, Y.; Zhao, H.; Liu, X. An improved RRT based obstacle avoidance path planning algorithm for industrial robot. Inf. Control 2021, 2, 235–246. [Google Scholar]
  28. Ruan, X.; Zhou, J.; Zhang, J. Robot goal guide RRT path planning based on sub-target search. Control Decis. 2020, 10, 2543–2548. [Google Scholar]
  29. Yu, M.; Luo, J.; Wang, M. Coordinated path planning by integrating improved RRT* and quartic spline. Chin. J. Theor. Appl. Mech. 2020, 4, 1024–1034. [Google Scholar]
  30. Karaman, S.; Frazzoli, E. Sampling-based algorithms for optimal motion planning. Int. J. Robot. Res. 2011, 7, 846–894. [Google Scholar] [CrossRef]
  31. Luo, S.; Liu, S.; Zhang, B. Path planning algorithm based on Gb informed RRT* with heuristic bias. In Proceedings of the 2017 36th Chinese Control Conference (CCC), Dalian, China, 26–28 July 2017; pp. 137–141. [Google Scholar]
  32. Zhang, Y.; Zuo, Y.; Wu, G. Research on path planning based on improved Informed-RRT* algorithm. Modul. Mach. Tool Autom. Manuf. Tech. 2020, 7, 21–25. [Google Scholar]
  33. Kuffner, J.; LaValle, S. RRT-Connect: An efficient approach to single-query path planning. In Proceedings of the IEEE International Conference on Robotics and Automation, San Francisco, CA, USA, 24–28 April 2000; pp. 71–75. [Google Scholar]
  34. Han, K.; Cheng, W. Path planning of robot arm based on improved RRT algorithm. Comput. Appl. Softw. 2022, 3, 260–265. [Google Scholar]
  35. Zhang, D.; Zhen, Z.; Chen, Y. Collaborative path planning based on improved RRT-Connect algorithm. Electron. Opt. Control 2021, 9, 25–29. [Google Scholar]
  36. Wang, K.; Huang, B.; Zeng, G. Faster path planning based on improved RRT-Connect algorithm. J. Wuhan Univ. 2019, 3, 283–289. [Google Scholar]
  37. Liu, Z.; Sengupta, R.; Kurzhanskiy, A. A power consumption model for multi-rotor small unmanned aircraft systems. In Proceedings of the International Conference on Unmanned Aircraft Systems (ICUAS), Miami, FL, USA, 4–7 June 2017; pp. 310–315. [Google Scholar]
  38. Haghighi, H.; Asadi, D.; Delahaye, D. Multi-Objective Cooperated Path Planning of Multiple Unmanned Aerial Vehicles Based on Revisit Time. J. Aerosp. Inf. Syst. 2021, 18, 919–932. [Google Scholar] [CrossRef]
Figure 1. System model of UAV-enabled task scheduling system in UAM scenario.
Figure 1. System model of UAV-enabled task scheduling system in UAM scenario.
Biomimetics 09 00125 g001
Figure 2. Cyclical movement of UAV.
Figure 2. Cyclical movement of UAV.
Biomimetics 09 00125 g002
Figure 3. Figure of multigene chromosome coding method.
Figure 3. Figure of multigene chromosome coding method.
Biomimetics 09 00125 g003
Figure 4. Figure of chromosome crossover.
Figure 4. Figure of chromosome crossover.
Biomimetics 09 00125 g004
Figure 5. Figure of chromosome variation.
Figure 5. Figure of chromosome variation.
Biomimetics 09 00125 g005
Figure 6. System performance of multigene compared with iterations. (a) Total energy consumption with iterations. (b) Average distance with iterations. (c) Average completion time with iterations.
Figure 6. System performance of multigene compared with iterations. (a) Total energy consumption with iterations. (b) Average distance with iterations. (c) Average completion time with iterations.
Biomimetics 09 00125 g006
Figure 7. System performance comparison of three algorithms. (a) Average search time by varying average simulation times. (b) Average search time by varying number of schemes for each iteration.
Figure 7. System performance comparison of three algorithms. (a) Average search time by varying average simulation times. (b) Average search time by varying number of schemes for each iteration.
Biomimetics 09 00125 g007
Figure 8. Energy consumption by varying number of tasks and UAVs. (a) Total energy consumption by varying number of tasks. (b) Total energy consumption by varying number of UAVs.
Figure 8. Energy consumption by varying number of tasks and UAVs. (a) Total energy consumption by varying number of tasks. (b) Total energy consumption by varying number of UAVs.
Biomimetics 09 00125 g008
Figure 9. The number of iterations to find the optimal scheme by varying probabilities of crossover and mutation. (a) The number of iterations to find the optimal scheme by varying probability of crossover. (b) The number of iterations to find the optimal scheme by varying probability of mutation.
Figure 9. The number of iterations to find the optimal scheme by varying probabilities of crossover and mutation. (a) The number of iterations to find the optimal scheme by varying probability of crossover. (b) The number of iterations to find the optimal scheme by varying probability of mutation.
Biomimetics 09 00125 g009
Figure 10. Task time schedule of four UAVs.
Figure 10. Task time schedule of four UAVs.
Biomimetics 09 00125 g010
Figure 11. Searching time performance over different number of buildings.
Figure 11. Searching time performance over different number of buildings.
Biomimetics 09 00125 g011
Figure 12. Routing planning map of IAC-RRT* algorithm in urban environment. (a) Single route found by IAC-RRT* algorithm. (b) Search process of IAC-RRT* algorithm. (c) Final planning route for all vehicles of IAC-RRT* algorithm.
Figure 12. Routing planning map of IAC-RRT* algorithm in urban environment. (a) Single route found by IAC-RRT* algorithm. (b) Search process of IAC-RRT* algorithm. (c) Final planning route for all vehicles of IAC-RRT* algorithm.
Biomimetics 09 00125 g012
Figure 13. System performance of IAC-RRT* algorithm compared with RRT algorithm. (a) Searching time performance of IAC-RRT* algorithm compared with RRT algorithm. (b) The optimal feasible distance of IAC-RRT* algorithm compared with RRT algorithm. (c) Times passing through Q s t of IAC-RRT* algorithm compared with RRT algorithm.
Figure 13. System performance of IAC-RRT* algorithm compared with RRT algorithm. (a) Searching time performance of IAC-RRT* algorithm compared with RRT algorithm. (b) The optimal feasible distance of IAC-RRT* algorithm compared with RRT algorithm. (c) Times passing through Q s t of IAC-RRT* algorithm compared with RRT algorithm.
Biomimetics 09 00125 g013
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

Zhou, Q.; Feng, H.; Liu , Y. Multigene and Improved Anti-Collision RRT* Algorithms for Unmanned Aerial Vehicle Task Allocation and Route Planning in an Urban Air Mobility Scenario. Biomimetics 2024, 9, 125. https://doi.org/10.3390/biomimetics9030125

AMA Style

Zhou Q, Feng H, Liu  Y. Multigene and Improved Anti-Collision RRT* Algorithms for Unmanned Aerial Vehicle Task Allocation and Route Planning in an Urban Air Mobility Scenario. Biomimetics. 2024; 9(3):125. https://doi.org/10.3390/biomimetics9030125

Chicago/Turabian Style

Zhou, Qiang, Houze Feng, and Yueyang Liu . 2024. "Multigene and Improved Anti-Collision RRT* Algorithms for Unmanned Aerial Vehicle Task Allocation and Route Planning in an Urban Air Mobility Scenario" Biomimetics 9, no. 3: 125. https://doi.org/10.3390/biomimetics9030125

Article Metrics

Back to TopTop