Next Article in Journal
Virtual Measurement of Explosion-Proof Performance: Application of an Improved RBF-GMSE-Based Surrogate Model to the Safety Performance Characterization of Coal Mine Equipment
Previous Article in Journal
Experimental Study of Post-Dryout Heat Transfer in a Tight-Lattice 3-Rod Bundle
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Recent Advances and a Hybrid Framework for Cooperative UAV Formation Control

College of Engineering, King Saud University, Riyadh 11473, Saudi Arabia
*
Author to whom correspondence should be addressed.
Appl. Sci. 2025, 15(17), 9761; https://doi.org/10.3390/app15179761
Submission received: 20 July 2025 / Revised: 21 August 2025 / Accepted: 26 August 2025 / Published: 5 September 2025

Abstract

Formation control plays a vital role in coordinating multi-agent systems and swarm robotics, enabling collaboration in applications such as autonomous vehicles, robotic swarms, and distributed sensing. This paper introduces the formation-control problem, highlights its challenges, and compares centralized and decentralized schemes. We review recent advances and analyze popular algorithms, then propose a hybrid framework that combines leader–follower tracking with an artificial potential field (APF) safety layer. In three-UAV tests, the followers cross paths and one encounters a static obstacle. We run multiple simulations across scenarios with obstacles and varying formations. Results show the hybrid controller maintains the required formation while avoiding inter-agent collisions. Using quantitative metrics, we find the leader–follower baseline achieves the lowest formation error but has the most safety violations, whereas APF greatly improves safety at the cost of higher error. The hybrid combines these strengths—delivering APF-level safety with lower error and negligible runtime overhead—providing a practical balance between precise formation keeping and robust collision avoidance.

1. Introduction

Unmanned aerial vehicles (UAVs), commonly known as drones, have experienced growing usage across various sectors including defense, agriculture, and healthcare [1]. Their ability to operate in harsh or high-risk environments makes them highly suitable for missions such as battlefield monitoring and disaster recovery [2]. Moreover, recent work leverages UAVs as mobile sensing and edge computing platforms to support the development and deployment of machine learning and augmented reality applications [3,4]. Beyond aeronautics, advances from adjacent domains, particularly space robotics, are increasingly being adapted to interoperate with UAVs and to enhance their navigation capabilities, including operation in GNSS-denied environments [5]. As the demand for more complex and coordinated missions grows, the use of multiple UAVs working cooperatively has emerged as a crucial solution. One of the core challenges in the coordination of UAV swarms is formation control, which enables groups of autonomous agents to move in organized patterns to achieve shared goals [6]. Recent studies have also addressed the challenges of time-varying delays and external disturbances, proposing observer-based approaches that improve stability and reliability in UAV operations carrying payloads [7,8]. Formation control has garnered significant research interest due to its applications in swarm robotics, distributed sensing, and collaborative autonomous systems. This area of study draws inspiration from natural swarming behaviors, such as those observed in bird flocks or fish schools. The goal is to develop algorithms that allow multiple agents to coordinate effectively, adapt to dynamic environments, and perform complex tasks collectively. A central concept in formation control is the concept of multi-agent systems (MASs), which involves multiple autonomous agents interacting to achieve common objectives. MAS architectures leverage decentralized decision making and local interactions to overcome the limitations of single-agent systems. These include improved scalability, fault tolerance, and adaptability. Over time, MASs have been applied in a wide range of domains, including robotic transportation, resource management, environmental monitoring, and search-and-rescue missions [9].
Despite their advantages, multi-agent and swarm-based systems face unique challenges such as ensuring reliable decentralized coordination and maintaining formation integrity under constraints like limited communication or environmental obstacles. Addressing these challenges has led to the development of various formation-control strategies including centralized, decentralized, and hybrid approaches, which are explored further in this paper [10]. Moreover, we review recent advances in cooperative control and formation-control strategies for multi-agent systems. We examine a range of formation strategies, highlighting their theoretical foundations and practical implementations. A comprehensive analysis is conducted to assess the strengths, limitations, and suitability of each algorithm. In addition, we propose a hybrid cooperative formation control for the problem of UAVs.
The key contributions of the paper are as follows:
  • We present a comparative evaluation of recent formation-control algorithms for UAV swarms, including leader–follower, virtual structure, behavior-based, APF, and graph theory approaches.
  • We propose a novel hybrid control framework that combines the leader–follower strategy with the collision-avoidance capabilities of APF.
  • We analyze the proposed framework and conduct a stability analysis using Lyapunov-based methods.
  • We demonstrate the effectiveness of the proposed framework through simulations, showing successful formation tracking and dynamic collision avoidance in multiple scenarios.
  • We provide a quantitative comparison of three controllers, leader–follower, APF, and the proposed hybrid using standardized metrics.

2. Related Work

In this section, we will review different strategies that have been used to tackle the formation-control problem in multi-agent systems. To keep the discussion organized and easy to follow, we start by breaking subjects into the two most common control schemes: centralized and decentralized. This distinction is useful because it sets the stage for understanding how agents coordinate and share responsibilities in different setups. Following that, we will explore specific algorithms that have shaped the field, such as the leader–follower method and behavior-based approaches. These are grouped in a way that reflects how they fit within the larger control frameworks. The goal here is not limited to listing past work, but to offer a clearer picture of how various methods are compared, what are their strengths and weaknesses, and what are their applications. Structuring the review this way makes it easier to connect the dots across different approaches and understand the logic behind each one.

2.1. Formation-Control Schemes

Commanding a swarm to maintain a certain formation can be achieved through centralized or decentralized control [11]. Both of these schemes have their advantages and disadvantages, and the selection between them depends on the situation. Table 1 presents a brief comparison between these approaches [12].

2.1.1. Centralized

Centralized formation control is a method where a central unit or agent directs a group of agents to move in a coordinated behavior. This approach allows for precise control over their positions and trajectories, ensuring they maintain a specific formation. By collecting information about each agent’s state, the central unit can optimize their movements, which is especially useful in tasks such as monitoring or rescue operations. One of the best known approaches based on the centralized scheme is the leader–follower algorithm. However, this system can face challenges like difficulties in scaling to larger groups and risks associated with relying on a single control point, prompting a need for careful consideration of its practical implementation. Figure 1 describes a centralized multi-agent swarm.
One notable contribution in the field is a centralized control, geometric-based formation strategy that emphasizes both connectivity preservation and formation flexibility [13]. The approach frames the problem from a graph-theoretic perspective, ensuring that the group remains connected during both steady and dynamic formation changes. A key feature of this method is its ability to maintain consistent and stable formations while enabling smooth switching between different shapes, all while avoiding inter-robot collisions through careful structure preservation. One of the limitations of the current approach lies in its centralized control, which deserves attention. A distributed implementation could offer greater flexibility and fault tolerance for the resulting formation. Another relevant study addresses the computational challenges in multi-agent reinforcement learning (MARL), especially in cooperative tasks with large joint action spaces [14]. While centralized training with decentralized execution is common, algorithms like Q-learning often suffer from heavy computation due to the need to evaluate all possible joint actions when updating Q-values. To overcome this, the authors propose the Top-2 Q-value (T2Q) algorithm, which significantly reduces the number of comparisons needed during training by maintaining only the top two Q-values for each state. A centralized approach to multi-agent planning under temporal and resource constraints was proposed in [15]. Their goal is to generate coordinated action plans that allow agents to achieve a set of goals while respecting both qualitative and quantitative temporal constraints, as well as limits on cost, number of agents, and other factors. The method uses AND–OR graph planning to handle task decomposition and scheduling, with all coordination performed centrally—leaving no planning autonomy to individual agents.

2.1.2. Decentralized

In decentralized formation control, the coordination of the group of agents does not depend on the central unit or agent. Instead, each agent makes decisions based on local information and interactions with its neighbors, enabling flexible and scalable systems. This approach promotes robustness, as the failure of one agent does not compromise the overall system performance. Agents, as shown in Figure 1, can dynamically adjust their positions to maintain the desired formation, which is particularly useful in environments where communication may be limited or intermittent. Decentralized formation control is widely applicable in scenarios such as swarm robotics, autonomous vehicles, and distributed sensor networks, where adaptability and resilience are essential. Decentralized control has been widely used in the latest research along with graph theory to control a network of robots. In [16], a robust distributed consensus-tracking framework for multi-UAV systems that simultaneously rejects measurement noise and external disturbances was explored. It combines a distributed observer with a local MEE and UDE dual estimator controller to estimate the leader’s state under switching topologies, noting that classic UDE alone can amplify noise. And in [17], the authors modeled mobile robots’ relations as an undirected graph to be used as a wireless network. Undirected graph-formation control was used in [18] along with a distributed model predictive control that allows every UAV to solve its own constrained receding-horizon problem. Their approach combines a formation-error term with an obstacle-avoidance penalty, and because of their decentralized setup, they were able to scale without a central bottleneck and more fault tolerance. Ref. [19] proposed a framework for decentralized control that allowed a team of robots to maintain a predefined formation and follow a planned path. That was done by implementing a model for switching between simple decentralized controllers that allows for changes in the robots’ formation.

2.2. Formation-Control Algorithms

Each of the existing formation-control schemes leaves critical gaps. In the leader–follower method, it gives clear geometry and low computational cost but struggles with dynamic obstacle avoidance and rapid topology changes. The artificial potential fields (APF) add collision avoidance but suffer from local minima, oscillations, and brittle gain tuning; make it hard to maintain specified coordinates. For a graph theory-based approach, it ensures distributed coordination yet often yields slow transients and relies on strict connectivity. And in the behavior-based schemes, UAVs adapt quickly but lack formal stability guarantees and repeatable performance. To close these gaps, we propose a hybrid framework that preserves the structural clarity and scalability of leader–follower control while embedding an APF safety layer that enforces inter-agent spacing and obstacle clearance. Table 2 lists some of these characteristics. In this section, related research work will be reviewed.

2.2.1. Leader–Follower

For the leader–follower formation control, several algorithms have been developed. In [20], the authors present a leader–follower formation-control algorithm integrated with collision-avoidance capabilities. Collision avoidance is primarily activated during transient states, as robots transition from random initial positions to an organized formation. To ensure collision avoidance, artificial potential functions are used. If a robot’s safety zone is violated, its reference linear velocity is temporarily halted to prioritize collision resolution. On the other hand, a controlled group of differential-drive wheeled mobile robots using a decentralized leader–follower scheme is presented in [21]. The robot only requires its own position and the position of the nearest leader. The authors applied a collision-avoidance mechanism between the members of the group by applying a state-dependent delay in the desired trajectory. To ensure that robots track the planned trajectory, an output feedback control and attitude observer are used based on the kinematic model of the differential-drive wheeled robots. Another approach was proposed in [22], an adaptive formation-control algorithm for a network of autonomous mobile robots. This network consists of only two leaders that are aware of the reference velocity. The other robots are considered followers. Those followers do not know the reference velocity. With this configuration, the robots were able to move in a rigid formation with a fixed velocity. The paper concludes with one open issue regarding spacing errors. That is, with the presence of disturbance at the leader, robots might increase the spacing error between two robots, which is considered a mesh stability problem. In [23], a distributed formation strategy for a team of mobile robots containing leaders and followers was studied. Followers can sense the relative displacements of neighboring followers as well as all leaders, while the leaders remain detectable by the followers. Within each group, the roles of followers and leaders are interchangeable. a control algorithm was proposed in [24] that resolves multiple quadrotor formation challenges based on a leader–follower approach. Their approach combined sliding mode control (SMC) with a linear quadratic regulator (LQR) to track the trajectory of individual robots. The outer loop is responsible for position control, which employs LQR to generate reference attitude angles for the inner loop. Their simulation results demonstrated the system’s stability, even when subjected to sudden external disturbances, such as wind gusts. A flight-control method based on leader–follower formation for multiple UAVs using feature modeling was proposed in [25]. The proposed approach employs a three-layer feedforward neural network to model the control dynamics of the UAV formation and uses intermediate variables to design a deviation control law for position and attitude. This method minimizes yaw and, by optimizing piecewise power approach parameters, enables the formation to converge more effectively to the desired distance. It also ensures faster convergence and allows the UAV formation to reorganize efficiently under disturbances and chatter within a short time. Another scheme, proposed in [26], effectively achieves the desired formation configuration in minimal time, accounting for control input constraints and ensuring collision avoidance during reconfiguration. The algorithm is straightforward to implement in real time, with experimental results showcasing its efficiency and ability to meet the specified requirements. In [27], a methodology was introduced that optimizes congestion management within a swarm of autonomous agents, ensuring collision avoidance with obstacles and restoring the desired formation shape after obstacle evasion. The approach introduces an agent population-control factor that considers the proximity of obstacles. The swarm leader makes centralized decisions by analyzing agent parameters (coordinates and velocities) along with obstacle data to compute the population factor. Based on this, the swarm’s grouping configuration is determined, selecting the setup that minimizes overall congestion delay. A distributed observer-based leader–follower consensus control was presented in [28] for LPV multi-agent systems, applied to quadcopter UAV formations. Using Lyapunov theory and LMIs with Polya’s theorem, the method ensures stability while observers estimate states and controllers synchronize followers with a virtual leader. A quasi-LPV quadcopter model is developed, and simulations with five UAVs show accurate state estimation, smooth trajectory tracking, and stable formation, with future work aimed at collision avoidance and fault tolerance. An observer-based consensus-tracking control algorithm was proposed in [7], addressing the leader–follower formation of multiple quadrotor UAVs under unknown time-varying delays. Their scheme ensures consensus tracking with the desired H∞ performance, effectively mitigating the impact of such delays in multi-agent systems by minimizing their influence.

2.2.2. Virtual Structure

Virtual structure formation control handles the swarm as a single virtual rigid body. It defines a geometric template in a body-fixed frame, and each UAV is assigned a fixed offset in that frame. By applying the formation’s global position translation, rotation, and, if needed, scaling to these offsets, each UAV tracks its corresponding moving waypoint. This yields coherent group motion with preserved relative spacing and provides a simple and precise mechanism to reshape the formation in response to mission objectives or obstacle avoidance. There are several research efforts focusing on virtual structured-based formation control. In [29], they introduced a formation-generation algorithm and an obstacle-avoidance strategy for multiple unmanned surface vehicles (USVs). Their algorithm combines a virtual structure with an APF (VSAPF), achieving high precision in maintaining formation shape and flexibility in adapting to formation changes. A virtual-structure formation-control approach was introduced in [30] for UAV swarms that does not require constant real-time inter-UAV communication, letting each drone track its assigned point from a virtual leader trajectory with simple geometric/LOS guidance.

2.2.3. Behavior-Based Formation Control

Behavior-based formation control for UAV swarms specifies simple local interaction rules for each vehicle that, together, yield complex global behaviors such as forming and maintaining patterns. Each UAV acts on its own sensor as well as the sensor for the states of nearby neighbors, applying basic behaviors—cohesion, collision avoidance, and alignment—so that coordinated formations emerge without a central controller. Behavior-based formation control has also gained significant attention due to its flexibility and adaptability in dynamic environments. A decentralized behavior-based formation-control algorithm was introduced in [31] for multiple robots that incorporates obstacle avoidance. Unlike conventional methods requiring global communication or leader state information, the approach relies only on relative positions between neighboring robots and obstacles. A formation is generated using a formation matrix and allocation algorithm, allowing robots to autonomously select roles and maintain formation even with dynamic group changes. A hybrid behavior-based (HB) method was proposed in [32], integrating four behaviors designed in accordance with COLREGs requirements into three behaviors derived from the Null Space-Based (NSB) method. This hybrid approach simultaneously addresses rendezvous tasks, formation maintenance, and collision avoidance for both static and dynamic obstacles. A behavior-based formation-control approach for swarm robots was presented in [33], extending the traditional behavior-based navigation method used for single robots. The focus was on defining and analyzing multiple behaviors to tackle two main challenges in formation control: initial formation and formation maintenance during navigation while avoiding obstacles. Simulation results confirmed the effectiveness of the proposed method in achieving successful formation control in swarm robotic systems. Reactive behaviors for four different formations and three types of formation references were developed in [37]. These behaviors were successfully demonstrated in both laboratory environments using mobile robots and in outdoor scenarios involving nonholonomic four-wheel-drive robots.

2.2.4. Artificial Potential Field

The artificial potential field (APF) approach forms and maintains UAV formations by assigning each vehicle virtual forces derived from a potential function. Attractive terms pull each UAV toward its designated slot or leader trajectory, while repulsive terms push it away from obstacles and neighboring vehicles to prevent collisions. Summing these components yields a guidance vector that drives smooth convergence to—and maintenance of—the desired formation. APF methods have also been widely applied in formation control, particularly for enhancing obstacle-avoidance capabilities. A collision-prediction mechanism was introduced in [34] to assess whether each UAV needs to perform obstacle avoidance. The proposed method achieved swarm-formation control and maintained formation while ensuring obstacle avoidance using the APF technique. Simulation results demonstrated that the UAV swarm could efficiently generate, maintain, and reconstruct the desired formation in a real-time, distributed manner while effectively avoiding obstacles.
A joint control method combining a robust H∞ controller with an improved APF method was proposed in [35]. The authors developed a mathematical model for the UAV formation flight system based on a leader–follower algorithm. The formation accuracy by using only an APF method is limited due to dynamic uncertainties from system disturbances and unmodeled factors. Hence, the authors designed an H∞ controller with three channels to achieve high precision formation keeping control. The simulation demonstrated the effectiveness of the proposed method. Another concept in APF is Adaptive Artificial Potential Field (IAAPF). In [36], the authors proposed an improved IAAPF algorithm for multi-UAV formation that attenuates the goal’s pull when far away and adapts obstacle repulsion with distance, augmented by virtual inter-UAV forces for collision avoidance; coupled with a sliding mode control inner loop in a leader–follower architecture, the hybrid controller reduces local oscillations and achieves safer, smoother paths in cluttered scenes, as shown in their simulation.

2.2.5. Graph Theory

Graph theory formation control models the swarm as a graph with UAVs as nodes and neighbor links as edges. Distributed consensus laws, built from adjacency and Laplacian matrices, make each UAV regulate relative distance or bearing to neighbors so the group converges to and preserves the target shape. Graph theory has also been widely utilized in formation control to model and manage communication and interaction among multiple agents. A cooperative guidance-control method was proposed in [38]. Their method uses the back-stepping approach to quickly achieve the desired formation and ensure the multi-UAV system reaches a steady state. The communication framework between UAVs was established based on graph theory. In this setup, one UAV serves as a virtual leader positioned at the center of a triangle, while the other three UAVs occupy its vertices. The guidance-control law was derived using the back-stepping approach, and the Lyapunov function was constructed to demonstrate the stability of the proposed method in both formation aggregation and maintenance. Another graph theory-based method was proposed in [39] for controlling formations that uses only local sensor-based information. The leader robot controls the follower robots to maintain the formation using directed graphs to navigate through terrain with obstacles while maintaining a predefined formation, changing formations when needed.
Table 3 summarizes these papers for each algorithm and their application.

3. Proposed Hybrid Formation-Control Framework

In the previous sections, we examined numerous papers built on various frameworks. Each framework is well suited for addressing specific problems, though it may not be effective for others. In this section, we will first define our problem and then propose a framework that effectively addresses the proposed issue.

3.1. Problem Formulation

The problem we aim to address revolves around the navigation of a swarm of UAVs operating collaboratively. In swarm missions, maintaining a specific formation is often crucial to optimizing the mission’s overall efficiency and achieving better results. A well-defined formation ensures effective resource utilization, streamlined coordination, and improved task execution. Our primary objective is to develop a control strategy that enables the swarm to preserve its formation dynamically while simultaneously avoiding internal collisions. This approach prioritizes minimizing complexity to ensure practical implementation and reliability, even in challenging and dynamic environments. However, the overall complexity depends on the communication architecture: if data are relayed only through the leader, the system scales with the number of UAVs; if all agents exchange information within the swarm, the communication load increases more significantly, while computation per agent still grows with the swarm size. This distinction highlights that scalability and feasibility depend on the chosen communication strategy, with larger swarms requiring more robust links and onboard resources.

3.2. Proposed Scheme Overview

To address the specified problem described in Section A, we propose a robust and innovative hybrid approach that integrates the low computational overhead and efficiency of the leader–follower model with the dynamic adaptability and flexibility offered by APF. The leader–follower model provides a straightforward mechanism for coordination, wherein a designated leader determines the trajectory while the followers align themselves accordingly, ensuring cohesive movement and minimizing computational complexity. However, relying solely on this model may limit adaptability in environments with obstacles or rapidly changing conditions. To overcome these limitations, APF are incorporated to enable dynamic responses to external influences. These fields generate attractive and repulsive forces, guiding agents to avoid obstacles, maintain safe distances, and preserve the desired formation structure. By combining these two methodologies, our hybrid approach strikes a balance between structured simplicity and responsive adaptability, making it a comprehensive solution to the challenges highlighted in the problem. Our objective is to achieve and maintain a specific formation for a three-UAV swarm that consists of one leader and two followers. The followers are required to occupy symmetric positions at fixed lateral offsets to the leader’s right and left. To test the collision-avoidance capability of the proposed controller, the two followers are commanded to deliberately cross each other’s trajectories during the transient phase; throughout this maneuver, safe separation must be preserved, and the agents must subsequently settle into the target configuration flanking the leader. Moreover, a static obstacle is placed directly in front of one follower along its approach path to evaluate the controller’s ability to maintain formation integrity and stability. Hence, the follower must avoid the obstacle with bounded deviation and promptly return to its prescribed lateral offset after clearance.
The overall block diagram of the system is shown in Figure 2.

3.3. Mathematical Modeling

To evaluate the proposed framework, we employed a simplified model for the swarm candidates, representing each as a point on a 2D plane, assuming each UAV in the swarm has a fixed height that is the same for all of them. Moreover, this model allows us to integrate it into different UAV configurations either into a quadcopter or a fixed wing UAV. Before presenting the mathematical model, we first define the assumptions and requirements of our framework. The formation consists of three UAVs: one leader and two followers. All UAVs are assumed to fly at the same fixed altitude, and the control inputs are restricted to adjustments in speed and heading. In the simulation study, a static obstacle at the same altitude is considered, representing terrains or predefined buildings, and the corresponding results will be presented in the next section. While the proposed model accounts for static obstacles, handling dynamic obstacles requires the integration of onboard sensing capabilities such as LiDAR, ultrasonic sensors, or cameras to enable real-time detection and avoidance. This two-dimensional model is intended to serve as a high-level controller, transmitting commands from a companion computer to the autopilot, which in turn manages the low-level controls such as pitch and roll. Furthermore, the positions and velocities of both the leader and the followers are assumed to be available to the swarm. For larger formations, simultaneous data exchange among agents increases the load on communication links and onboard processors, requiring more robust communication infrastructure depending on the communication architecture, whether data are relayed solely through the leader or exchanged among all agents in the swarm and there is higher computational capacity to maintain reliable coordination.
The state-space representations for the leader and the follower are provided in Equation (1).
X L = x L y L θ L , X F = x F y F θ F
X L and X F are the leader and the follower states, respectively. x, y, and θ are position and angle. Their movement in a 2D plane can be expressed as follows:
x ˙ L y ˙ L θ ˙ L = v cos θ L v sin θ L w L , x ˙ F y ˙ F θ ˙ F = v cos θ F v sin θ F w F
w L and w F are the rotational speed for the leader and the follower, which can be expressed as:
w F = k p · ( θ F d θ F )
k p is a proportional gain that determines how aggressively the follower adjusts its orientation. v is the linear speed vector, which can be expressed as v = V γ . V is a positive, constant speed and γ is a positive variable gain which proportionally increases with the linear error. θ F d is the desired orientation of the follower, which is based on the leader’s position and orientation. θ F is the current orientation of the follower.
The desired orientation θ F d can be calculated using the leader’s current position and orientation and can be expressed as:
θ F d = atan2 ( d y , d x )
where ( d x , d y ) are:
d x = d o f f x d F x
d y = d o f f y d F y
where d o f f x and d o f f y are the desired ( x , y ) offsets from the leader.
In this model, we design a normal leader–follower formation algorithm. This means that the followers might collide with the leader or the other follower since the main model does not inherently include the collision-avoidance term. Hence, based on APF, we added the collision-avoidance term in the proposed model.
We considered the follower’s model in (2) as an attraction force, which means the follower is attracted to a specific offset to the leader. To implement the collision-avoidance term, we change the input controller of the follower as follows:
u F = F a t t + i = 1 N F r e p
where F a t t is the attraction term from (3), N is the number of agents, and F r e p is the repulsion term, which can be expressed as:
F r e p = k r e p · 1 p F p L 1 R · p F p L p F p L 2
where k r e p is the repulsion constant that defines the repulsion speed of the follower to the leader. p L and p F are the ( x , y ) positions of the leader and the follower, respectively. R is the desired radius of the repulsion force. When R >   p F p L , the repulsion force F r e p = 0 . Equation (9) describes the states of F r e p :
F r e p = k r e p · 1 p F p L 1 R · p F p L p F p L 2 , R >   p F p L 0 , R   p F p L

3.4. Stability Analysis

To analyze the stability of the proposed controller, we consider the controller in (7), where F a t t and F r e p are the terms from (2) and (8). The stability of this has been studied comprehensively in [40]. For F a t t , a Lyapunov stability theorem will be used. We defined the errors as follows:
e x = x d e s i r e d x a c t u a l
e y = y d e s i r e d y a c t u a l
e θ = θ d e s i r e d θ a c t u a l
where e x , e y , e θ are the errors of each state.
The Lyapunov function can be expressed as:
V ( e x , e y , e θ ) = 1 2 e x 2 + 1 2 e y 2 + 1 2 e θ 2
and
V ˙ ( e x , e y , e θ ) = e x e ˙ x + e y e ˙ y + e θ e ˙ θ
where e ˙ x = x ˙ a c t u a l , e ˙ y = y ˙ a c t u a l , and e ˙ θ = θ ˙ a c t u a l , assuming the desired attitude is fixed.
Expanding (14) by substituting (2) will result in the following:
V ˙ = e x v cos θ e y v sin θ e θ k p ( θ d e s i r e d θ a c t u a l )
Since we are using (17) to calculate the desired angle, both x and y errors can be expressed as:
cos θ e x e , sin θ e y e
Rewriting (15):
V ˙ = v e x 2 e v e y 2 e e θ 2 k p
when k p > 0 , it follows that V ˙ 0 . Therefore, when t , V ( e x , e y , e θ ) monotonically decreases. This implies that the system asymptotically converges to the desired position for any positive gain k p > 0 .

4. Illustrative Example

Initial simulations were done based on the proposed model with multiple scenarios. The first scenario: the leader is moving in a circle with rotational speed of 0.1 deg/s and k p = 10 , then the follower will follow the leader with an offset of 1 m on the right of the leader as shown in Figure 3, where the leader is the blue dot, and the follower is the red dot.
In the second scenario, there are two followers with different offsets, right and left of the leader as shown in Figure 4, where the leader is the blue dot, and the followers are the red dot and the green dot.
Implementing Equation (8) in the third scenario will result in collision-avoidance behavior from the follower (red dot) towards the leader (blue dot) as shown in Figure 5. We can notice that the follower is avoiding the leader by creating a new path to follow.
This shows the collision-avoidance term between the leader and the follower. However, our concern is activating this term between the followers. We added a new follower and applied the repulsion term in (8) but modifying the p L variable to the followers’ position.
Figure 6 shows the followers (red and green dots) trying to maintain a relative position to the leader (blue dot) while avoiding colliding with each other.
In some missions, the followers may change their relative position during the mission. Figure 7 shows the leader is moving in an s-path mission and the followers will maintain the relative position, and then when t = 15 s, the two followers will replace their postion again without colliding with each other.
Followers may encounter a static, predefined obstacle (e.g., terrain). In Figure 8, follower 2 is maintaining the formation while avoiding the static obstacle.

5. Discussion

In the previous section, we derived and illustrated the proposed method that combines the strengths of the leader–follower and APF. In this section, we present quantitative metrics to compare the leader–follower baseline, the APF baseline, and the proposed hybrid method. First, we define three metrics: root-mean-square error (RMSE), collision-avoidance performance, and computational efficiency. RMSE quantifies the discrepancy between the followers’ desired and actual relative positions and it can be expressed as:
RMSE = 1 N i = 1 N d i actual d i desired 2
where N is the number of agents. The collision-avoidance performance metric defines how safely the team remains separated. We track the minimum pairwise distance among leader–follower1, leader–follower2, and follower1–follower2 at every step. Thus, we calculate the percentage of time steps when pairwise distance is below a safety threshold d safe . Computational efficiency measures the controller’s runtime cost. At each step, we record the wall clock time to compute the control update and report two values (ms) using the tic toc function in Matlab. The mean per-step latency and the maximum latency are found. Lower mean latency implies a lighter steady-state burden and better scalability to larger swarms or embedded CPUs. A small maximum is equally crucial for real-time operation, since even rare spikes can miss deadlines and jeopardize closed-loop stability. All simulations and timing measurements were performed on a Windows 11 machine with a 12th Gen Intel Core i7-12700KF (3.60 GHz). Results may vary across different hardware, operating systems, and software configurations.
Based on the above metrics, Table 4 summarizes the comparison. Leader–follower maintains formation best (lowest RMSE) and has the fastest computation, but it shows the highest safety violations. APF, by contrast, offers much better safety (fewer violations, larger separations) at the expense of a higher RMSE. The hybrid controller combines their strengths: it lowers RMSE relative to APF while preserving safe distances. Its per-step execution time is higher than both baselines, but only slightly above APF (≈0.0003 ms), which is not a practically significant difference on our platform.

6. Conclusions and Future Work

In this paper, we introduced the concept of formation control, exploring its challenges and applications in multi-agent systems and swarm robotics. We examined the centralized and decentralized schemes for formation control, highlighting their respective strengths, limitations, and areas of application. Additionally, we presented a review of the latest advancements in formation-control research, analyzing popular algorithms, their strengths, weaknesses, and recent developments in each category. Building on this foundation, we proposed a novel framework that integrates the ease of implementation of the leader–follower algorithm with the collision-avoidance capabilities of the APF algorithm. Our initial design and model were introduced, the system’s stability was studied and analyzed, and simulations demonstrated the effectiveness of this combined approach. To stress test the controller, we conducted three-UAV trials in which the two followers intentionally crossed paths and one encountered a static obstacle; across multiple scenarios with obstacles and varying formations, the hybrid maintained the required formation while avoiding inter-agent collisions. Quantitative evaluation showed that the leader–follower baseline achieved the lowest formation error but incurred the most safety violations, whereas APF improved safety at the cost of higher error. The proposed hybrid matched APF-level safety while reducing formation error and adding negligible runtime overhead, indicating practicality for onboard deployment. Future work will refine the proposed framework, conduct extensive simulations across diverse scenarios, and include experimental validation on real UAV platforms, such as hardware-in-the-loop and outdoor field tests, to test on-board performance, communication constraints, and robustness to disturbances, advancing toward a reliable, deployable solution for multi-agent formation control.

Author Contributions

Conceptualization, S.N.A., S.A.A. and Y.B.S.; methodology, S.N.A., S.A.A. and Y.B.S.; software, S.N.A.; validation, S.N.A., S.A.A. and Y.B.S.; formal analysis, S.N.A., S.A.A. and Y.B.S.; investigation, S.N.A., S.A.A. and Y.B.S.; resources, S.N.A., S.A.A. and Y.B.S.; data curation, S.N.A., S.A.A. and Y.B.S.; writing—original draft preparation, S.N.A.; writing—review and editing, S.A.A. and Y.B.S.; visualization, S.N.A.; supervision, S.A.A. and Y.B.S.; project administration, Y.B.S.; funding acquisition, Y.B.S. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by General Authority for Defense Development (GADD) in Saudi Arabia through project number (GADD_2024_01_387).

Data Availability Statement

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

Acknowledgments

The authors would like to acknowledge the General Authority for Defense Development (GADD) in Saudi Arabia for funding this research through project number (GADD_2024_01_387).

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Hossain, N.U.I.; Lutfi, M.; Ahmed, I.; Akundi, A.; Cobb, D. Modeling and Analysis of Unmanned Aerial Vehicle System Leveraging Systems Modeling Language (SysML). Systems 2022, 10, 264. [Google Scholar] [CrossRef]
  2. Do, H.T. Formation Control Algorithms for Multiple-UAVs: A Comprehensive Survey. EAI Endorsed Trans. Ind. Netw. Intell. Syst. 2021, 8, e3. [Google Scholar] [CrossRef]
  3. Xu, Y.; Xu, H.; Chen, X.; Zhang, H.; Chen, B.; Han, Z. Blockchain-Based AR Offloading in UAV-Enabled MEC Networks: A Trade-off Between Energy Consumption and Rendering Latency. IEEE Trans. Veh. Technol. 2025; early access. [Google Scholar] [CrossRef]
  4. Duong, D.V.A.; Akter, S.; Yoon, S. Task Offloading and Resource Allocation for Augmented Reality Applications in UAV-Based Networks Using a Dual Network Architecture. Electronics 2024, 13, 3590. [Google Scholar] [CrossRef]
  5. Qiu, X.; Liao, S.; Yang, D.; Li, Y.; Wang, S. Visual geo-localization and attitude estimation using satellite imagery and topographical elevation for unmanned aerial vehicles. Eng. Appl. Artif. Intell. 2025, 153, 110759. [Google Scholar] [CrossRef]
  6. Do, H.; Nguyen, H.; Nguyen, V.-C.; Nguyen, M.; Nguyen, M. Formation control of multiple unmanned vehicles based on graph theory: A Comprehensive Review. ICST Trans. Mob. Commun. Appl. 2022, 7, e3. [Google Scholar] [CrossRef]
  7. Liu, X.; Wang, Y.; Peng, Z. Observer-based consensus tracking control for multiple quadrotor UAVs with unknown time-varying delays in leader–follower formations. Machines 2024, 12, 337. [Google Scholar]
  8. Hernández-González, O.; Targui, B.; Valencia-Palomo, G.; Guerrero-Sánchez, M.E. Robust cascade observer for a disturbance unmanned aerial vehicle carrying a load under multiple time-varying delays and uncertainties. Int. J. Syst. Sci. 2024, 55, 1056–1072. [Google Scholar] [CrossRef]
  9. Shi, Z.; Tu, J.; Zhang, Q.; Liu, L.; Wei, J. A Survey of Swarm Robotics System. In International Conference in Swarm Intelligence; Lecture Notes in Computer Science; Springer: Berlin/Heidelberg, Germany, 2012; Volume 7331. [Google Scholar]
  10. Lau, H.K. Error Detection in Swarm Robotics: A Focus on Adaptivity to Dynamic Environments. Ph.D. Thesis, Department of Computer Science, University of York, York, UK, 2012. [Google Scholar]
  11. De La Cruz, C.; Carelli, R. Dynamic Modeling and Centralized Formation Control of Mobile Robots. In Proceedings of the IECON 2006—32nd Annual Conference on IEEE Industrial Electronics, Paris, France, 7–10 November 2006; pp. 3880–3885. [Google Scholar]
  12. Liu, Y.; Liu, J.; He, Z.; Li, Z.; Zhang, Q.; Ding, Z. A Survey of Multi-Agent Systems on Distributed Formation Control. Unmanned Syst. 2023, 12, 913–926. [Google Scholar] [CrossRef]
  13. Keshmiri, S.; Payandeh, S. Collaborative Agents—Research and Development; Guttmann, C., Dignum, F., Georgeff, M., Eds.; Springer: Berlin/Heidelberg, Germany, 2011; pp. 85–98. [Google Scholar]
  14. Liao, D.; Zhang, Z.; Song, T.; Liu, M. An Efficient Centralized Multi-Agent Reinforcement Learner for Cooperative Tasks. IEEE Access 2023, 11, 139284–139294. [Google Scholar] [CrossRef]
  15. Baki, B.; Bouzid, M.; Ligęza, A.; Mouaddib, A.I. A centralized planning technique with temporal constraints and uncertainty for multi-agent systems. J. Exp. Theor. Artif. Intell. 2006, 18, 331–364. [Google Scholar] [CrossRef]
  16. Zheng, Z.; Tong, S.; Wang, E.; Zhu, Y.; Shao, J. Robust Consensus Tracking Control for Multi-Unmanned-Aerial-Vehicle (UAV) System Subjected to Measurement Noise and External Disturbance. Drones 2025, 9, 61. [Google Scholar] [CrossRef]
  17. Winfield, A.F. Distributed Sensing and Data Collection Via Broken Ad Hoc Wireless Connected Networks of Mobile Robots. In Distributed Autonomous Robotic Systems 4; Springer: Tokyo, Japan, 2000. [Google Scholar]
  18. Yang, M.; Guan, X.; Shi, M.; Li, B.; Wei, C.; Yiu, K.-F.C. Distributed Model Predictive Formation Control for UAVs and Cooperative Capability Evaluation of Swarm. Drones 2025, 9, 366. [Google Scholar] [CrossRef]
  19. Das, A.K.; Fierro, R.; Kumar, V.; Ostrowski, J.P.; Spletzer, J.; Taylor, C.J. A vision-based formation control framework. IEEE Trans. Robot. Autom. 2002, 18, 813–825. [Google Scholar] [CrossRef]
  20. Kowalczyk, W.; Kozlowski, K. Leader–Follower Control and Collision Avoidance for the Formation of Differentially-Driven Mobile Robots. In Proceedings of the 2018 23rd International Conference on Methods & Models in Automation & Robotics (MMAR), Miedzyzdroje, Poland, 27–30 August 2018; pp. 132–137. [Google Scholar]
  21. Hirata-Acosta, J.; Pliego-Jiménez, J.; Cruz-Hernádez, C.; Martínez-Clark, R. Leader–Follower Formation Control of Wheeled Mobile Robots without Attitude Measurements. Appl. Sci. 2021, 11, 5639. [Google Scholar] [CrossRef]
  22. Guo, J.; Lin, Z.; Cao, M.; Yan, G. Adaptive leader–follower formation control for autonomous mobile robots. In Proceedings of the American Control Conference, Baltimore, MD, USA, 30 June–2 July 2010; pp. 6822–6827. [Google Scholar]
  23. Yu, H.; Shi, P.; Lim, C.-C.; Wang, D. Formation Control for Multi-Robot Systems with Collision Avoidance. Int. J. Control 2018, 92, 2223–2234. [Google Scholar] [CrossRef]
  24. Ghamry, K.A.; Zhang, Y. Formation control of multiple quadrotors based on leader–follower method. In Proceedings of the 2015 International Conference on Unmanned Aircraft Systems (ICUAS), Denver, CO, USA, 9–12 June 2015; pp. 1037–1042. [Google Scholar]
  25. Chen, Y.; Deng, T. Leader–Follower UAV formation flight control based on feature modelling. Syst. Sci. Control Eng. 2023, 11, 2268153. [Google Scholar] [CrossRef]
  26. Kamel, M.A.; Yu, X.; Zhang, Y. Real-time optimal formation reconfiguration of multiple wheeled mobile robots based on particle swarm optimization. In Proceedings of the 2016 12th World Congress on Intelligent Control and Automation (WCICA), Guilin, China, 12–15 June 2016; pp. 703–708. [Google Scholar]
  27. Yasin, J.N.; Haghbayan, M.H.; Yasin, M.M.; Plosila, J. Swarm formation morphing for congestion-aware collision avoidance. Heliyon 2021, 7, e07840. [Google Scholar] [CrossRef] [PubMed]
  28. Trejo, J.A.V.; Ponsart, J.C.; Adam-Medina, M.; Valencia-Palomo, G.; Theilliol, D. Distributed Observer-based Leader-following Consensus Control for LPV Multi-agent Systems: Application to multiple VTOL-UAVs Formation Control. In Proceedings of the 2023 International Conference on Unmanned Aircraft Systems (ICUAS), Warsaw, Poland, 6–9 June 2023; pp. 1316–1323. [Google Scholar] [CrossRef]
  29. Yan, X.; Jiang, D.; Miao, R.; Li, Y. Formation Control and Obstacle Avoidance Algorithm of a Multi-USV System Based on Virtual Structure and APF. J. Mar. Sci. Eng. 2021, 9, 161. [Google Scholar] [CrossRef]
  30. Guo, J.; Liu, Z.; Song, Y.; Yang, C.; Liang, C. Research on Multi-UAV Formation and Semi-Physical Simulation with Virtual Structure. IEEE Access 2023, 11, 126027–126039. [Google Scholar] [CrossRef]
  31. Lee, G.; Chwa, D. Decentralized behavior-based formation control of multiple robots considering obstacle avoidance. Intell. Serv. Robot. 2018, 11, 127–138. [Google Scholar] [CrossRef]
  32. Tan, G.; Zhuang, J.; Zou, J.; Wan, L. Coordination control for multiple unmanned surface vehicles using hybrid behavior-based method. Ocean Eng. 2021, 232, 109147. [Google Scholar] [CrossRef]
  33. Xu, D.; Zhang, X.; Zhu, Z.; Chen, C.; Yang, P. Behavior-Based Formation Control of Swarm Robots. Math. Probl. Eng. 2014, 2014, 205759. [Google Scholar] [CrossRef]
  34. Fu, X.; Pan, J.; Wang, H.; Gao, X. A Formation Maintenance and Reconstruction Method of UAV Swarm based on Distributed Control. Aerosp. Sci. Technol. 2020, 104, 105981. [Google Scholar] [CrossRef]
  35. Sheng, H. New multi-UAV formation keeping method based on improved APF. Chin. J. Aeronaut. 2023, 36, 249–270. [Google Scholar] [CrossRef]
  36. Zhang, P.; Wang, Z.; Zhu, Z.; Liang, Q.; Luo, J. Enhanced Multi-UAV Formation Control and Obstacle Avoidance Using IAAPF–SMC. Drones 2024, 8, 514. [Google Scholar] [CrossRef]
  37. Balch, T.; Arkin, R.C. Behavior-based formation control for multirobot teams. IEEE Trans. Robot. Autom. 1998, 14, 926–939. [Google Scholar] [CrossRef]
  38. Zhang, J.; Yan, J.; Zhang, P. Multi-UAV Formation Control Based on a Novel Back-Stepping Approach. IEEE Trans. Veh. Technol. 2020, 69, 2437–2448. [Google Scholar] [CrossRef]
  39. Desai, J.P.; Ostrowski, J.; Kumar, V. Controlling formations of multiple mobile robots. In Proceeding of the IEEE International Conference on Robotics and Automation, Leuven, Belgium, 20 May 1998; pp. 2864–2869. [Google Scholar]
  40. Khatib, O. Real-time obstacle avoidance for manipulators and mobile robots. In Proceedings of the 1985 IEEE International Conference on Robotics and Automation, St. Louis, MO, USA, 25–28 March 1985; pp. 500–505. [Google Scholar]
Figure 1. This figure describes a multi-agent communication scheme. (a) Centralized multi-agent scheme. (b) Decentralized multi-agent scheme.
Figure 1. This figure describes a multi-agent communication scheme. (a) Centralized multi-agent scheme. (b) Decentralized multi-agent scheme.
Applsci 15 09761 g001
Figure 2. Overall block diagram of a single UAV.
Figure 2. Overall block diagram of a single UAV.
Applsci 15 09761 g002
Figure 3. Scenario 1: leader and follower moving in a circle.
Figure 3. Scenario 1: leader and follower moving in a circle.
Applsci 15 09761 g003
Figure 4. Scenario 2: leader and two followers moving in a circle.
Figure 4. Scenario 2: leader and two followers moving in a circle.
Applsci 15 09761 g004
Figure 5. Scenario 3: leader and follower moving in a circle with collision avoidance.
Figure 5. Scenario 3: leader and follower moving in a circle with collision avoidance.
Applsci 15 09761 g005
Figure 6. Scenario 4: leader and multiple followers moving in a circle with collision avoidance.
Figure 6. Scenario 4: leader and multiple followers moving in a circle with collision avoidance.
Applsci 15 09761 g006
Figure 7. Scenario 5: leader and multiple followers moving in an s-path shape while changing their relative position.
Figure 7. Scenario 5: leader and multiple followers moving in an s-path shape while changing their relative position.
Applsci 15 09761 g007
Figure 8. Scenario 6: leader and multiple followers with a static obstacle.
Figure 8. Scenario 6: leader and multiple followers with a static obstacle.
Applsci 15 09761 g008
Table 1. Comparison of schemes.
Table 1. Comparison of schemes.
Control SchemeOptimizationScalabilityRobustness
Centralizedsufficientlimitedlimited
Decentralizedlimitedsufficientsufficient
Table 2. Strengths and limitations of formation-control algorithms.
Table 2. Strengths and limitations of formation-control algorithms.
AlgorithmControl TypeStrengthsLimitations
Leader–Follower [7,20,21,22,23,24,25,26,27,28]CentralizedSimple design, easy implementation, and robust formation trackingDependence on leader, lack of feedback from followers to leader, and poor inherent obstacle avoidance
Virtual Structure [29,30]CentralizedHigh stability and precise formation maintenanceLimited flexibility without replanning; poor inherent obstacle avoidance
Behavior-Based [31,32,33]DecentralizedHandles multiple-goal missions effectivelyDifficult to model mathematically and lower stability compared to other methods
Artificial Potential Fields (APFs) [34,35,36]DecentralizedSmooth and continuous trajectories and effective obstacle avoidanceLess efficient in highly complex environments
Table 3. Summary of Related Work on Formation Control Algorithms.
Table 3. Summary of Related Work on Formation Control Algorithms.
AlgorithmRef.Application
Leader–Follower[20]Controlled robots while implementing collision avoidance
[21]Controlled a group of differential-drive wheeled mobile robots
[22]Controlled a network of robots using two leaders’ scheme
[23]Controlled a team of mobile robots using leader–follower approach
[24]Combined Sliding Mode Control (SMC) with Linear Quadratic Regulator (LQR) for trajectory tracking of robots
[25]Optimized the attitude of multiple UAVs
[26]Achieved desired formation configuration efficiently in minimal time
[27]Optimized congestion management, obstacle avoidance, and formation restoration in swarms
[28]A distributed observer-based leader-following consensus control for LPV multi-agent of quadcopter UAVs to track a leader and maintain stable formations.
[7]Proposed an observer-based consensus-tracking-control algorithm for leader–follower quadrotor formations under unknown time-varying delays.
Virtual Structure[29]Combined virtual structure with APF for precise and flexible formation maintenance
[30]Virtual-structure formation controller where a virtual leader lets UAVs track assigned offsets with minimal inter-UAV communication
Behavior Based[31]Utilized formation matrices using a behavior-based framework for flexible formations
[32]Hybrid behavior-based (HB) method integrating multiple behaviors
[33]Extended behavior-based navigation from single robots to swarm-formation control
[37]Developed reactive behaviors for various formations and reference types
APF[34]Swarm-formation control and obstacle avoidance using APF
[35]Combined robust H∞ control with enhanced APF for UAV control
[36]Proposed an IAAPF with a sliding mode inner loop in a leader–follower setup scales attraction-repulsion and adds virtual inter-UAV forces to achieve robust, collision-free multi-UAV formations in cluttered scenes.
Graph Theory[38]Cooperative guidance-control method for multiple UAVs
[39]Formation control based on graph theory using local sensor information
Table 4. Quantitative comparison across formation algorithms.
Table 4. Quantitative comparison across formation algorithms.
AlgorithmFormation RMSE (m)Safety Violations (%)Average Execution Time (ms)Max Execution Time (ms)
Leader–Follower2.090725.3490.0150682.0216
APF2.994500.0180852.6592
Hybrid (proposed)2.314000.0182533.3568
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

Alkhamees, S.N.; Alsaif, S.A.; Bin Salamah, Y. Recent Advances and a Hybrid Framework for Cooperative UAV Formation Control. Appl. Sci. 2025, 15, 9761. https://doi.org/10.3390/app15179761

AMA Style

Alkhamees SN, Alsaif SA, Bin Salamah Y. Recent Advances and a Hybrid Framework for Cooperative UAV Formation Control. Applied Sciences. 2025; 15(17):9761. https://doi.org/10.3390/app15179761

Chicago/Turabian Style

Alkhamees, Saleh N., Saif A. Alsaif, and Yasser Bin Salamah. 2025. "Recent Advances and a Hybrid Framework for Cooperative UAV Formation Control" Applied Sciences 15, no. 17: 9761. https://doi.org/10.3390/app15179761

APA Style

Alkhamees, S. N., Alsaif, S. A., & Bin Salamah, Y. (2025). Recent Advances and a Hybrid Framework for Cooperative UAV Formation Control. Applied Sciences, 15(17), 9761. https://doi.org/10.3390/app15179761

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop