Skip Content
You are currently on the new version of our website. Access the old version .
AerospaceAerospace
  • Article
  • Open Access

30 January 2026

Image-Based Visual Servoing for Quadrotor Formation Encirclement and Tracking of Unknown Targets

,
,
,
,
,
and
1
School of Aerospace Engineering, Beijing Institute of Technology, Beijing 100081, China
2
Advanced Research and Innovation Center (ARIC), Department of Aerospace Engineering, Khalifa University, Abu Dhabi 127788, United Arab Emirates
3
School of Automation, Chongqing University, Chongqing 400044, China
4
Center for Autonomous Robotic Systems, Khalifa University of Science and Technology, Abu Dhabi 127788, United Arab Emirates
This article belongs to the Section Aeronautics

Abstract

A target state estimation method based on multiple quadrotors is proposed for unknown maneuvering targets, and a distributed formation control method Image-Based Visual Servoing (IBVS) is also proposed to achieve encirclement tracking of unknown maneuvering targets. In the tracking control, collision avoidance constraints for nodes within the formation are also introduced, and based on the shared position information within the formation, the positions of other nodes within the Field of View (FOV) of each node are predicted for detecting unknown targets. Firstly, an Interacting Multiple Model (IMM) was designed based on multiple motion modes to estimate the position and velocity of the target. A virtual camera coordinate system containing translational and yaw rotations was established between the formation and the target based on the estimated values. Then, a distributed control method based on IBVS was further designed by combining image deviation. At the same time, a safe distance between nodes within the formation was introduced, and collision avoidance constraints of the Control Barrier Function (CBF) were designed. Finally, the position of the formation nodes within the FOV was predicted. The simulation results demonstrate that, utilizing the proposed estimation method, the estimation accuracy for target velocity improves by 26.5% in terms of Root Mean Square Error (RMSE) compared to existing methods. Furthermore, the proposed control method enables quadrotor formations to successfully achieve encirclement tracking of unknown maneuvering targets, significantly reducing tracking errors in comparison to conventional approaches.

1. Introduction

With the further enhancement of the intelligence and autonomy of quadrotors, as well as the increasing exploration of the potential of multi-agent systems across various industries, low-cost and efficient autonomous control methods for quadrotor formations have attracted growing attention from enthusiasts and researchers [1,2,3,4,5]. In scenarios involving the tracking of unknown aerial maneuvering targets, accurate perception of the target’s motion state is indispensable [6,7]. For lightweight small-scale quadrotors, lightweight onboard strapdown cameras are often used for environmental and target state perception [8]. However, a single camera only provides two-dimensional information of the target, making it difficult for the quadrotors to obtain an accurate estimate of the target’s three-dimensional motion. Moreover, the maneuverability of the target can easily cause it to move out of the quadrotor’s camera FOV, thereby hindering effective autonomous tracking [9]. The use of stereo cameras can partially alleviate this issue [10,11], yet, constrained by small quadrotor platforms, accurately estimating the motion state of highly maneuverable and distant targets remains challenging [12]. Employing formations of small quadrotors can better adapt to the aforementioned scenarios [13]. Theoretically, the perception of the target is no longer limited by the size of a single quadrotor platform, enabling the tracking of highly maneuverable targets. Furthermore, by designing specific formations [11], the target can be more effectively observed by multiple onboard cameras—for instance, by positioning the target’s image near the center of the FOV of cameras oriented from different directions and locations.
Accurately estimating the target velocity based on observation data from quadrotor formations is essential for formation tracking control. Common methods include direct differentiation of position measurements [14] and the design of Extended Kalman Filters (EKF) [15]. While direct differentiation may be feasible for estimating low-speed targets with stable motion, it is susceptible to noise interference [16]. The EKF can satisfy most application scenarios but may introduce significant estimation errors when the target’s motion mode changes [17]. For targets exhibiting abrupt motion changes, the IMM filter may offer better adaptability for state estimation [18]. The essence of the IMM is similar to that of the EKF. However, when the target’s motion mode changes, the IMM adaptively adjusts the estimation gain coefficients based on the matching degree of different motion models, thereby reducing estimation errors caused by target motion variations [19].
For target tracking scenarios, lightweight and small quadrotors often employ vision-based servo control methods, which are primarily categorized into Position-Based Visual Servoing (PBVS) and IBVS [20]. PBVS constructs the three-dimensional positional relationship relative to the target based on two-dimensional image information from the camera and subsequently designs the control law using this established relative positional relationship [21]. Consequently, the design of its control law is generally not constrained by the limitations of two-dimensional image errors, and it often disregards FOV constraints. However, its control accuracy and stability can be affected by modeling uncertainties, camera calibration errors, and noise [22]. In contrast, IBVS directly designs the control law based on two-dimensional image errors, thereby reducing the influence of modeling uncertainties, camera calibration errors, and noise to a relatively lesser extent [22], while also more readily guiding the target toward the center of the FOV.
In general, the primary objective of formation control schemes is to enable a group of agents to achieve predefined relative positions, distances, and maintain a desired configuration (typically geometric) under certain inter-agent constraints [23]. For instance, Wang [24] designed a circular formation comprising three quadrotors around a target to facilitate localization and motion planning for micro-drones. Karras [25] proposed an encirclement formation of four quadrotors for capturing maneuvering targets. Rothe [26] devised a specialized quadrotor formation for net-based capture of targets. Wu [27] developed a specific quadrotor formation for maritime strike and defense operations. Montijano [28] designed several formation configurations for quadrotors to investigate the influence of formations on observation performance. The authors further noted that a commonly employed distributed formation control strategy is consensus-based control, in which states such as position and orientation of each agent converge collectively to their respective desired values. This approach offers robustness against a variety of interaction topologies within the team.
We propose a distributed formation control method for quadrotors based on IBVS, designed to generate an approaching and encircling formation for tracking an unknown maneuvering target. This method enables stable tracking of the target while preventing collisions among formation members during the process. The main contributions of this work are as follows:
Multi-View Target Estimation via IMM Filtering.
Using onboard strapdown cameras on multiple quadrotors, the unknown target is localized from multiple viewpoints. Considering both constant velocity (CV) and constant acceleration (CA) motion modes, an IMM filter is designed to estimate the target’s position and velocity, and the estimated states are utilized to compensate for the control input.
Distributed IBVS Control with Virtual Camera Coordinates.
By establishing a virtual camera coordinate system that incorporates the quadrotor’s own attitude, the influence of pitch and roll motions on the target’s image features is eliminated. Based on the virtual image error and the estimated target states, a distributed IBVS control law is designed using graph connectivity theory. The stability of the proposed method is analyzed via Lyapunov-based techniques, enabling stable formation-based encircling and tracking of the unknown target while driving the target’s image toward the center of the FOV.
Collision Avoidance and Formation Prediction of Quadrotors.
Taking into account the minimum safe distance among quadrotors within the formation, CBFs are incorporated with the motion model to derive linearized collision avoidance constraints. A quadratic cost function is formulated, leading to an optimal control law that satisfies all constraints. Moreover, by integrating the estimated target states with each quadrotor’s own attitude, the image positions of other formation members in the camera field are predicted, thereby preventing misidentification of fellow quadrotors as the target.
Numerical Simulation and Validation.
Numerical simulations are conducted for formation-based encircling and tracking of an unknown maneuvering target. The results demonstrate that the adopted IMM estimator improves target velocity estimation accuracy by 23% compared to existing methods. The proposed control scheme achieves stable encircling and tracking of the target by a quadrotor formation, with significantly reduced tracking errors relative to state-of-the-art approaches.
The remainder of this paper is organized as follows. Section 2 introduces the necessary preliminaries. Section 3 details the design process of the estimator and controller. Simulation experiments are presented in Section 4, followed by the conclusion in the final section.

2. Preliminaries

2.1. Coordinate Frame Description

As illustrated in Figure 1, the system involves multiple coordinate frames. Transformations between different frames m and n are performed via the rotation matrix R m n The Earth-fixed coordinate system (ECS) is denoted as frame O e x e y e z e . The body-fixed coordinate system (BCS) is denoted as frame O b x b y b z b . The camera coordinate system (CCS), denoted as frame O c x c y c z c , is typically assumed to coincide with the BCS for simplicity of description. Frame O v x v y v z v represents the virtual camera coordinate system (VCS). Its origin coincides with O c and it is established to simplify the description of the projection relationship between the translational motion of the target in the ECS and the image, without being influenced by camera attitude. The position of the target in the ECS is denoted as T. The coordinates u vt , v vt represent the position of T in the virtual image, while u rt , v rt represents the position of T in the real image.
Figure 1. System framework and coordinate system diagram.

2.2. Quadrotor Model

p ˙ = v v ˙ = g + 1 m ( F + F d ) R ˙ b e = R b e ω × J ω ˙ = τ ω × J ω + τ d
Here, p = p x p y p z T and v = v x v y v z T denote the velocity and position of the quadrotor in the Earth-fixed coordinate system, respectively, satisfying v = R b e v b , where v b = v b x v b y v b z T represents the velocity of the quadrotor in the BCS. g = 0 0 g G T and g G denotes the gravitational constant. R b e 3 × 3 denotes the rotation matrix from the BCS to the ECS. ω = ω x ω y ω z T represents the angular velocity of the quadrotor, and ω × denotes the skew-symmetric matrix generated by ω . F 3 and τ 3 denote the thrust force and torque, respectively, while F d 3 and τ d 3 represent the disturbance force and disturbance torque, respectively. Additionally, m and J 3 × 3 denote the mass and moment of inertia of the quadrotor, respectively.

2.3. IBVS Framework

For clarity of presentation, it is assumed that the CCS coincides with the BCS of the quadrotor, leading to the relation v c = v b . A pinhole camera model is adopted, where the image-space position of quadrotor i is given by s = u v T = f p c y / p c x f p c z / p c x T . Here, f denotes the camera focal length, and p c = p c x p c y p c z T represents the relative position in the camera frame. Based on its position in the ECS, the dynamics of the image feature s ˙ can be expressed via the interaction matrix L s r 2 × 6 [29] and the velocity vector v s r = v c T ω T T as follows:
s ˙ = L s r v s r
The specific form of L s r is given as follows:
L s r = u p c x f p c x 0 v f 2 + u 2 f u v f v p c x 0 f p c x u f 2 + v 2 f u v f
The desired relative position in the ECS corresponds to the desired position s in the image space. The IBVS control law is typically designed as v rd = γ L ^ s r + ( s s ) , where γ > 0 is a gain coefficient, L s r + denotes the Moore–Penrose inverse of L s r , and the depth information p c x required in L s r needs to be estimated. Even under large initial error conditions, this control law can achieve local asymptotic stability of the closed-loop system [30], i.e., s s .
Since the quadrotor is an underactuated system, to decouple the coupling effects of pitch and roll motions on translational motion, the following image model is established based on a virtual camera system:
s ˙ v = u ˙ v v ˙ v = L s v v s v = u v p v x f p v x 0 f 2 + u v 2 f v v p v x 0 f p v x u v v v f v v x v v y v c z ω z
where p v = p v x p v y p v z T denotes the relative position vector in the VCS, and velocity vector v s v = v v T ω z T , where v v represents the velocity in the VCS. Therefore, v vd = γ L ^ s v + ( s s ) can be adopted as the control law based on the selected image model.

2.4. Basic Concepts of Graph Theory

A graph G consists of a vertex set V G and an edge set E G , representing the communication relationships among nodes in this paper, where each node corresponds to a quadrotor. The set of neighboring nodes of vertex i is denoted as N i G j V | i , j E G . The Laplacian matrix of graph G is defined as L G D A N × N , where A = a i j N × N denotes the adjacency matrix of G with elements a i j = 1 if i j and i , j E G , and a i j = 0 otherwise. D = diag d 1 , , d N is the degree matrix with d i j = 1 N a i j . Since the graph considered in this paper is undirected, L G is a symmetric positive semidefinite matrix [30].
Consider a multi- quadrotor system composed of N quadrotors (nodes), whose dynamic model is given by Equation (1). The joint state vector formed by the positions of all nodes is denoted as p q = [ p 1 T p N T ] T , and the distance between any two nodes i and j is given by δ i j = p i p j .
Assumption 1.
The graph G considered in this paper is connected.

2.5. Problem Statement

This paper aims to employ multiple quadrotors, modeled as in Equation (1), to achieve formation-based encirclement tracking control of an unknown maneuvering target.
In the image space, based on the IBVS control law, the image position of the maneuvering target is driven to converge to the center of the camera’s FOV, i.e., s s . Simultaneously, the image positions of quadrotors are predicted and marked within the FOV to prevent misidentifying a quadrotor as the maneuvering target.
In the ECS, through a distributed control scheme, the quadrotors are guided to form a uniformly distributed encircling formation around the target, i.e., δ i j p d , where p d + denotes the desired inter-agent distance. Meanwhile, collisions between quadrotors must be avoided, i.e., δ i j > h c , where h c > 0 represents the safety distance.

3. Control Method Design

The proposed control framework is illustrated in Figure 2.
Figure 2. Schematic diagram of control system framework.

3.1. Target Velocity Estimation via IMM Filter

An Interacting Multiple Model (IMM) filter is a hybrid estimation framework that incorporates m kinematic models, each corresponding to an independent Kalman Filter. The switching among the models is governed by a Markov chain, with model probabilities μ k j updated recursively over time [17].
The IMM filter generally operates in two phases: the filtering phase and the mixing phase. In the filtering phase, each filter performs prediction and update (the Kalman filtering process) on the state x ^ k i based on its corresponding dynamic model and the current measurement z k . In the mixing phase, the estimation results from all models are interactively fused according to their probabilities μ k i | j . For each model j , the mixed initial state estimate x ^ k j and covariance P k j are computed, preparing the initialization for the next filtering step. The specific procedure is given in Equation (4):
x ^ k j = i = 1 m μ k i | j x ^ k i P k j = i = 1 m μ k i | j P k j + x ^ k i x ^ k j x ^ k i x ^ k j T
Based on the likelihoods μ k j of each model, the overall state estimate x ^ k and overall covariance P k are obtained by performing weighted fusion of the estimates from all models, as shown in Equation (5):
x ^ k = j = 1 m μ k j x ^ k j P k = j = 1 m μ k j P k j + x ^ k j x ^ k x ^ k i x ^ k T
For further details regarding the IMM framework, please refer to [31]. In this work, we adopt two motion models: the CV model and the CA model. The stochastic discrete-time state-space representation of the kinematic models is given by Equation (6):
x k + 1 = A x k + n R , k , n R , k ~ N 0 , R
where x is the state vector of the target, A denotes the state transition matrix, n R , k represents zero-mean Gaussian process noise with covariance matrix R . For the measurement of the target position, multiple onboard cameras are employed for cooperative localization. A multi-view geometric linearized triangulation technique [32] is adopted, and the target position is estimated via least-squares fitting. The stochastic discrete-time state-space representation of the measurement model is given by Equation (7):
z k + 1 = H x k + n Q , k , n Q , k ~ N 0 , Q
where z 3 is the measurement vector, H denotes the measurement matrix, and n Q , k represents zero-mean Gaussian measurement noise with covariance matrix Q = σ q I 3 . The CV and CA motion models can be derived from Equation (6), which follows a classical state transition process [17].

3.2. Formation Encirclement Controller Based on IBVS

As stated in the problem description in Section 2.5, a control law must be designed to achieve the control objectives in both the image space and the ECS.
p vr , i = R e , i v p ^ r , i , i 1 N
where p vr , i denotes the relative position in the VCS, the subscript i represents the i -the quadrotor, R e , i v signifies the rotation matrix from the ECS to the VCS, and p ^ r , i = p i p ^ t indicates the relative position in the ECS. The virtual image coordinates u v , i , v v , i can be obtained through Equation (9):
u v , i = f p v r , i ( 1 ) p v r , i ( 2 ) v v , i = f p v r , i ( 1 ) p v r , i ( 3 )
The virtual image error is constructed as shown in Equation (10):
e img , i = u vd u v , i v vd v v , i
where u vd and v vd denote the desired virtual image coordinates. The depth-direction error in the virtual camera coordinate system is constructed as Equation (11):
e dis , i = 2 p v r , i ( 1 ) 2 p d 2 p d
where p d is the desired position error, which is designed here as a time-varying quantity. Let p d 0 and p d 1 denote the initial and final desired position errors, respectively, and let ξ t represent the time decay rate. The expression for p d is given by p d = p d 0 p d 1 exp ξ t t + p d 1 .
The yaw-angle error is constructed as Equation (12):
e ψ , i = ψ d , i ψ i
Combining (9)–(12), the error vector e i is obtained as shown in Equation (13):
e i = e dis , i e img , i T e ψ , i T
Based on (3) and (13), the control law in the image space is designed as follows:
v v , i = λ v , i L ^ v , i + e i
where λ v , i + is the control gain coefficient, v v , i 4 denotes the fourth element of vector v v , i , representing the desired yaw angular rate that can be directly used as the input to the attitude control loop. L ^ v , i + denotes the Moore–Penrose pseudoinverse of L ^ v , i , whose explicit form is given by Equation (15):
L ^ v , i = 2 p d 0 0 2 p v r , i ( 2 ) p d u v , i p ^ v r , i ( 1 ) f p ^ v r , i ( 1 ) 0 f 2 + u v , i 2 f v v , i p ^ v r , i ( 1 ) 0 f p ^ v r , i ( 1 ) u v , i v v , i f 0 0 0 1
From Equation (15), it can be observed that L ^ v , i is non-singular. Inspired by [33], the position error of each node is formulated as Equation (16):
e rel , i = j N i G ( p j p i p d 2 ) p j p i p j p i
where denotes the Euclidean norm of a vector. By combining the expression of p q from Section 2.2 with Equation (13), we further derive Equation (17):
e rel = L I 3 p q 2 2 D p q
where e rel = e rel , 1 e rel , N T is the relative position error vector of all nodes, and denotes the Kronecker product. Combining with Equation (14), the control law is designed as (18):
v c , i = λ v , i L ^ v , i + 1 : 3 , 1 : 3 e i 1 : 3 + λ c , i R e , i v e rel , i
where λ c , i + is the control gain coefficient, L ^ v , i + 1 : 3 , 1 : 3 denotes the submatrix formed by the first three rows and three columns of L ^ v , i + , and e i 1 : 3 represents the vector containing the first three elements of e i . Incorporating the estimated target velocity v ^ t obtained from the IMM filter in Section 3.1 and performing coordinate transformation, the desired control input is given by:
v con , i = R v e v c , i + R e v v ^ t
Lemma 1.
According to LaSalle’s invariance principle, if a system x ˙ = f x is locally Lipschitz and there exists a continuously differentiable positive-definite function  V x | D n  such that V ˙ x 0  for all x D . Let Ω = x D | V ˙ x = 0  and let M  be the largest invariant set in Ω . Then every trajectory x t  starting in D  approaches   M  as t .
Let V r e l = 1 4 i j p j p i p d 2 and H i j = 2 V rel / p i p j . The Hessian matrix H 3 m   ×   3 m is defined as symmetric and positive semidefinite, where its block i , j i , j 1 , N is given by H i j . Let h min > 0 and h max > 0 denote the minimum eigenvalue λ min H and the maximum eigenvalue λ max H of H , respectively. Furthermore, let L = diag L s , 1 L s , m and L 1 = diag L s , 1 1 L s , m 1 , where L s , i represents L ^ v , i + 1 : 3 , 1 : 3 .
Assumption 2.
The norms of the block matrix L  and its pseudo-inverse L 1 , denoted as A = L and B = L 1 , respectively, satisfy A B > 1 . Furthermore, there exists η [ ( q + q 2 + 4 p g ) / 2 p , min α / h max B β h min / A ] , where p = h max ( A B 1 ) , g = α β h max A B h min , q = α A + h max + β h max B ( h min + A ) , α > 0  and β > 0 .
Theorem 1.
Under Assumptions 1 and 2, the control law given by Equation (19) simultaneously achieves convergence of the image error in the image space and convergence of the formation error in the ECS. The proof is as follows:
Proof. 
Combining Equations (14) and (16), let a i = e i 1 : 3 and b i = e rel , i . Substituting these into Equation (18) yields:
a ˙ i = λ v a i λ c L s , i b i
Combining V r e l = 1 4 i j p j p i p d 2 , we have b i = p i V rel . Thus, it follows that:
b ˙ i = p i 2 V rel p ˙ i j i 2 V rel p i p j p ˙ j
Linearizing around the equilibrium point, b ˙ i can be approximated as:
b ˙ i λ v H i i L s , i 1 a i λ c H i i b i λ v j i H i j L s , j 1 a j λ c j i H i j b j
Let a = a 1 a N T , b = b 1 b N T . Based on the definition of the block matrix L , and according to Equations (20)–(22), the following dynamic relationship holds:
a ˙ = λ v a λ c L b
b ˙ = λ v H L 1 a λ c H b
Consider the following Lyapunov function candidate:
V a , b = 1 2 α a 2 + 1 2 β b T H 1 b + η a T b
From V a , b , it can be observed that when V a , b = 0 , it is equivalent to e = 0 and e r e l = 0 , which implies that both the image-space error and the formation position error converge to zero.
According to the positive-definiteness condition:
α I η I η I β H 1 > 0
This requires satisfying:
β > η 2 α h min
Computing the derivative of V a , b yields:
V ˙ a , b = α a T a ˙ + β b T H 1 b ˙ + η a ˙ T b + η a T b ˙
Substituting Equations (26) and (27) and rearranging into quadratic form:
V ˙ a , b = λ v α a 2 λ c β b 2 η λ v a T H L 1 a η λ c b T L T b λ c α a T L T b λ v β b T L - T a η λ v a T b η λ c a T H b
Denoting A = L and B = L 1 , an upper bound of V ˙ a , b can be obtained:
V ˙ a , b λ v α η h max B a 2 λ c β h min η A b 2 + λ c α A + λ v β h max B + η ( λ v + λ c h max ) a b
Let p 11 = λ v α η h max B ,   p 22 = λ c β h min η A ,   p 12 = 1 2 λ c α A + λ v β h max B + η ( λ v + λ c h max ) ,
V ˙ a , b a b T p 11 p 12 p 12 p 22 a b
From Equation (26), it is required that conditions α > η h max B and β h min > η A are satisfied. To ensure condition p 11 p 22 > p 12 2 , the following must hold:
c 1 c 2 λ v λ c > 1 4 a λ v + b λ c 2
where c 1 = α η h max B > 0 , c 2 = β h min η A > 0 , a = β h max B + η , b = α A + η h max . Let r = λ v / λ c , a quadratic inequality with respect to r can be derived:
a 2 r 2 + 2 a b 4 c 1 c 2 r + b 2 < 0
According to the discriminant of the quadratic equation and Assumption 2, the feasible range of r is
4 c 1 c 2 2 a b 4 c 1 c 2 ( c 1 c 2 a b ) 2 a 2 < r < 4 c 1 c 2 2 a b + 4 c 1 c 2 ( c 1 c 2 a b ) 2 a 2
Rearranging the discriminant c 1 c 2 a b into a quadratic equation in terms of η
p η 2 q η g > 0
According to the positive-definiteness conditions α > η h max B and β h min > η A , together with Assumption 2, there exist constants η [ ( q + q 2 + 4 p g ) / 2 p , and min α / h max B β h min / A ] such that inequality (30) holds. Consequently, a feasible solution for r in (29) exists, ensuring that (26) is negative semidefinite. Thus, Theorem 1 is proved. Furthermore, by invoking Lemma 1, the system is uniformly asymptotically stable.

3.3. CBF-Based Collision Avoidance for Quadrotors

As mentioned in Section 2.3, during motion, collision avoidance among quadrotors must be guaranteed, i.e., δ i j > h c must hold, where h c denotes the minimum safe distance. Inspired by [34], we introduce a collision-avoidance constraint based on the CBF h i j , with s i = p i T v i T T , and subsequently derive the admissible input set:
S i j = ( s i , s j ) | h i j ( s i , s j ) 0
where the specific form of h i j is given by Equation (32):
h i j = 4 u m Δ p i j h c + Δ p i j T Δ p i j Δ v i j
where u m denotes the maximum allowable velocity. The corresponding linear CBF constraint can then be derived as:
Δ p i j T Δ u i j T α 1 h i j 3 Δ p i j Δ v i j T Δ p i j 2 Δ p i j 2 + Δ v i j 2 + 2 u m Δ v i j T Δ p i j 4 u m Δ p i j h c
where Δ u i j = v c o n , i v c o n , j . Substituting f i j for the right-hand side expression in inequality (33), it follows that f i j = f j i must be satisfied. Constraint (33) can thus be rewritten as:
Δ p i j T Δ u i j T f i j
which can be further allocated to nodes i and j , respectively, as:
Δ p i j T v con , i f i j 2 , Δ p i j T v con , j f j i 2
Based on the linear constraint in (35), the optimal control law for node i is obtained as:
v con , i = arg   min j N i     1 2 v con , i T v con , i s . t .       C 1 : s ˙ i = A s i + B v oc , i               C 2 : Δ p i j T v con , i f i j 2 , j N i                 C 3 : v con , i u m
Assumption 3.
The quadrotor formation satisfies constraint δ i j > h c at the initial time t = 0   s .

3.4. Image-Coordinate Prediction of Quadrotors in the Field of View

During the tracking of a maneuvering target, the formation motion may cause a member of the formation to appear within the FOV of a node, leading to potential misidentification as the target. Such misidentification can interfere with accurate target tracking control and degrade the precision and stability of state estimation. Therefore, it is necessary to incorporate the prediction and marking of quadrotor positions into the control process to avoid misidentification. Inspired by [35], we project the positions of cooperative quadrotor onto the image plane for labeling and eliminate potential false detections based on overlap analysis. Each node receives the position information of other cooperating nodes via the communication network. The procedure for calculating the image-plane position of the j -th neighboring quadrotor on the onboard camera of the i -th quadrotor is described as follows:
p i j = R e c , i p j p i
where p i j denotes the position of quadrotor j in the CCS of quadrotor i , and R e c , i is the rotation matrix from the ECS to the CCS of quadrotor i Combining with Equation (9), the image-plane coordinates u i j and v i j can be further obtained through the camera model as:
u ^ i j v ^ i j = f p i j ( 2 ) p i j ( 1 ) f p i j ( 3 ) p i j ( 1 ) T
Similarly, the position of the target in the CCS i , denoted as p i t , and its corresponding image-plane coordinates u i t and v i t can be obtained as:
u i t v i t = f p i t ( 2 ) p i t ( 1 ) f p i t ( 3 ) p i t ( 1 ) T
Taking the projected image coordinates u i j , v i j as the center, we define a bounding box with a threshold radius d N . When a moving point appears within the bounding box of radius d N , it is labeled as a misidentified quadrotor. In special cases where the same moving point appears simultaneously in two intersecting bounding boxes, such scenarios are not analyzed or processed here but will be addressed in detail in future work.

4. Simulation Experiments

4.1. Position and Velocity Estimation of the Maneuvering Target

The initial position of the target is p t = 50   m 0   m 20   m T , and its initial velocity is v t = 2   m / s 1   m / s 0.5   m / s T . At time t = 6.67 s, the target acceleration is a t = 3   m / s 2 2   m / s 2 1   m / s 2 T . At time t = 13.33 s, the target acceleration switches to a t = 2   m / s 2 2   m / s 2 2   m / s 2 T .
In Table 1, MPE denotes mean positional error, MVE denotes mean velocity error, MAPE denotes mean absolute positional error, and MAVE denotes mean absolute velocity error. MPE and MVE are computed as the RMSE, while MAPE and MAVE are calculated as the mean absolute error.
Table 1. Root mean square error and mean absolute error of the estimation.
Figure 3a illustrates the estimated trajectory of the target, where the triangle marker denotes the starting point and the circle marker indicates the endpoint. Both the EKF and the IMM filter achieve stable estimation of the target’s changing position. As shown in Figure 3b, the IMM filter outperforms the EKF in terms of both position and velocity estimation errors. Based on the MPE and MVE data in Table 1, it is observed that for target position estimation, the IMM reduces the estimation bias by 14.4% compared to the EKF, while for target velocity estimation, the accuracy improvement reaches 26.5%. The accuracy metric employed here is the root mean square error (RMSE) between the estimated and actual values. The percentage improvement in estimation accuracy is calculated as per Equation (39).
p im = R M S E I M M R M S E E K F R M S E E K F 100 %
where p im denotes the percentage of improvement, and R M S E I M M and R M S E E K F represent the RMSE corresponding to the IMM and EKF estimation methods, respectively.
Figure 3. EKF and IMM estimation of target location.
Table 2 presents the instantaneous absolute estimation errors at the time instants of 1 s, 5 s, 10 s, 15 s, and 20 s. Table 3 summarizes the average absolute estimation errors over the intervals of 0–5 s, 5–10 s, 10–15 s, and 15–20 s.
Table 2. Instantaneous absolute error.
Table 3. Average absolute error per interval.
As shown in Table 2 and Table 3, the estimation performance of the IMM filter is comparable to that of the EKF when the target undergoes uniform linear motion. However, when the target exhibits accelerated motion, the IMM filter demonstrates superior estimation accuracy. These observations are further corroborated by the results presented in Figure 3b.

4.2. Simulation of Encirclement and Tracking Control of Mobile Targets

The target has an initial position p t = 50   m 0   m 20   m T and initial velocity v t = 3   m / s 1.5   m / s 0.6   m / s T . At time t = 10 s, the target acceleration is a t = 0   m / s 2 0.5   m / s 2 0   m / s 2 T . At t = 20 s, the acceleration changes to a t = 0   m / s 2 0.3   m / s 2 0.06   m / s 2 T From t = 30 s onward, the target maintains a constant velocity motion.
Four quadrotors, denoted as Q A , Q B , Q C , and Q D , are employed to perform encircling tracking of the target. Their respective initial positions are p A = 0   m 0   m 1   m T , p B = 0.1   m 1   m 1   m T , p C = 0.1   m 0   m 0   m T , and p D = 0.2   m 1   m 0   m T , all with the same initial velocity 0   m / s . The desired initial position offset p d 0 and final position offset p d 1 are set to 1 m and 0.3 m, respectively. The initial yaw angles of all quadrotors are 0   rad , while the desired yaw angles are ψ d A = π / 4   rad ,   ψ d B = π / 4   rad ,   ψ d C = 3 π / 4   rad ,   ψ d D = 3 π / 4   rad .
Figure 4 illustrates the tracking performance of the target using control methods based on PBVS and IBVS, respectively. Curves of different colors in the figure denote the flight trajectories of different quadrotors, with each color representing a single vehicle. Circular markers in the same color as a curve indicate the final position of the corresponding quadrotor. As shown in Figure 4, both methods are capable of achieving stable tracking of the target. The triangle in the figure represents the starting point of the formation and the target, the circle represents the final position of the formation, and the black square represents the final position of the target. From the enlarged view in Figure 4a, it can be observed that the formation successfully tracks the target. However, due to the high susceptibility of the PBVS method to noisy environments and its strong dependence on model accuracy, the formation fails to achieve a well-rounded encircling formation around the target during the tracking process, which deviates from our control objective. From Figure 4b, it can be observed that compared with the PBVS method, the IBVS-based control approach results in initially divergent trajectories among the quadrotors. This behavior arises because the IBVS-based control law is solved in the image space. Referring to the control law design process in Section 3.2, it can be noted that changes in yaw directly affect the error in the image space. Based on the current yaw angle and image error, a unique solution for the relative position with respect to the target in the ECS can be obtained. Consequently, while achieving the desired image position and yaw angle, an encircling formation around the target is generated. In the terminal tracking phase, the enlarged view in the figure shows the position distribution between the formation and the target, with arrows indicating the yaw direction of the quadrotor. This indicates that during the tracking process, the formation establishes and maintains an encircling configuration around the target.
Figure 4. Encirclement and tracking engineering of a maneuvering target.
Figure 5 shows the variation in tracking error e p for quadrotors Q A , Q B , Q C , and Q D relative to the target T using the PBVS and IBVS methods, respectively. The figure indicates that both methods achieve stable convergence of the tracking error. At t = 10   s and t = 20   s , the tracking error exhibits noticeable fluctuations, which are attributed to changes in the target’s maneuverability at those instants. Within the same tracking period, the tracking error under the IBVS method is significantly smaller than that under PBVS. This is because the IBVS method relies directly on the image-space error, offering better robustness to noise and model uncertainties. In contrast, the PBVS method reconstructs a 3D relative position with respect to the target from 2D image information and then designs the control law based on this positional relationship. Consequently, noise and model uncertainties present in the 2D image space are amplified in the 3D space, directly degrading control accuracy. As seen in Figure 5c,d, during the initial tracking stage, the error along the y-axis e p y is relatively large when using the IBVS method, which aligns with the formation-divergence behavior observed in Figure 4b. This occurs because the designed control law, which is based on the current image error and yaw angle, leads to an encircling motion trajectory around the target before the yaw angle converges to its desired value.
Figure 5. Position tracking error of maneuvering target.
Figure 6 illustrates the variation in relative distances among quadrotors within the formation, both before and after the introduction of CBF-based collision-avoidance constraints. In the figure, the dashed lines labeled i , j , i , j A B C D ,   i j represent the relative distance curves between quadrotors Q i and Q j without CBF, while the solid lines labeled i c j c denote the corresponding curves after CBF is applied. The red dotted line near the bottom indicates the minimum safe distance h c defined in the CBF framework: a collision is considered to occur if the relative distance δ i j < h c between any two quadrotors falls below h c . From the figure, it can be seen that in the final stage of encirclement tracking, the introduction of CBF effectively ensures that the distance between all quadrotors remains above the safety threshold h c . In contrast, the curve B C without CBF shows the occurrence of collisions (as shown in bold between 35 s and 40 s in the figure).
Figure 6. Changes in relative position before and after introducing collision avoidance constraints.
Figure 7 illustrates the FOV schematic of the onboard strapdown camera mounted on Q A . Subfigures (a)–(f) show the FOV status at t = 1   s . 9   s , 19   s , 29   s , 39   s and 49   s , respectively. The dots in the figure denote the quadrotors of the formation visible in the FOV, labeled as Q i , i A B C D . The cross symbol × marks the position of the target within the FOV. The dashed circles represent the identification markers for the formation quadrotors, denoted as M i . As can be observed, during the tracking process, each quadrotor can predict the image positions of other formation members in its own FOV by utilizing its own attitude and the communicated position information of other quadrotors. This allows the target to be distinguished from multiple moving objects when they appear simultaneously in the FOV, thereby preventing estimation errors and control disruptions caused by misidentification. Furthermore, the figure confirms that the proposed image-space-based control method successfully maintains the target near the center of the FOV throughout the tracking process.
Figure 7. Dynamic changes in the position of moving objects within Q A ’s FOV.

5. Conclusions

This paper addresses the formation-based encirclement control of an unknown maneuvering target by proposing an IMM filter for target state estimation and a distributed IBVS formation control method for target encircling and tracking. Based on the RMSE metric, the simulation results show that the proposed estimation method achieves a 26.5% improvement in target state estimation accuracy compared to existing methods. The stability of the proposed control scheme is rigorously analyzed using Lyapunov theory. Compared to existing control methods, the distributed IBVS-based formation control not only achieves stable encircling and tracking of the target but also further reduces tracking errors. The introduced collision-avoidance constraints effectively prevent inter-agent collisions during formation control, thereby enhancing operational safety. Furthermore, the integrated prediction of other formation members within the FOV enables reliable distinction between the target and cooperative agents, mitigating estimation errors and control disruptions caused by misidentification. Meanwhile, the proposed control law successfully drives the image position of the target toward the center of the FOV.

Author Contributions

Conceptualization, J.Y.; Methodology, H.G.; Software, H.G.; Validation, Y.D.; Formal analysis, Y.A.; Investigation, Y.A.; Resources, T.S.; Data curation, X.G.; Writing—original draft, H.G.; Writing—review & editing, T.J.; Visualization, X.G. and Y.D.; Supervision, T.S., J.Y. and T.J. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by the Sichuan-Chongqing Science and Technology Innovation Cooperation Program Project, grant number CSTB2022TIAD-CUX0015.

Data Availability Statement

The datasets presented in this article are not readily available because the data are part of an ongoing study.

Conflicts of Interest

The authors declare no conflict of interest.

Nomenclature

Tthe position of the target A the state transition matrix
R b e 3 × 3 the rotation matrix n R , k zero-mean Gaussian process noise
g G the gravitational constant R the process covariance matrix
u v , v v virtual image coordinates H the measurement matrix
u r , v r real image coordinates n Q , k zero-mean Gaussian measurement noise
p the position of the quadrotor σ q Standard error
v the velocity of the quadrotor Q the measurement noise covariance
v b the velocity of the quadrotor in the BCS p v r , i the relative position in the VCS
ω the angular velocity p ^ r , i the relative position in the ECS
ω × the skew-symmetric matrix generated by ω e dis the depth-direction error
F 3 the thrust force p d 0 the initial desired position errors
τ 3 the torque p d 1 the final desired position errors
F d 3 the disturbance force ξ t the time decay rate
τ d 3 the disturbance torque e ψ the yaw-angle error
m m the mass of the quadrotor ψ d the desired yaw-angle
J 3 × 3 the moment of inertia of the quadrotor ψ the yaw-angle
v c the velocity of the quadrotor in the CCS e img the virtual image error
s the image feature λ v , i + the control gain coefficient
f the camera focal length
p c the relative position in the camera frame L ^ v + the Moore–Penrose pseudoinverse of L ^ v
L s r 2 × 6 the interaction matrix e rel the relative position error vector of all nodes
v s r v s r = v c T ω T T λ c , i + the control gain coefficient
s the desired image feature v ^ t the estimated target velocity
v rd the IBVS control law V r e l a positive-definite function
γ > 0 a gain coefficient H 3 m × 3 m the Hessian matrix
L s r + the Moore–Penrose inverse of L s r λ min H the minimum eigenvalue
p v the relative position vector λ max H the maximum eigenvalue
v s v the velocity vector L L = diag L s , 1 L s , m
L ^ s v the interaction matrix h min > 0 h min = λ min H
L ^ s v + the Moore–Penrose inverse of L ^ s v h max > 0 h max = λ max H
v v the velocity in the VCS η η [ ( q + q 2 + 4 p g ) / 2 p , min α / h max B β h min / A ]
v vd the control law based on virtual camera model A A = L
G A graph B B = L 1
V G a vertex set p p = h max ( A B 1 )
E G an edge set g g = α β h max A B h min
N i G N i G j V | i , j E G q q = α A + h max + β h max B ( h min + A )
L G N × N the Laplacian matrix α α > 0
A = a i j N × N the adjacency matrix β β > 0
D the degree matrix a i a i = e i 1 : 3
Nthe number of quadrotors b i b i = e rel , i
p q the positions of all nodes p i gradient
δ i j the distance between any two nodes i and j a a = a 1 a N T
t time b b = b 1 b N T
p i t the position of the target in the CCS i V a , b the Lyapunov function candidate
u i t image-plane coordinates I identity matrix
v i t image-plane coordinates p 11 p 11 = λ v α η h max B
p t the position of the target p 22 p 22 = λ c β h min η A
v t its initial velocity p 12 p 12 = 1 2 [ λ c α A + λ v β h max B + η ( λ v + λ c h max ) ]
a t the target acceleration c 1 c 1 = α η h max B > 0
e p the variation in tracking error c 2 c 2 = β h min η A > 0
p d + the desired interagent distance a a = β h max B + η
h c > 0 the safety distance b b = α A + η h max
x the state vector r r = λ v / λ c
μ k j model probabilities likelihoods Δ u i j Δ u i j = v c o n , i v c o n , j
x ^ k i A priori state vector u m the maximum allowable velocity
z 3 the measurement vector f i j the right-hand side expression in (33)
μ k i | j The likelihood of model i conditional on model j. d N a threshold radius
x ^ k j the mixed initial state estimate p im the percentage of improvement
P k j estimation error covariance   Q A ,   Q B ,   Q C ,   Q D quadrotors
x ^ k the overall state estimate p A ,   p B ,   p C ,   p D initial positions
P k the overall covariance ψ d A ,   ψ d B ,   ψ d C ,   ψ d D the desired yaw angles

References

  1. Li, Q.; Lu, X.; Wang, Y. A Novel Hierarchical Distributed Robust Formation Control Strategy for Multiple Quadrotor Aircrafts. IEEE Trans. Syst. Man Cybern. Syst. 2025, 55, 6450–6462. [Google Scholar] [CrossRef]
  2. Liu, K.; Yang, W.; Jiao, L.; Yuan, Z.; Wen, C.Y. Fast Fixed-Time Distributed Neural Formation Control-based Disturbance Observer for Multiple Quadrotor UAVs Under Unknown Disturbances. IEEE Trans. Aerosp. Electron. Syst. 2025, 61, 13137–13155. [Google Scholar] [CrossRef]
  3. Huang, Y.; Xu, X.; Meng, Z.; Sun, J. A Smooth Distributed Formation Control Method for Quadrotor UAVs Under Event-Triggering Mechanism and Switching Topologies. IEEE Trans. Vehic. Technol. 2025, 74, 10081–10091. [Google Scholar] [CrossRef]
  4. Liu, H.; Li, B.; Ahn, C.K. Asymptotically stable learning-based formation control for multi-quadrotor UAVs. IEEE Internet Things J. 2025, 12, 24985–24995. [Google Scholar] [CrossRef]
  5. Doakhan, M.; Kabganian, M.; Azimi, A. Aerial Payload Transportation with Energy-Efficient Flexible Formation Control of Quadrotors. Eur. J. Control 2025, 86, 101406. [Google Scholar] [CrossRef]
  6. Upadhyay, J.; Rawat, A.; Deb, D. Multiple drone navigation and formation using selective target tracking-based computer vision. Electronics 2021, 10, 2125. [Google Scholar] [CrossRef]
  7. Seidaliyeva, U.; Ilipbayeva, L.; Taissariyeva, K.; Smailov, N.; Matson, E.T. Advances and Challenges in Drone Detection and Classification Techniques: A State-of-the-Art Review. Sensors 2024, 24, 125. [Google Scholar] [CrossRef] [PubMed]
  8. García, M.; Caballero, R.; González, F.; Viguria, A.; Ollero, A. Autonomous drone with ability to track and capture an aerial target. In Proceedings of the 2020 International Conference on Unmanned Aircraft Systems (ICUAS), Athens, Greece, 1–4 September 2020; IEEE: New York, NY, USA, 2020; pp. 32–40. [Google Scholar]
  9. Yang, L.; Wang, X.; Liu, Z.; Shen, L. Robust Online Predictive Visual Servoing for Autonomous Landing of a Rotor UAV. IEEE Trans. Intell. Veh. 2025, 10, 2818–2835. [Google Scholar] [CrossRef]
  10. Li, W.; Ma, Y.; Zhang, Y.; Li, B.; Shi, Y.; Chu, L. A Multiangle Observation and Imaging Method for UAV Swarm SAR Based on Consensus Constraints. IEEE Sens. J. 2025, 25, 19776–19793. [Google Scholar] [CrossRef]
  11. Yang, K.; Bai, C.; Quan, Q. Multiview Target Estimation for Multicopter Swarm Interception. IEEE Trans. Instrum. Meas. 2025, 74, 5023312. [Google Scholar] [CrossRef]
  12. Tao, Y.; Chen, S.; Huo, X. Image-Based Visual Servo Control of a Quadrotor under Field of View Constraints Using a Pan-Tilt Camera. In Proceedings of the 39th Chinese Control Conference (CCC), Shenyang, China, 27–29 July 2020; IEEE: New York, NY, USA, 2020; pp. 3518–3523. [Google Scholar]
  13. Lin, F.; Peng, K.; Dong, X.; Zhao, S.; Chen, B.M. Vision-based formation for UAVs. In Proceedings of the 11th IEEE International Conference on Control & Automation (ICCA), Taichung, Taiwan, 18–20 June 2014; IEEE: New York, NY, USA, 2014; pp. 1375–1380. [Google Scholar]
  14. Vrba, M.; Stasinchuk, Y.; Báča, T.; Spurný, V.; Petrlík, M.; Heřt, D.; Žaitlík, D.; Saska, M. Autonomous capture of agile flying objects using UAVs: The MBZIRC 2020 challenge. Rob. Auton. Syst. 2022, 149, 103970. [Google Scholar] [CrossRef]
  15. Ma, J.; Chen, P.; Xiong, X.; Zhang, L.; Yu, S.; Zhang, D. Research on vision-based servoing and trajectory prediction strategy for capturing illegal drones. Drones 2024, 8, 127. [Google Scholar] [CrossRef]
  16. Su, Y.X.; Zheng, C.H.; Müller, P.C.; Duan, B.Y. A simple improved velocity estimation for low-speed regions based on position measurements only. IEEE Trans. Control Syst. Technol. 2006, 14, 937–942. [Google Scholar] [CrossRef]
  17. Pliska, M.; Vrba, M.; Báča, T.; Saska, M. Towards safe mid-air drone interception: Strategies for tracking & capture. IEEE Robot. Autom. Lett. 2024, 10, 8810–8817. [Google Scholar] [CrossRef]
  18. Fan, X.; Wang, G.; Han, J.; Wang, Y. Interacting multiple model based on maximum correntropy Kalman filter. IEEE Trans. Circuits Syst. II Exp. Briefs 2021, 68, 3017–3021. [Google Scholar] [CrossRef]
  19. Yunita, M.; Suryana, J.; Izzuddin, A. Error performance analysis of IMM-Kalman filter for maneuvering target tracking application. In Proceedings of the 2020 6th International Conference on Wireless and Telematics (ICWT), Yogyakarta, Indonesia, 3–4 September 2020; IEEE: New York, NY, USA, 2020; pp. 1–6. [Google Scholar]
  20. Leomanni, M.; Ferrante, F.; Dionigi, A.; Costante, G.; Valigi, P.; Fravolini, M.L. Quadrotor Control System Design for Robust Monocular Visual Tracking. IEEE Trans. Control Syst. Technol. 2024, 32, 1995–2008. [Google Scholar] [CrossRef]
  21. Lin, J.; Miao, Z.; Wang, Y.; Wang, H.; Wang, X.; Fierro, R. Vision-Based Safety-Critical Landing Control of Quadrotors with External Uncertainties and Collision Avoidance. IEEE Trans. Control Syst. Technol. 2024, 32, 1310–1322. [Google Scholar] [CrossRef]
  22. Zhao, W.; Liu, H.; Lewis, F.L.; Valavanis, K.P.; Wang, X. Robust Visual Servoing Control for Ground Target Tracking of Quadrotors. IEEE Trans. Control Syst. Technol. 2019, 28, 1980–1987. [Google Scholar] [CrossRef]
  23. Bastourous, M.; Al-Tuwayyij, J.; Guérin, F.; Guinand, F. Image based visual servoing for multi aerial robots formation. In Proceedings of the 28th Mediterranean Conference on Control and Automation (MED), Saint-Raphaël, France, 15–18 September 2020; IEEE: New York, NY, USA, 2020; pp. 115–120. [Google Scholar]
  24. Wang, C.; Sun, Y.; Ma, X.; Chen, Q.; Gao, Q.; Liu, X. Multi-agent dynamic formation interception control based on rigid graph. Complex Intell. Syst. 2024, 10, 5585–5598. [Google Scholar] [CrossRef]
  25. Karras, G.C.; Bechlioulis, C.P.; Fourlas, G.K.; Kyriakopoulos, K.J. Formation control and target interception for multiple multi-rotor aerial vehicles. In Proceedings of the 2020 International Conference on Unmanned Aircraft Systems (ICUAS), Athens, Greece, 1–4 September 2020; IEEE: New York, NY, USA, 2020; pp. 85–92. [Google Scholar]
  26. Rothe, J.; Strohmeier, M.; Montenegro, S. Autonomous Multi-UAV Net Defense System for Aerial Drone Interception. In Proceedings of the 2025 10th International Conference on Control and Robotics Engineering (ICCRE), Nagoya, Japan, 9–11 May 2025; IEEE: New York, NY, USA, 2025; pp. 171–177. [Google Scholar]
  27. Wu, A.; Yang, R.; Li, H.; Lv, M. A specified-time cooperative optimal control approach to unmanned aerial vehicle swarms. In Proceedings of the 2023 9th International Conference on Control, Automation and Robotics (ICCAR), Beijing, China, 21–23 April 2023; IEEE: New York, NY, USA, 2023; pp. 163–169. [Google Scholar]
  28. Montijano, E.; Cristofalo, E.; Zhou, D.; Schwager, M.; Sagues, C. Vision-based distributed formation control without an external positioning system. IEEE Trans. Robot. 2016, 32, 339–351. [Google Scholar] [CrossRef]
  29. Chaumette, F.; Hutchinson, S. Visual servo control. I. Basic approaches. IEEE Robot. Autom. Mag. 2006, 13, 82–90. [Google Scholar] [CrossRef]
  30. Chavez-Aparicio, E.I.; Becerra, H.M.; Hayet, J.B. A Novel Consensus-Based Formation Control Scheme in the Image Space. IEEE Control Syst. Lett. 2024, 8, 2769–2774. [Google Scholar] [CrossRef]
  31. Li, X.R.; Jilkov, V.P. Survey of maneuvering target tracking. Part V. Multiple-model methods. IEEE Trans. Aerosp. Electron. Syst. 2005, 41, 1255–1321. [Google Scholar] [CrossRef]
  32. Lee, J.; Lee, D.; Wang, Z.; Wong, K.C.; So, S. Vision-based position and velocity estimation of an intruder drone by multiple detector drones. In Proceedings of the Asia Pacific International Symposium On Aerospace Technology (APISAT 2024), Adelaide, South Australia, 5–8 November 2024; pp. 1748–1754. [Google Scholar]
  33. Xu, Y.; Qu, Y.; Luo, D.; Duan, H.; Guo, Z. Distributed predefined-time estimator-based affine formation target-enclosing maneuver control for cooperative underactuated quadrotor UAVs with fault-tolerant capabilities. Chin. J. Aeronaut. 2025, 38, 103042. [Google Scholar] [CrossRef]
  34. Wang, L.; Ames, A.D.; Egerstedt, M. Safety barrier certificates for collisions-free multirobot systems. IEEE Trans. Robot. 2017, 33, 661–674. [Google Scholar] [CrossRef]
  35. Zheng, C.; Mi, Y.; Guo, H.; Chen, H.; Zhao, S. Vision-Based Cooperative MAV-Capturing-MAV. arXiv 2025, arXiv:2503.06412. [Google Scholar] [CrossRef]
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.

Article Metrics

Citations

Article Access Statistics

Multiple requests from the same IP address are counted as one view.