Introduction
Unmanned aerial vehicles (UAVs), prevalent in robotics and military applications, are recognized for their agility and deployment versatility. These attributes make them suitable for diverse operations such as surveillance, search and tracking, cargo transportation, and farm management [1]. However, the scope of tasks that a single UAV can execute is finite, necessitating the exploration of swarm control for UAVs to optimize their utilization. Recent studies have been focusing on tasks execution while concurrently avoiding potential collisions with obstacles or other agents [2], [3], [4], [5].
Key technologies for managing swarm UAVs encompass path planning and collision avoidance. In the absence of a collision avoidance algorithm during group movement or formation alignment, collisions may occur, potentially causing damage to the UAVs. A path planning algorithm that simultaneously avoids inter-UAV collisions, maintains a pre-determined formation, and swiftly reaches the destination is integral to swarm air control. Nonetheless, it is challenging for UAVs to establish a real-time, smooth, and safe collision-free path. Over the past few years, extensive research has been conducted on path planning in an unmapped environment, where the UAV avoids real-time sensor-detected obstacles and navigates toward the destination. Several methodologies have been proposed, including the A* algorithm for offline path planning [6], [7], Rapidly-exploring Random Tree (RRT) for quickly exploring uncharted areas [8], [9], [10], Model Predictive Control (MPC) [11], [12], geometric-based methods [13], [14], and artificial potential fields (APF) [15], [16].
The A* algorithm, a heuristic search algorithm extensively employed, introduces global information to verify all possible nodes of the shortest path and estimates the distance from the current node to the destination. This estimation reflects the probability that the current node is part of the shortest path. The A* algorithm executes a global search for path planning under UAVs’ dynamic constraints, generates a series of intermediate points, and initiates a local search to circumvent obstacles. Due to these characteristics, the A* algorithm is computationally complex and memory-intensive when planning a 3D path for UAVs. Additionally, post-processing to smooth the path is often required to apply the path to the UAV [6], [7].
The RRT is a sampling-based probabilistic algorithm designed to swiftly traverse unexplored areas in a search space. By randomly generating nodes and connecting them to the direction of their nearest neighbor, it achieves effective exploration. Kothari and Postlethwaite [9] applied chance constraints within the RRT to limit the probability of constraint violation and to navigate uncertain dynamic obstacles. To optimize computation time, Kuffner and LaValle [8] introduced a bidirectional RRT that conducts simultaneous searches from both the starting point and the destination. Furthermore, the RRT can find feasible paths in environments with high dimensional spaces and complexity. By integrating control functions with specific input parameters, this approach can be adapted to various constraints. However, paths derived from RRT often require refinement using the Dijkstra algorithm, which can extend the time needed for path adjustment.
MPC is a type of control system that optimizes control input considering current and expected future operations. This method uses the dynamic model of the system to predict future outputs and calculates the optimal control signal based on these predictions. MPC heavily depends on the accuracy of the model, and the calculation complexity can be high.
Geometric-based methods primarily find the optimal collision avoidance strategy based on the geometric properties of fixed-wing forms. For example, a geometric optimization approach to resolving collisions between planes minimizes the change in the velocity vector required to resolve collisions to obtain the minimum deviation from the normal trajectory. These methods are very efficient, but because they require a specific geometric relationship between the UAV and the obstacle, they can be difficult to apply in complex and dynamic environments [13], [14].
UAVs are commonly operated in dynamic environments characterized by high degrees of freedom and fast speeds. In such dynamic environments, each UAV in a swarm must be able to autonomously avoid collisions. The APF algorithm offers a mathematically simple and physically realistic approach that provides smooth paths suitable for robot and UAV applications. Consequently, the APF algorithm is well-suited for swarm UAVs that require agile and rapid movements. Because the APF algorithm does not guarantee complete collision avoidance, various algorithms have been explored to mitigate collision risks [17], [18].
Woods and La introduced an advanced version of the conventional potential field controller, termed the extended potential field controller (ePFC). This enhancement permits a drone to track dynamic targets while evading obstructions, offering improved performance in terms of smoother paths and reduced settling times. The stability of the ePFC was verified using the Lyapunov approach, and its effectiveness was demonstrated through lab experiments [19]. Meanwhile, Sun et al. focused on the complexities of path planning for drone formations in dense settings. They revamped the traditional artificial potential field (APF) algorithm, addressing challenges in multi-drone path planning in three-dimensional spaces. Their innovative approach ameliorated path oscillation issues and integrated a target exchange mechanism to circumvent local optimization traps. This improved algorithm was tested on a formation of 500 drones, proving its practical value in real-flight scenarios [20]. In parallel, Singletary et al. explored the relationship between the longstanding APFs and the more recent Control Barrier Functions (CBFs). They provided a theoretical linkage, indicating that a broad category of APFs can lead to the creation of CBFs that promise safety. These newly derived CBFs showcase versatility and are applicable to nonlinear systems. Practical tests further affirmed the potential of their method, especially for obstacle avoidance in both simulated and real environments, including for quadrotors with non-deterministic dynamics [21].
One challenge in implementing the APF algorithm is the setting of appropriate gains in the collision prevention Proportional-Integral-Differential (PID) controller [22]. If the gains are set too high, the resulting path becomes excessively long, while setting them too low compromises collision prevention. This indicates that the performance of the existing PF algorithm in collision avoidance is highly sensitive to the values of PID gains. Achieving optimal gain values for dynamic mission environments often necessitates extensive trial and error.
Furthermore, the APF algorithm reduces the velocity of UAVs when maneuvering around obstacles, resulting in increased time required to reach the target. Moreover, it makes UAVs susceptible to local minima, which is a common issue in PF-based approaches. Additionally, accurately predicting the timing of collision with obstacles remains challenging within the existing PF algorithm, as collision probability increases based on obstacle or UAV velocities. Given the fragile nature of UAVs and their vulnerability to even minor collisions, collision probability directly impacts mission capabilities. Existing collision avoidance algorithms struggle to handle obstacles with varying speeds, thus increasing the likelihood of collisions.
To address these limitations, this paper proposes an adaptive collision avoidance algorithm based on the Estimated Collision Time (ACACT) algorithm. The goal of the proposed algorithm is to save travel time by shortening the path length to the destination while avoiding collisions with obstacles, regardless of their speed. It exhibits robustness in dynamic environments and reduced sensitivity to PID gains.
A. Contributions
This paper presents a novel collision avoidance algorithm based on a potential field with adaptive target velocity. Specifically designed for swarm UAVs in dynamic environments, it prioritizes the shortest path to the target and effectively mitigates collisions using the estimated collision time. Additionally, a unique Path Traveling Time Ratio metric has been introduced, offering a comprehensive assessment of the algorithm’s performance in both collision avoidance and path planning.
The ACACT algorithm showcased noteworthy enhancements, achieving up to a 20% improvement in collision avoidance and path planning over traditional methods. This includes providing consistent collision avoidance capabilities across varying-speed obstacles, regardless of PID gain modifications, thus bolstering the algorithm’s versatility.
To comprehensively compare the established and the new algorithms, we devised a realistic simulator anchored on a physics engine, facilitating a meticulous evaluation of collision avoidance under diverse conditions.
Problem Statement
In this paper, the UAV employed is a quadrotor drone with a configuration of four rotors. This rotor arrangement grants the UAV unrestricted motion in all six degrees of freedom, enabling it to maneuver through three-dimensional paths in order to avoid obstacles and reach the target position. The practical implementation of the algorithm proposed necessitates two foundational assumptions:
Every UAV within the swarm continually disseminates its respective position and velocity data via a dependable network infrastructure.
Each UAV is integrated with a sensor adept at ascertaining both the location and speed of impediments in every direction, having a maximal detection range denoted as
.r_{s}
To simplify the calculations in the algorithm, each UAV is treated as a particle in 3D space. Therefore, although this paper primarily focuses on small UAVs, by increasing the size of the particles, the algorithm can be applied regardless of the UAV’s size.
Figure 1 illustrates a UAV positioned in a Cartesian coordinate system commonly used as the East-North-Up (ENU) coordinate system [23]. The origin represents the starting position of the UAV, denoted as
Attractive force and repulsive force at the UAV generated concerning the position of the obstacle and position of the goal.
The control method employed for swarm drones is based on centralized control. While decentralized approaches, which offer scalability and improved system stability, are actively researched, they fall outside the scope of this paper’s focus and will not be discussed in detail [24], [25].
For any vector
A. Gain Optimization Problem
Gain optimization is a common challenge in many control systems, where the performance is influenced by the choice of gain values. In most cases, a single gain optimization process can yield consistent performance when the control environment remains static. However, in the context of UAV path planning, the speeds of obstacles or other agents can vary, necessitating repeated gain optimization for different service environments. This results in the challenge of potential collision probabilities with fast-moving obstacles. There’s a trade-off between optimizing gains to reduce these risks and ensuring efficient trajectories that save travel time and energy with slow-moving obstacles.
B. Target Unreachability Problem
The target unreachability problem is a well-known limitation of existing APF algorithms, particularly when UAVs encounter static obstacles on their path to the target position. In such cases, the UAV may become trapped in local minima, preventing it from reaching the intended target position. This occurs when the repulsive forces to avoid obstacles and the attractive forces towards the target position balance each other, resulting in a net force of zero and stagnation of the UAV’s motion.
C. Oscillation Problem
The oscillation problem arises when obstacles are located near the UAV’s target position. The oscillation problem occurs when the UAV experiences repetitive oscillations near the target position due to the interplay of increasing repulsive forces from obstacles and diminishing attractive forces as the UAV approaches the target. Over time, the amplitude of these oscillations tends to decrease, eventually leading to the UAV reaching the target position after a significant duration.
Proposed Collision Avoidance Algorithm for SWARM UAVs
UAVs are required to respond rapidly to changes in their surrounding environment and generate real-time paths that are both efficient and safe. The APF algorithm is widely used for path planning in robotics, particularly in scenarios where map information is limited and dynamic obstacles are prevalent. The appeal of the APF algorithm lies in its simplicity and its ability to generate smooth trajectories that facilitate collision avoidance. Unlike approaches that search for a global trajectory, the APF algorithm generates local paths in close proximity, resulting in smoother paths for robots to follow. However, the APF algorithm necessitates careful optimization of gain values to effectively avoid collisions. Furthermore, even with gain optimization, there remains the possibility of collisions with faster obstacles that were not accounted for during the optimization process. Conservative gain optimization can result in overly long detours around slower obstacles, leading to inefficient path planning. To address these limitations, we propose an enhancement to the APF algorithm by introducing the concept of estimated collision time. Specifically, we adjust the change in path direction based on the velocity of obstacles, enabling the algorithm to provide stable collision avoidance paths for obstacles with varying speeds. As a result, our proposed algorithm ensures UAV safety even in scenarios where gain optimization has not been performed, distinguishing it from previous approaches that exhibited varying collision avoidance performance based on gain optimization.
A. APF Algorithm
Fig. 2 illustrates the concept of an artificial PF algorithm. In the traditional APF algorithm introduced by Khatib in 1986, the avoidance of collisions is achieved through the utilization of attractive and repulsive forces [26]. The attractive force, represented as a force vector, is directed towards the desired target location to guide the robot in reaching its destination. Conversely, the repulsive force, also expressed as a force vector, points in the opposite direction of obstacles, aiming to prevent collisions by creating a repulsive effect.
Example of an artificial potential field with a high potential obstacle and low potential target.
In Fig. 1, the attractive force vector \begin{equation*} \vec {a} = (x_{g}-x_{v}, y_{g}-y_{v}, z_{g}-z_{v}). \tag{1}\end{equation*}
\begin{equation*} \vec {r} = (x_{v}-x_{o}, y_{v}-y_{o}, z_{v}-z_{o}). \tag{2}\end{equation*}
\begin{equation*} \vec {r}_{p} = \frac {r_{s}^{2}}{ {\left \|{ \vec {r} }\right \|}^{2}} \hat {\vec {r}} \text {, if} \left \|{ \vec {r} }\right \| < \left |{ r_{s} }\right |, \tag{3}\end{equation*}
Let \begin{equation*} \vec {v}_{v} = k_{pa}\vec {a} + k_{pp}\vec {r}_{p}, \tag{4}\end{equation*}
B. Adaptive Collision Avoidance Based on Estimated Collision Time
1) Robust Path Generation Based on Estimated Collision Time
In order to enhance the collision avoidance performance in the presence of obstacles with different velocities, an additional repulsive force that takes into account the relative velocity between the UAV and the obstacles is incorporated. The relative velocity is calculated as \begin{equation*} \vec {v}_{r} = \vec {v}_{o} - \vec {v}_{v}. \tag{5}\end{equation*}
The repulsive force generated by the relative velocity vector \begin{align*} \vec {r}_{vn} = \begin{cases} \displaystyle \frac {\hat {\vec {r}}}{\hat {\vec {r}}\cdot \hat {\vec {v}}_{r}}-\hat {\vec {v}}_{r} &\text {if } 0 < \hat {\vec {r}}\cdot \hat {\vec {v}}_{r} < 1 \\ \displaystyle 0 &\text {else }. \end{cases} \tag{6}\end{align*}
\begin{equation*} \vec {v}_{v} = k_{pa}\vec {a} + k_{pp}\vec {r}_{p} + k_{pv}\vec {r}_{vn}. \tag{7}\end{equation*}
The concepts of projected target velocity and estimated collision time are employed for adaptive collision avoidance. These concepts allow for the anticipation of the target velocity and the prediction of the time until a potential collision. By incorporating these estimates, the system can dynamically adjust its trajectory and take proactive measures to avoid potential collisions. The estimated collision time is obtained by considering the distance to the obstacle and the target velocity. For objects moving at a constant velocity, the time it takes to traverse a certain distance can be determined by dividing the distance by the velocity. Similarly, when the UAV maintains its current target velocity, the estimated collision time is defined as the duration required to collide with the obstacle. However, since the direction of the target velocity may not align with the obstacle, the target velocity is projected in the direction of the obstacle for precise calculations. By continuously updating the target velocity based on obstacle avoidance, the UAV’s trajectory is dynamically generated.
The target velocity \begin{equation*} \vec{v}_{v}^{p}=-\left\|\vec{v}_v\right\| \cos \theta \cdot \hat{\vec{r}}, \tag{8}\end{equation*}
\begin{equation*} \cos \theta = \frac {-\vec {v}_{v}\cdot \vec {r}}{\left \|{ \vec {v}_{v} }\right \|\cdot \left \|{ \vec {r} }\right \|}. \tag{9}\end{equation*}
\begin{equation*} \vec {v}^{p}_{v} = \frac {\vec {v}_{v}\cdot \vec {r}}{\left \|{ \vec {r} }\right \|}\cdot \hat {\vec {r}}. \tag{10}\end{equation*}
\begin{equation*} t_{c} = \frac {\left \|{ \vec {r} }\right \|}{\left \|{ \vec {v}^{p}_{v} }\right \|}, \tag{11}\end{equation*}
\begin{equation*} t_{c} = \frac {{\left \|{ \vec {r} }\right \|}^{2}}{\left |{\vec {v}_{v}\cdot \vec {r}}\right |}. \tag{12}\end{equation*}
Target velocity
Let \begin{equation*} \left \|{ \vec {v}^{p+}_{v} }\right \| = \frac {\left \|{\vec {r}}\right \|}{t_{s}}. \tag{13}\end{equation*}
\begin{equation*} \vec {v}^{v}_{v} = \vec {v}_{v} - \vec {v}^{p}_{v}. \tag{14}\end{equation*}
\begin{equation*} \vec {v}^{+}_{v} = \left \|{\vec {v}^{p+}_{v}}\right \|\hat {\vec {v}}^{p}_{v} + \sqrt {{\left \|{\vec {v}_{v}}\right \|}^{2} - {\left \|{\vec {v}^{p+}_{v}}\right \|}^{2}}\hat {\vec {v}}^{v}_{v}, \tag{15}\end{equation*}
The obtained
2) Contingency Plan
As a characteristic of the APF algorithm, which iteratively generates paths within local regions to reach the target position, it is necessary to have a contingency plan to overcome situations where the algorithm becomes trapped in local minima and fails to reach the target position. To determine whether the UAV is trapped in a local minima, we can assess its position, velocity, and target point. If the magnitude of vector
When trapped in a local minima, obstacles typically obstruct the UAV’s forward movement. Therefore, to escape, it is advisable to move backward. Since information about obstacles is only available within a radius of
Algorithm 1 Contingency Plan
if
for all obstacle
compute
compute
compute
append values in the
end for
get random value
get random value
if (
get random value
get random value
else
compute
compute
compute
return
end if
end if
3) Oscillation Cancellation
Oscillation phenomena in UAVs caused by obstacles near the destination occasionally occur. While these oscillations generally diminish or disappear over time, minimizing the time required for UAVs with shorter flight durations to reach the destination is desirable. The first step is to determine whether the UAV has approached the target position and if there are obstacles in close proximity. By selecting an arbitrary distance, denoted as \begin{align*} \vec {v}_{v} = \begin{cases} \displaystyle k_{pa}\vec {a} &\text {if } \left \|{ \vec {a} }\right \| < r_{ref}, \vec {r}_{p} > 0, \vec {r}_{vn} < 0.2 \\ \displaystyle k_{pa}\vec {a} + k_{pp}\vec {r}_{p} \\ \displaystyle + k_{pv}\vec {r}_{vn} &\text {else }, \end{cases} \tag{16}\end{align*}
C. Collision Avoidance for SWARM UAVs
The first requirement for controlling a swarm of UAVs is a unified global coordinate system. Typically, each UAV maintains its own local coordinate system for controlling its own position. The system that controls the entire swarm issues commands based on the global coordinate system, so each UAV shares its coordinates with the system by transforming them using the following as \begin{align*} \begin{bmatrix} x_{l} \\ y_{l} \\ z_{l} \\ 1 \end{bmatrix} = \begin{bmatrix} \cos {\theta } &\quad -\sin {\theta } &\quad 0 &\quad t_{x} \\ \sin {\theta } &\quad \cos {\theta } &\quad 0 &\quad t_{y} \\ 0 &\quad 0 &\quad 1 &\quad t_{z} \\ 0 &\quad 0 &\quad 0 &\quad 1 \end{bmatrix} \begin{bmatrix} x_{g} \\ y_{g} \\ z_{g} \\ 1 \end{bmatrix} \tag{17}\end{align*}
In a swarm UAVs, it is necessary to avoid collisions not only with obstacles but also with other agents within the swarm. The proposed ACACT algorithm encompasses collision avoidance from multiple obstacles, including other agents.
The repulsive force for the \begin{equation*} \vec {r}_{i} = \sum _{j=0, j\neq {i}, \left \|{ \vec {r}_{j} }\right \| < \left |{ r_{s} }\right |}^{N} \vec {r}_{j}, \tag{18}\end{equation*}
\begin{equation*} \vec {r}_{min}: \left \|{ \vec {r}_{i} }\right \| \leq \left \|{ \vec {r}_{j} }\right \|, i\neq {j}\quad \forall i,j \in N, \tag{19}\end{equation*}
Algorithm 2 summarizes the aforementioned algorithm. The ACACT algorithm is, in theory, adaptable to extensive multi-UAV systems, encompassing between 100 and 1,000 UAVs. The scalability of this system hinges on two pivotal assumptions. Firstly, the position and velocity of every UAV in the swarm should be disseminated in real-time via a robust network infrastructure. Secondly, the ACACT algorithm necessitates a decentralized control architecture for individual UAV control. When realized through this distributed control paradigm, the algorithm exhibits a computational complexity of
Algorithm 2 Swarm Collision Avoidance
for all vehicle
Coordinate Transform
Compute
if
compute
else
compute
end if
if
execute Contingency Plan
end if
compute
if
compute
return
else
return
end if
end for
D. Performance Evaluation Metric
Dynamic path planning algorithms for UAVs in 3D space are currently limited, and there is a lack of suitable metrics for evaluating their performance. To address this challenge, we propose the path traveling time ratio (PTTR) as a novel measure to assess the effectiveness of collision avoidance and path planning. PTTR is defined as the ratio of the actual path traveling time to the ideal path traveling time, as shown in Fig. 4. It provides a quantitative measure of the efficiency and effectiveness of the UAV’s trajectory planning in navigating complex environments.PTTR is defined as \begin{equation*} PTTR = {\frac { { \frac {d}{v_{max}}} - t^{c}_{travel}}{t_{travel}}}, \tag{20}\end{equation*}
An example scenario showing how PTTR is calculated. In this scenario,
Therefore, the second term in (20) is defined as the collision area occupancy time ratio (CTR), which quantifies the proportion of time the UAV spends within the collision risk area relative to its total travel time. In this paper, the collision risk area is determined as a radius of 2 meters around the UAV, considering its size to be 0.5 meters. It is recommended to set the collision risk area as approximately 1.5 meters larger than the UAV size to account for variations in performance evaluation. For instance, if the UAV spends 1 second within the collision risk area during a total travel time of 8 seconds, the CTR would be calculated as 0.125. A CTR value of 0 indicates optimal collision avoidance performance, while smaller values signify more effective avoidance of collisions.
PTTR is theoretically bounded between 1 and −1, but in practice, TTR is typically greater than CTR, resulting in PTTR values ranging from 1 to 0. PTTR serves as a comprehensive metric for assessing path planning performance, encompassing both collision avoidance capability and overall path quality. A PTTR value close to 1 indicates superior path planning performance with effective collision avoidance. The PTTR metric is applicable across diverse environments. In a given scenario, if Algorithm A exhibits a superior PTTR value compared to Algorithm B, it suggests that Algorithm A is a more efficient path-planning algorithm. To compute the PTTR value, one requires the UAV’s initial position, its target position, the total traveling time, and the time expended within the collision-area. To evaluate the algorithms, at least 30 experiments are conducted per scenario, and the highest and lowest PTTR values are excluded before computing the average. The PTTR graphs for each algorithm are presented in Section IV-B.
Simulation and Experimental Results
A. Simulation Environment
To evaluate the ACACT algorithm, a simulator has been implemented using Gazebo, a widely adopted platform in conjunction with the Robot Operating System (ROS) [28]. The simulator incorporates a physics engine that emulates real-world dynamics, while also offering sensor models capable of introducing Gaussian noise to mimic real-world conditions. The simulation employs the 3DR Iris drone model, and the drone’s control software utilizes the PX4 flight stack, which is a prevalent tool in drone research. The loading process for the PX4 flight stack and Iris models in the Gazebo simulation is detailed in [29]. For drone control within the ROS ecosystem, Mavros, a ROS application, is utilized to establish a connection with the PX4 flight stack [30]. The simulation was conducted on a computer equipped with a 10th generation Intel i7 CPU, 48GB of RAM, and without a dedicated GPU.
In Fig. 5, a formation of ten Iris drones is employed, and the ACACT algorithm was applied to the simulation. In the simulation, the drones maintain a formation centered around a reference drone, with the remaining nine drones rotating counterclockwise while adhering to the formation. A flight video showcasing the formation flight is available in [31]. Fig. 6 depicts the software architecture of the simulation. The algorithm proposed is amenable to both centralized and decentralized control approaches. Our developed simulator for swarm UAV formation control is available for download at [32].
Formation flight with 10 iris in Gazebo environment(upper). Attractive and repulsive forces and the target velocity as a result of the ACACT algorithm acting on each UAV(lower).
Software architecture of the simulator. (a) centralized architecture, (b) decentralized architecture.
A force visualization tool has been developed, as illustrated in Fig. 5, to evaluate the algorithm’s efficacy during formation flight simulations [33]. This tool graphically depicts the attractive force (displayed in green), the repulsive force (displayed in red), and the target velocity (displayed in light blue), conveying both their magnitude and direction. Moreover, the tool presents the three-dimensional path followed by each UAV. Such a visual representation facilitates a deeper understanding of the workings of the proposed algorithm.
B. Experiment
A comprehensive set of experiments were carried out to assess the effectiveness of the proposed collision avoidance algorithm across various UAV contexts. Fig. 7 delineates three scenarios representative of the challenges typically encountered when UAVs undergo formation changes in swarm settings. Detailed results pertaining to Scenario1 are illustrated in Fig. 8. This figure contrasts the performance of the newly proposed ACACT algorithm with the existing APF algorithm. In this test case, two UAVs were initially stationed at points A(0, 5, 5) and B(0, −5, 5). With both UAVs navigating concurrently toward opposite directions, the aim was to gauge the proficiency of each algorithm in averting collisions and ensuring that the drone adheres to the most direct trajectory while reaching the target position quickly.
Three distinct experimental scenarios designed to assess the algorithm’s performance. (a) Scenario1, (b) Scenario2, (c) Scenario3.
For Scenario1: Comparison of performance of (a), (b), (c), (d) with conventional algorithm and (e), (f), (g), (h) with ACACT algorithm in the four cases where the gain
The image in Fig. 8 displays the flight paths and the proximity between the drones. The space between drones was measured 30 times a second. When they came less than 2 m apart, it was counted as a collision. Results indicate that the older PF method led to several collisions, evident in Fig. 8a, 8b, and 8d. These collisions occurred because the forces pushed the drones towards each other, making them follow longer paths and reducing their speeds. In contrast, the new ACACT method prevented these collisions and chose clearer paths, leading to faster destination arrivals.
The ACACT algorithm consistently exhibited superior performance in collision avoidance compared to other established methods. The comprehensive analysis of experimental results was conducted using the PTTR metric, as introduced in Section III-D. Fig. 9 displays the efficacy of collision avoidance path planning based on this metric. As previously discussed, a PTTR value closer to 1 indicates a more efficient UAV performance in both collision avoidance and expedited target approach. Within the figure, the term “offset” delineates the deviation from the optimal tuning point and indicates the extent to which the PID gain deviates from this optimal point. Typically, as the PID gain diminishes, so does its collision avoidance capability. Hence, a rising offset correlates with a declining PTTR. Conversely, when the PID gain is elevated, the resultant path tends to elongate, leading to a prolonged duration to reach the target, which in turn causes the PTTR to decline. Across all examined scenarios, the ACACT algorithm consistently outshined its counterparts.
For Scenario1: Evaluation based on the proposed average PTTR metric for each algorithm and situation.
The second experiment, similar to Scenario1, becomes more challenging with the inclusion of four UAVs. UAV No. 1 transitions from A(5, 5, 5) to D(−5, −5, 5), while UAV No. 2 goes from B(5, −5, 5) to C(−5, 5, 5). UAVs 3 and 4 navigate from D to A and from C to B, respectively. Commands for all UAV movements are issued concurrently. Conditions were deliberately made challenging by setting the
Top view of the Scenario2 experimental path for four algorithms, with the PID gain
Top view of the Scenario2 experimental path for four algorithms, under conditions where the obstacles’ velocities and the UAV’s maximum velocity exceed anticipated values (5m/s). (a) APF, (b) Adaptive APF, (c) Dynamic APF, (d) Proposed.
Fig. 12 provides a multi-angle view of the Scenario2 results. Notably, the path length chosen by the proposed algorithm, as seen in the left of Fig. 12a, is marginally longer than other algorithms. This implies a preference for slightly extended routes to ensure safe collision avoidance. Despite the longer path, due to the algorithm’s aim to minimize deceleration while evading collisions, the destination is reached much quicker than with other algorithms, as evident in Fig. 12b. When assessed using the proposed metric, which gauges both collision avoidance and rapid target attainment, the performance of the proposed algorithm surpasses others in all situations, as shown in Fig. 12c.
For Scenario2: (a) Average traveling distance for each algorithm under varied situations; (b) Corresponding average traveling time; (c) Evaluation based on the proposed average PTTR metric for each algorithm and situation.
In the third experiment, a UAV moving in a straight line faces multiple obstacles intermittently charging towards it. UAV No. 1 transitions from A(−17, 0, 5) to B(7, 0,5). UAV No. 2 moves from C(−5, 5, 5) to D(−15, −5, 5), while UAV No. 3 travels from E(−5, −5, 5) to F(−15, 5, 5). Approximately 2.5 to 3 seconds later, UAV No. 4 starts from G(5, 5, 5) to reach E, and UAV No. 5 sets off from H(5, −5, 5) targeting C. As with Scenario2, conditions were made more challenging by setting
Top view of the Scenario3 experimental path for four algorithms, with the PID gain
Top view of the Scenario3 experimental path for four algorithms, under conditions where the obstacles’ velocities and the UAV’s maximum velocity exceed anticipated values (5m/s). (a) APF, (b) Adaptive APF, (c) Dynamic APF, (d) Proposed.
Fig. 15 displays the results of Scenario3 from different perspectives. Mirroring the findings from Scenario2, the path determined by the proposed algorithm, as shown in the left side of Fig. 15a, is marginally elongated. Nevertheless, it facilitates the fastest arrival at the target position, and its PTTR score significantly surpasses those of the other algorithms.
For Scenario3: (a) Average traveling distance for each algorithm under varied situations; (b) Corresponding average traveling time; (c) Evaluation based on the proposed average PTTR metric for each algorithm and situation.
The parameters employed in the experiments are enumerated in Table 1. Parameters consistent across experiments are excluded from the table for clarity. The sensing range, denoted as
In the case of the conventional algorithm, it was observed that when the maximum speed was set to 5 m/s, the overall PTTR value was lower compared to the case with a speed of 3 m/s. This can be attributed to the increased inertial force acting on the drone when it avoids collisions at higher speeds, resulting in longer travel distances and a higher likelihood of passing through the collision zone.
Furthermore, for the conventional algorithm, noticeable differences were observed between cases where collision avoidance PID gains were appropriately set and cases where they were not. However, in the proposed ACACT algorithm, the performances of these two cases were almost identical, with a PTTR value of approximately 0.5. These results suggest that the ACACT algorithm consistently delivered excellent performance, regardless of the specific settings of the collision avoidance PID gains.
In terms of the CTR, a value of 0 was recorded for all cases of the ACACT algorithm (except vel5), as indicated in Fig. 9. This indicates that the proposed algorithm effectively avoids collisions, and no obstacles enter the collision area of the UAV. When the maximum speed is set to 5 m/s, the CTR values are comparable between the proposed and conventional algorithms. However, the proposed algorithm exhibits improved Travel Time Ratio (TTR) and overall performance.
Conclusion
This research presents an advanced collision avoidance algorithm based on estimated collision time, addressing the limitations of the conventional potential field method. The algorithm calculates the estimated collision time using the projected velocity. This allows unmanned aerial vehicles (UAVs) to adjust their direction to avoid collisions without slowing down, provided the estimated collision time remains below a predefined safety threshold. This approach significantly improves the UAV’s path smoothness and reduces unnecessary energy consumption, resulting in faster arrival at the target position. Extensive experiments are conducted in a simulated environment to assess the efficacy of the proposed algorithm. A novel performance metric called Path Traveling Time Ratio (PTTR) is introduced to compare and analyze the performance of the proposed algorithm against existing approaches. The experimental results reveal an average PTTR improvement of 0.126, representing a maximum 20% enhancement in collision avoidance performance when considering the full metric range. The simulations, incorporating a physics engine that closely emulates real-world conditions, demonstrate the algorithm’s practical applicability and offer an effective means for its evaluation.