Next Article in Journal
Power Consumption Comparison of GPU Linear Solvers for Cellular Potts Model Simulations
Previous Article in Journal
Video Quality Modelling—Comparison of the Classical and Machine Learning Techniques
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

An Efficient Trajectory Planning Method for High-Speed Interception of Invasive Drones

1
College of Aerospace Science and Engineering, National University of Defense Technology, Changsha 410073, China
2
Test Center, National University of Defense Technology, Xi’an 710106, China
*
Author to whom correspondence should be addressed.
Appl. Sci. 2024, 14(16), 7030; https://doi.org/10.3390/app14167030 (registering DOI)
Submission received: 10 July 2024 / Revised: 3 August 2024 / Accepted: 5 August 2024 / Published: 10 August 2024

Abstract

:
This article introduces a rapid interception trajectory generation algorithm tailored for the mitigation of malicious drone activities and other high-speed airborne threats. The proposed method facilitates a high degree of flexibility in defining the terminal state parameters, including position, velocity, and acceleration, as well as the anticipated duration of drone maneuvers, thereby enabling the fulfillment of a variety of mission objectives. The approach employed in this study linearizes the aerodynamic resistance model and computes an efficient closed-form solution for the optimal trajectory motion primitive by applying Pontryagin’s Maximum Principle. Concurrently, it minimizes the cost function associated with the aggression of control inputs. The motion primitive is defined by the combination of the initial and terminal states of the drone, as well as the expected movement time. An efficient input feasibility verification method has been designed for the optimal trajectory. This algorithm can serve as a low-level trajectory generator for advanced task planning methods. After compilation, it can evaluate and compare thousands of motion primitives per second on a personal portable computer, thereby achieving certain advanced goals. The reliability of the algorithm is verified by setting up a multi-objective approach task in a physical simulation environment.

1. Introduction

In recent years, drone technology has made significant progress, and its application areas involve monitoring, rescue, intelligent logistics, environmental monitoring, agricultural building measurement, and other aspects. However, the rapid growth of the drone market has also brought serious safety issues. Improper use or malicious behavior may pose a threat to social security and cause significant economic losses. For example, in 2018, London Gatwick Airport cancelled hundreds of flights due to drone interference [1]. In the UK, 62% of close contact incidents between small drones and aircraft in 2019 were considered high-risk [2]. To address these challenges, it has become particularly important to develop new technologies that can detect, identify, and respond to malicious drones. Therefore, developing a countermeasure system that can effectively identify and combat single or multiple threatening drones has become an urgent task [1].
Multi-rotor drones, represented by quadcopters, are known for their excellent maneuverability. They have become an ideal platform for testing advanced algorithms due to their excellent linear and angular acceleration performance brought by their high thrust to weight ratio. In recent years, quadcopter drones have achieved significant results in 3D autonomous flight [3], unknown environment map construction [4], cluster flight obstacle avoidance [5], and other areas. Some successful application cases, such as Agile Catch [6] and Rapid Aircraft Capture [7], demonstrate the enormous potential of quadcopter drones in the field of anti-drones.
When executing the target arrival task, two main methods are used: (1) Focusing on guidance rate design and feedback control based on observation information. For example, methods such as the proportional guidance method [8], model predictive control [9], optimal control [10], and reinforcement learning [11,12,13] all focus on feedback control based on observation information to achieve guidance objectives. These methods have achieved good results in Markov-like scenarios, but it is difficult to analyze the entire task process in advance, such as energy consumption, task time, and other indicators, which poses difficulties for performance evaluation in complex task scenarios. (2) Emphasis is placed on task trajectory planning, which involves planning task trajectories [14,15,16] in advance and enabling the aircraft to accurately track them to achieve mission objectives. Its main task is to generate executable flight trajectories that conform to the dynamic characteristics of unmanned aerial vehicles in a short period of time. This type of method is usually able to constrain the starting and ending states or flight time based on specific task objectives, which has stronger adaptability for more complex anti-drone swarm task scenarios.
There are usually two representative methods to solve trajectories: (1) Decoupling geometric and temporal information, connecting two endpoints through polynomials or spline curves, and then parameterizing the geometric trajectory in time to generate a state trajectory that respects the dynamic characteristics of the drone. This type of method cannot directly consider the dynamic characteristics of the drone to determine the flight time when planning the path. However, the later use of methods such as PID and model predictive control [17] to track the trajectory further introduces errors, leading to increased uncertainty in the final task result. (2) By leveraging the differential flatness inherent in quadrotor dynamics, both the system state and input are expressed as flat outputs along with their derivatives. Subsequently, constraints on the trajectory are extrapolated from system dynamics constraints via differential equations. Through the application of convex optimization techniques, it becomes feasible to address trajectory optimization challenges such as time optimization [18], energy efficiency [19], and minimum input jerk [6].
High-speed flight in dynamic environments may require drones to quickly adjust and recalculate trajectories based on changes in the environment or external disturbances. Therefore, the computational efficiency of trajectories, the degree of freedom of parameters, and the degree of respect for constraints are usually important indicators for evaluating trajectory generation methods. The time consumption of the above methods in trajectory execution and constraint optimization has hindered their application in real-time flight planning in dynamic scenes. Reference [6] proposes a computationally efficient motion primitive that uses a fast recursive method to test for constraint violations instead of explicitly encoding constraints during the planning phase. This provides high flexibility in defining quadcopter terminal states and achieves advanced goals through low-cost searches on multiple primitives. The computational efficiency of this method makes it a low-level trajectory generator for other advanced tasks [3,20], and has achieved good results. It is worth noting that such methods describe quadcopters as a rigid body with six degrees of freedom, using rigid body motion equations to describe drone motion while ignoring external disturbances such as air resistance. Under the condition of low-speed flight in unmanned aerial vehicles, this method can compensate for modeling errors by sacrificing the accuracy of single planning and continuously re-planning.
However, in certain contexts where drones approach their maximum flight speed, such as pursuit and evasion [21,22] and racing [23,24], research indicates that the aerodynamic drag encountered by the aircraft escalates with the square of the flight speed. This nonlinear progression results in a swift increase in aerodynamic drag, eventually stabilizing at an equilibrium with the aircraft’s thrust. This becomes a significant factor limiting the flight state and trajectory. Consequently, this limitation means that the efficacy of existing methods cannot be reliably ensured in medium to high-speed flight scenarios.
Recent studies have demonstrated notable advancements in high-speed flight scenarios using intelligent methods, particularly reinforcement learning. These methods have achieved high-speed flight under complex external disturbances through extensive trial and error learning in virtual simulation environments. They can indeed approach the limit performance of aircraft after prolonged training in specific fixed scenarios [24]. However, these methods exhibit significant limitations during application. Firstly, their training process is time-consuming, significantly reducing their practical applicability, especially in real-time tasks within high dynamic environments. Secondly, as these methods depend on specific simulation environments and scenarios, their generalization ability and adaptability need improvement when confronted with diverse actual flight environments. In conclusion, existing research still faces substantial limitations in real-time high-speed flight tasks within high dynamic environments. Therefore, it is imperative to further explore more efficient and adaptable solutions.
Taking inspiration from reference [6], this article attempts to design a computationally efficient and applicable high-speed flight trajectory planning method for multi-rotor aircraft based on a rigid body motion model that includes aerodynamics, and is applicable to any performance characteristic (mass, aerodynamics). The method mainly includes two parts: air resistance approximation and motion primitive generation and evaluation. The first part is based on the dynamics of a rigid body with six degrees of freedom, with the goal of minimizing the drag model error of quadcopters in the speed operating range. A linearized approximation method for air resistance is designed, and an approximate air resistance model is obtained for the purpose of solving the optimal trajectory in a closed form. The second part, based on the designed linearized resistance model and optimal control theory, aims to minimize the input jerk of unmanned aerial vehicles. By utilizing the differential flatness characteristics of multi-rotor aircraft, the position, velocity, and acceleration state trajectories, as well as corresponding thrust and body rate input trajectories, are planned, and a fast determination method for trajectory feasibility is provided.
This paper confronts the security challenges posed by malicious drones, offering a series of novel research findings designed to bolster countermeasures against these threats in high-speed dynamic environments. The primary contributions and innovations of this study are as follows:
(1) This paper introduces an innovative linearization approximation method for the air resistance model. Existing research often neglects or oversimplifies the impact of air resistance on high-speed flight, leading to inaccuracies in trajectory planning. Our proposed method accurately restores the drone’s flight conditions, thereby significantly enhancing the accuracy of trajectory planning. This not only addresses the limitations of previous studies but also provides crucial assurances for the safety and reliability of drones in high-speed flight scenarios.
(2) This paper presents a set of motion primitives tailored for drones with varying performance parameters. These primitives are based on the linearized approximation of the air resistance model, enabling efficient solutions for high-speed flight trajectories. This innovation not only enhances the computational efficiency of trajectory planning but also improves the adaptability and universality of the method across different drone models. This development opens up possibilities for real-time flight planning in complex task scenarios.
(3) A physical simulation environment was utilized to demonstrate the rapid arrival task of multiple moving targets. This paper substantiates the efficacy of the proposed method through tangible demonstrations, thereby illustrating its superior performance in dynamic scenarios. This accomplishment not only validates the practicality and advancement of the method but also underscores the significant importance of this research in augmenting the efficiency of drone countermeasure systems.
The remaining parts of this article are organized as follows: Section 2 provides a basic description of the quadrotor maneuvering mechanics model and problems, and Section 3 provides the linearization approximation principle of the air resistance model and the method of generating motion primitives. Section 4 analyzes the impact of the two drag coefficients designed in this article on the optimal trajectory. Section 5 provides a fast method for determining the feasibility of trajectories. In Section 6, the performance of the proposed method was compared with the method in reference [6], and the error variation of the linearization approximation method in this paper within the performance limit range of unmanned aerial vehicles was analyzed. A high-speed flight mission demonstration was presented in the Gazebo [25] physical simulation environment. Section 7 presents the conclusion.

2. System Dynamics and Problem Statement

This section first introduces the quadcopter dynamics model used in this article, including gravity, thrust, and external interference forces during flight. An analysis was conducted on the control input constraints of quadcopters, and then a statement was made on the problems to be solved in this article.

2.1. Quadrotor Dynamics Model

The quadcopter is modeled as a six degree of freedom rigid body and represented as two three-dimensional column vectors: a translational p = ( p 1 , p 2 , p 3 ) along the orthogonal inertial axis, and three degrees of freedom θ = ( θ 1 , θ 2 , θ 3 ) , describing the rotation of the frame connected to the fuselage relative to the inertial frame.
As shown in Figure 1, the control input of the system is treated as a scalar f t representing the total thrust generated by the quadcopter, and a column vector ω = ( ω 1 , ω 2 , ω 3 ) representing the body velocity in the aircraft coordinate system. Due to the relatively low moment of inertia and high torque generation ability of quadcopters, this article ignores angular dynamics and assumes that angular rate commands are perfectly tracked. As a result, the state of the quadcopter is designed as a 9-dimensional column vector consisting of position, velocity, and attitude angle.
This article takes the differential equation [26] of a rigid body as the basis for controlling the flight of a quadcopter, and models external disturbances using the method of reference [27]:
p ˙ = v
v ˙ = a t + a e
a t = g + R e 3 f t
a e = f ^ r b + R e 3 f r p
R ˙ = R ω ×
where p represents position, v represents velocity, at represents the acceleration component generated by the drone’s thrust, and ae represents the acceleration component generated by external interference forces; g is the gravitational acceleration represented in the inertial coordinate system, R is the orthogonal matrix used to describe rotation, e 3 = ( 0 , 0 , 1 ) is a constant vector in the fixed object coordinate system, f ^ r b is the resistance experienced by the aircraft structure during quadcopter flight [28], f r p is the resistance generated by the rotation of the propeller [29], and ω × is the oblique symmetric matrix form of the vector cross product:
ω × = [ 0 ω 3 ω 2 ω 3 0 ω 1 ω 2 ω 1 0 ]
It is important to note that this model represents an approximation of quadrotor flight and does not accurately reflect the true physical properties of quadrotors. In reality, the propeller’s thrust is influenced by a variety of factors including rotational speed, wind speed, and inflow angle. The differentiation between thrust (3) and drag (4) produced by propeller rotation is challenging to effectively implement in practice. As demonstrated in Section 6, treating thrust, propeller drag, and body drag as independent variables results in minor errors; however, these are significantly less than those introduced by the previous method [6].

2.2. Feasible Inputs for Quadcopters

The actual thrust ft that quadcopters can generate is limited to a certain range:
0 f min f t f max
Among them, fmin is non-negative and is usually limited by the lowest speed of the rotor motor during operation. The size of the angular velocity command is constrained within a three-dimensional sphere:
ω ω max
Among them, is the Euclidean norm, which can ensure invariance under rotation and is easy to calculate. This limitation is usually due to the saturation rate of flight control gyroscope components, or the working conditions of some loads installed on quadcopters.

2.3. Problem Statement

The aim of this research is to enable the precise interception of multiple intruders by pre-calculating maneuvers for a UAV. The following section provides a detailed specification of the problem under investigation.
Define σ ( t ) as the translation variable of a quadcopter, including its position, velocity, and acceleration thrust components:
σ ( t ) = ( p ( t ) , v ( t ) , a t ( t ) ) 9 .
Let T be the target duration of the motion, and σ ^ be the component of the state translation variable required at the end of the motion. The users can set it flexibly according to different task requirements:
σ ( T ) = σ ^ .
In this paper, the interception task is used as an example. As illustrated in Figure 2, the UAV is required to track the velocity of the target when it reaches the target position. It is assumed that both sensors and interceptors are installed on the centroid of the UAV and follow the body coordinate system of the UAV.
This research seeks to address the following challenges: Given a quadrotor drone that initiates from an initial state set, comprising position, velocity, and attitude at t0, within the time interval [t0, T] it is necessary to determine suitable inputs ft(t), ω(t) such that the drone’s terminal state at the termination time T aligns with equation (10). Concurrently, throughout the entire flight trajectory, the drone’s movement must adhere to the quadrotor dynamics Equations (1), (2) and (5), in addition to input constraints (7) and (8).

3. Air Resistance Approximation and Motion Primitive Generation

This section will linearize and approximate the air resistance, with the aim of minimizing the error between the quadcopter dynamics model and actual conditions under high-speed flight, while utilizing the Pontryagin principle to solve the motion primitives of the optimal trajectory in a closed form.

3.1. Linearization Approximation of Air Resistance Model

This article considers the external disturbances experienced by quadcopters from two perspectives (4), including airframe resistance f ^ r b and rotor resistance f r p :
f ^ r b = k ^ r b v 2
f r p = k r p a t ω p 2
Among them, k ^ r b and krp are the drag coefficients, v is the quadcopter velocity, and ω p 2 is the propeller speed.
Using a linearized model to approximate resistance (11):
f r b = k r b v
where k ^ r b is the approximate resistance coefficient.
Take a single axis for analysis and express the similarity between the standard model (11) and the approximate model (13) in the maximum operating speed range v max of the quadcopter in the form of definite integrals:
L ( k r b ) = 0 v max ( k ^ r b v 2 k r b v ) 2 d v
Find the extreme point of function (14) relative to the approximate resistance coefficient k ^ r b , and the approximate result is shown in Figure 3.
d L d k r b = v max 3 ( 3 k ^ r b v max + 4 k r b ) 6 = 0
k r b = 3 k ^ r b v max 4
Therefore, Equation (4) is rewritten as:
a e = f r b + R e 3 f r p

3.2. Motion Primitive Generation

Given the end time T and the target translational variable σ ^ , use the dynamic model in Section 2.1 to generate motion primitives and guide the quadcopter from an initial state to a state that achieves the target translational variable. The motion primitive is constructed based on the jerk of the quadcopter dynamics model, and the cost value of each axis is minimized by decoupling the three axes and independently solving each one. The control input constraints of quadcopters are temporarily ignored at this stage and analyzed in Section 5.

3.2.1. Dynamic Modeling

We plan the motion of a quadcopter based on the jerk of each axis, as specified in reference [30]. By ignoring input constraints, the axes can be decoupled, and motion trajectories can be generated for each axis separately. This section will describe how to calculate thrust and body velocity inputs from this trajectory. The following chapters will recombine the decoupled axes to consider the feasibility of the trajectory.
Calculate the input thrust ft by applying the Euclidean norm to (3), with the jerk denoted as j = a ˙ t :
f t = a t g
Take the first derivative of (3) and (18) to obtain:
j = R ω × e 3 f t + R e 3 f ˙ t
f ˙ t = e 3 T R 1 j
After substituting and evaluating the product ω   ×   e 3 , according to reference [6], the jerk j and thrust f t fixed the two components of body velocity:
[ ω 2 ω 1 0 ] = 1 f t [ 1 0 0 0 1 0 0 0 0 ] R 1 j
As ω 3 does not affect linear motion, in order to simplify the writing expression, it will be considered as ω 3 = 0 in the rest of this article.

3.2.2. Cost Function

The goal of the motion primitive in this article is to calculate a quadratic differentiable trajectory that guides a quadcopter from its initial state to a fully or partially defined terminal state in time T, while minimizing the cost function:
J Σ = 1 T 0 T j ( t ) 2 d t
Rewriting (21), this cost function can be interpreted as the upper bound of the average value of the product of the inputs of the quadcopter system:
f t 2 ω 2 =   f [ ω 2 ω 1 0 ]   2 =   [ 1 0 0 0 1 0 0 0 0 ] R 1 j 2 j 2
Thereby
1 T 0 T f t 2 ( t ) ω ( t ) 2 d t J Σ .
This cost function has high computational efficiency and can be used to rank the input aggressiveness of multiple candidate feasible motion primitives, thereby filtering out trajectories that can achieve terminal translation constraint σ ( T ) with more reasonable thrust and body rate inputs.

3.2.3. Single Axis Trajectory Generation

By decoupling dynamics into three orthogonal inertial axes and using jerk as a control input, the problem of nonlinear trajectory generation is simplified. Subsequently, using Equations (18) and (21), the actual control inputs ft and ω were inverted from the jerk input. The final state is determined by the target final state component σ ^ corresponding to each axis, and the trajectory duration T is specified.
Decoupling the cost number J Σ of three-dimensional motion into the cost per axis Jk through the integrand function in expansion (22):
J Σ = k = 1 3 J k , where   J k = 1 T 0 T j k ( t ) 2 d t
Due to the consistency of the three axes in form, for the convenience of writing, the following text will analyze the single axis and ignore the subscript k.
Introduce state s = ( p , v , a t ) , consisting of scalar position, velocity, and acceleration thrust components. Take the jerk j as input:
s ˙ = f s ( s , j ) = ( v , a t k r b v k r p a t , j )
By introducing the covariate variable λ = ( λ 1 , λ 2 , λ 3 ) and defining the Hamiltonian function H ( s , j , λ ) , the optimal state trajectory can be directly solved using the Pontryagin minimum principle [31].
H ( s , j , λ ) = 1 T j 2 + λ T f s ( s , j )   = 1 T j 2 + λ 1 v + λ 2 ( a t k r b v k r p a t ) + λ 3 j
λ ˙ = s H ( s , j , λ ) = ( 0 ,   k r b λ 2 ( t ) λ 1 ( t ) ,   λ 2 ( t ) ( k r p 1 ) )
Among them, j * and s * represent the optimal input and optimal state trajectories for a single axis, respectively.
Solve the general solution of the co-state differential Equation (28), where C represents the undetermined constant:
λ ( t ) = 1 T [ C 3 C 3 k ^ r b C 2 e k ^ r b t k ^ r b ( C 3 + C 3 k ^ r b t C 2 e k ^ r b t ) ( k r p 1 ) k ^ r b 2 + C 1 ( k r p 1 ) k ^ r b ]
By applying the optimal conditions to the Hamiltonian function H(s, j, λ), we can obtain:
j ( t ) = arg min j ( t ) H ( s ( t ) , j ( t ) , λ ( t ) )   = ( 1 k r p ) ( ( C 3 C 2 e k ^ r b t ) k ^ r b 2 + ( C 3 t + C 1 ) k ^ r b )
The optimal state trajectory can be obtained from Equation (26) and the initial condition s ( 0 ) = ( p 0 , v 0 , a 0 ) :
s * ( t ) = ( k r p 1 ) [ e k r b t σ 1 σ 2 ( 1 k r b t ) k r b 2 σ 3 k r b e k r b t σ 1 σ 2 k r b a 0 ( k r p 1 ) + C 2 ( e k r b t 1 ) k r b 3 t ( C 3 t + 2 C 1 ) 2 k r b C 3 t k r b 2 ] where σ 1 = 2 v 0 k r b 4 + ( 2 a 0 k r b 3 ) ( k r p 1 ) ( C 2 2 C 1 k r b ) ( k r p 1 ) 2 2 k r b 3 ( k r p 1 ) + e k r b t ( C 2 e k r b t 2 C 3 k r b t 2 C 1 k r b ) ( k r p 1 ) 2 k r b 3 σ 2 = a 0 k r b 3 C 2 ( k r p 1 ) k r b 3 ( 2 C 2 e k r b t + ( C 3 k r b t ) ( 2 + k r b t ) + 2 C 1 k r b 2 t ) ( k r p 1 ) 2 k r b 3 σ 3 = ( 6 C 2 e k r b t ( 1 k r b t ) + ( C 3 k r b 2 t 2 ) ( 3 + 2 k r b t ) + 3 C 1 k r b 3 t 2 ) ( k r p 1 ) 6 k r b 4 p 0 k r b 5 + v 0 k r b 4 + C 2 ( k r p 1 ) 2 k r b 4 ( k r p 1 )
Solve the remaining unknown constant C as a function of the expected end shift variable component σ ^ as shown in (10).
For the case of fully defining the end effector translation state, make the expected end effector state equal to the position, velocity, and acceleration s ( T ) = ( p f , v f , a f ) defined by the variable σ ^ . Then, by rearranging Equation (31), the unknown constant C is separated:
( k r p 1 ) 2 ϕ [ C 1 C 2 C 3 ] = [ Δ p Δ v Δ a ]
where
ϕ = [ e k r b t + k r b t k r b 2 t 2 2 1 k r b 4 sinh ( k r b t ) k r b t k r b 5 t 3 6 k r b 2 e k r b t + k r b t 1 k r b 3 2 sinh ( k r b t 2 ) 2 k r b 4 t 2 2 k r b 2 t k r b ( k r p 1 ) e k r b t 1 k r b 3 ( k r p 1 ) t ( k r b t + 2 ) 2 k r b 2 ( k r p 1 ) ] [ Δ p Δ v Δ a ] = [ p f v f a f ] [ p 0 k r b 5 + v 0 k r b 4 k r b 5 σ 1 k r b 5 a 0 ( k r b t 1 ) ( k r p 1 ) k r b 2 σ 1 k r b 4 a 0 ( k r p 1 ) k r b a 0 ] σ 1 = e k r b t ( k r b 4 v 0 a 0 k r b 3 + a 0 k r b 3 k r p )
Solving for unknown coefficient C
[ C 1 C 2 C 3 ] = ϕ 1 ( k r p 1 ) 2 [ Δ p Δ v Δ a ]
At this point, generating motion primitives only requires multiplying the above matrices for each axis, and then finding the optimal state trajectory corresponding to the primitive by solving (31).
For partially defined terminal translation states, it is possible to make the co-states of undefined states equal to zero at the end time when solving for the optimal input trajectory [31], thereby allowing the corresponding σ ^ to be free. These additional situations are usually not of practical significance in the research scenario of this article, and therefore will not be further discussed here.
The single axis cost of formula (25) can be explicitly calculated as follows. The lowest cost sports primitive can be considered the most reasonable in the sense of formula (23).
J = ( k r p 1 ) 2 6 × ( 3 C 2 2 e 2 k r b t k r b 5 t 6 ( 2 C 2 e k r b t ( C 3 t + C 1 ) C 3 2 t ) k r b 4 t + 6 C 3 ( C 3 t + 2 C 1 ) k r b 3 + 2 ( ( C 3 t + C 1 ) 2 + C 1 ( C 3 t + 2 C 1 ) ) k r b 2 )
This cost applies to all combinations of fully or partially defined terminal translation variables.

4. Resistance Parameter Analysis

This section will focus on a horizontal axis that is not affected by gravity, with σ ( 3 ) = ( 15 , 0 , 0 ) as the terminal translation constraint, and discuss the effects of the two resistance parameters in the acceleration models (12) and (13) of this paper on the optimal trajectory of unmanned aerial vehicles.

4.1. Analysis of Rotor Resistance Parameters krp

The rotor resistance parameter k r p mainly represents the negative impact of factors related to quadcopter actuators (such as friction caused by rotor and blade rotation) on the acceleration performance of unmanned aerial vehicles. Figure 4 shows the optimal state trajectory s * ( t ) corresponding to different rotor resistance parameters when the air resistance is approximately zero k r b = 0.01 . The resistance component f r p of the propeller is inversely proportional to the thrust component f t by a factor of k r p , and f t changes with f r p to offset its impact. Ultimately, only the stretching effect of f t on the longitudinal axis is produced, without changing the moment when its extreme and zero points appear.

4.2. Analysis of Body Resistance Parameters krb

The body resistance parameter k r b mainly represents the negative impact of factors related to the speed of quadcopter motion (such as friction caused by relative air motion) on the acceleration performance of unmanned aerial vehicles. Figure 5 shows the optimal state trajectory s * ( t ) corresponding to different body resistance parameters when the rotor resistance is approximately zero k r p = 0.01 . The resistance component f r b of the aircraft body is inversely proportional to the velocity trajectory by k r b times, while the thrust component f t changes with f r b to counteract its effects, ultimately resulting in complex effects on f t , changing the timing of its extreme and zero points.
By comprehensively analyzing the impact of two types of resistance on thrust, the optimal thrust trajectory presents a way to counteract the influence of resistance, allowing the optimal state trajectory to operate in a manner close to the optimal state trajectory without resistance.

5. Trajectory Feasibility Assessment

In order to provide an efficient trajectory generation method, thrust and body velocity limitations were temporarily ignored in Section 3 of this article. For practical applications, it is necessary to limit the control input trajectory based on the performance parameters of the drone. As mentioned in Section 4, compared to the ideal model, the presence of two types of resistance has a complex and comprehensive impact on the optimal input trajectory. This section will provide a low-cost and fast judgment method for the feasibility of this trajectory based on the control input constraints brought by the real quadcopter physical system.
Given a certain time interval T = [ t 1 , t 2 ] [ 0 , T ] and the optimal state trajectory s * ( t ) in the form of (31) and its corresponding jerk input j ( t ) , the goal is to determine whether the system inputs ft and ω appearing in the quadcopter dynamics models (2) and (5) in Section 2.1 meet the feasibility requirements of (7) and (8) in Section 2.2.

5.1. Thrust

The interval T is feasible relative to the thrust limit (7) if and only if:
max t T f ( t ) 2 f max 2 and
min t T f ( t ) 2 f min 2 .
Square (18) obtained
f t 2 = a t g 2 = k = 1 3 ( a k g k ) 2
where ak represents the acceleration component of at on axis k, and gk is the gravity component on axis k. Combining (36)–(38), the thrust constraint can be explained as a spherical constraint on acceleration. Order:
f k ( t ) = a k ( t ) g k
By taking the extreme values of each axis of (38), the following boundaries are obtained:
max t T f k 2 ( t )   for   k { 1 , 2 , 3 }
max t T f t 2 ( t ) k = 1 3 max t T f k 2 ( t )
min t T f t 2 ( t ) k = 1 3 min t T f k 2 .
If the left-hand side of (40) is greater than fmax, then the interval is absolutely infeasible, while if the right-hand side of (41) is less than fmax and the right-hand side of (42) is greater than fmin, then the interval is absolutely feasible relative to the thrust constraint.
By solving the root of the differential jk of ak and comparing it with the endpoint values at the left and right boundaries of T , the maximum and minimum values of the thrust fk in formula (39) can be found in a closed form (represented as f ¯ k and f _ k , respectively):
j k ( t * ) = ( k r p 1 ) ( ( C 3 C 2 e k ^ r b t * ) k ^ r b 2 + ( C 3 t * + C 1 ) k ^ r b ) = 0
t * = { Δ 1 W 0 ( Δ 2 ) k ^ r b Δ 2 [ 1 e , + ) Δ 1 W 1 ( Δ 2 ) k ^ r b Δ 2 ( 1 e , 0 ) where Δ 1 = C 3 + C 1 k ^ r b C 3 Δ 2 = C 2 e Δ 1 C 3
where j k = a ˙ k , W 0 and W 1 are two branches of the Lambert W function.
The extreme values of f k 2 are as follows:
max t T f k 2 ( t ) = max { f ¯ k 2 , f _ k 2 }
min t T f k 2 ( t ) = { min { f ¯ k 2 , f _ k 2 } , if   f ¯ k f _ k 0 0 , otherwise
where f ¯ k f _ k < 0 means that the symbol of f k ( t ) in T changes and there is a zero crossing point.
Therefore, the sufficient condition for the infeasibility of the input thrust in formula (40) is:
max { f ¯ k 2 , f _ k 2 } > f max .
Similarly, according to (41) and (42), the sufficient conditions for input thrust to be feasible are:
k = 1 3 max { f ¯ k 2 , f _ k 2 } f max and
k = 1 3 min { f ¯ k 2 , f _ k 2 } f min
If conditions (47), (48), and (49) are not applicable, the thrust feasibility of this trajectory segment is uncertain.

5.2. Body Rate

According to reference [6], the magnitude of body speed can be used as a function of jerk and thrust, as shown below:
ω 1 2 + ω 2 2 1 f t 2 j 2 .
The upper bound on the right-hand side of formula (50) can be determined by the ω ¯ 2 defined below, thereby providing an upper bound on the left-hand side, whose denominator is calculated using (39) and (46).
ω 1 2 + ω 2 2 1 f t 2 j 2 ω ¯ 2 = k = 1 3 max t T j k ( t ) 2 k = 1 3 min t T ( a k ( t ) g k ) 2 .
Assuming ω 3 = 0 , according to the above equation, when ω ¯ 2 ω m a x 2 occurs, the body rate input for the time period is marked as feasible; Otherwise, it is marked as uncertain.

5.3. Recursive Testing

The design focus of this test is on computing speed, and literature [6] provides sufficient but not necessary conditions for the feasibility and infeasibility of trajectories.
Test the feasibility of a given time interval T [ 0 , T ] by applying the aforementioned thrust and body velocity tests to T . If both tests return feasible, T is marked as input feasible and the algorithm terminates; If one of the tests returns infeasible, the algorithm terminates and T is marked as input infeasible. Otherwise, T will be split into two:
t 1 2 = t 1 + t 2 2
T 1 = [ t 1 , t 1 2 ] , T 2 = [ t 1 2 , t 2 ] .
As shown in Figure 6, if the time interval t 1 2 t 1 is less than the predefined minimum Δ t , the algorithm marks the primitive as undetermined and terminates. Otherwise, the algorithm is first recursively applied to T 1 : if the result is feasible, the algorithm is recursively applied to T 2 . If T 2 is also a feasible interval, the entire primitive can be marked as feasible; Otherwise, the primitive is marked as infeasible or uncertain. Therefore, the test will return one of three results.
As the length of interval T decreases, the upper bound of interval (45) and the lower bound of interval (46) will gradually converge, and thus (41) and (42) will also tend to converge, making thrust feasibility testing more accurate.

6. Performance Verification and Error Analysis

This section aims to conduct a comprehensive comparative analysis of the planning effects of the method proposed in this paper and the one described in reference [6], under both single-objective and multi-objective scenarios. This will be achieved through rigorous experimental verification within the Gazebo [31] physical simulation environment. The study will primarily focus on assessing the performance advantages of the algorithm presented in this paper in high-speed flight scenarios, as well as its efficacy in managing complex multi-moving target environments. To provide a holistic evaluation of these two methods, we will systematically test them in both low-speed and high-speed flight scenarios, conducting an in-depth analysis of their respective planning results and performance differences during simulation experiments. To ensure the comparability of experimental conditions throughout the comparison process, both methods will utilize the same drone model for simulation, with key parameters detailed in Table 1:

6.1. Low-Speed Trajectory Comparison

The comparison results of the two methods under low-speed conditions are shown in Figure 7 and Figure 8, respectively.
The method in [6] does not consider air resistance, so its simulation actual thrust output is slightly higher than the planned value. This additional thrust is mainly used to compensate for the rotor self-resistance and the body air resistance.
However, the actual output thrust of our method under low-speed conditions is slightly lower than the planned value, which is consistent with the linear approximation analysis in Section 3.1.
Although there are differences between them, both methods are within the actual capability range of drones in terms of actual thrust demand. Under the effective regulation of the feedback controller, both methods can achieve relatively accurate tracking of the planned trajectory. This shows that both methods have certain effectiveness in low-speed flight scenarios, although they adopt different strategies to deal with dynamic models and external resistance effects.

6.2. Comparison of High-Speed Trajectories

In scenarios involving high-speed flight, Figure 9 and Figure 10 offer a comprehensive comparison between the method proposed in this paper and that of reference [6] through simulation. The discrepancy between the planned and actual output thrust in reference [6] is substantial due to the quadratic increase in air resistance under high-speed conditions. This discrepancy escalates, surpassing the drone’s maximum thrust limit, which results in a significant rise in the tracking error of the state trajectory during actual flight. Consequently, there is a considerable deviation between the final position and velocity states and the terminal state constraints. Despite these issues, the trajectory is still deemed feasible under the planning results of reference [6].
Contrarily, the linearization method proposed in this study more accurately restores actual drag under high-speed conditions. This is evidenced by the significant correlation between the maximum thrust of the planning results and the actual maximum thrust. Consequently, when using the planning results derived from this method, a trajectory is deemed unfeasible, aligning more closely with real-world scenarios. This notable advantage demonstrates that our method offers superior accuracy and reliability in handling high-speed flight situations, particularly when considering intricate dynamic models and external drag effects.
The lateral tracking error identified in the experimental results predominantly arises from control delays, attributed to the drone’s physical property constraints and the inherent response time of its flight control system. This particular error exhibits a consistent trend in the simulation outcomes of both methodologies, which is not the primary focus of this study. The central emphasis of this paper lies in contrasting the trajectory planning techniques between the two methods and highlighting the performance superiority of the proposed method in high-speed flight conditions.
In conclusion, the algorithm presented in this paper offers more effective trajectory planning outcomes within a comparable timeframe to the method referenced in [6]. This is particularly important for managing high-dynamic anti-drone swarm task scenarios, as the quality of trajectory planning significantly influences both task efficiency and safety.

6.3. Multi Target Trajectory Comparison

This section designs a scenario for unmanned aerial vehicles to approach multiple targets, mainly to verify the applicability of the algorithm proposed in this paper in anti-drone swarm task scenarios. There are multiple target drones distributed in an area of 150 m × 150 m × 50 m, assuming that the positions of all targets are known and can be accurately tracked and predicted. Our drones start from the origin and approach all target drones in sequence. It is required that the relative velocities of both sides be zero when reaching the target position, in order to facilitate the payload operation of our drones.
Thanks to the high computational efficiency of the closed form solution of the optimal trajectory, which can evaluate a large number of trajectories in a short time, this paper uses numerical methods to solve the shortest completion time of a single target trajectory that meets the control input constraints, and combines genetic algorithms to optimize the task sequence of multiple objectives.
Figure 11 shows the trajectory planning results and physical simulation effects of the comparison method. The maximum planning speed of this method exceeded 30 m/s, which is far beyond the performance limit of drones considering the air resistance in the actual physical environment. This phenomenon of exceeding the capability range is also reflected in the large error between the simulated state trajectory and the expected state trajectory, which is unacceptable.
Figure 12 elucidates the fluctuations in relative distance and speed between the drone, controlled by the contrastive method planning results, and multiple targets during actual flight. The findings suggest that there is a notable discrepancy between the simulated flight outcomes and the preset expected values, whether considering relative distance or speed. This significant deviation undoubtedly fails to satisfy the stringent demands of the drone’s payload for its operational environment.
Figure 13 provides a three-dimensional visualization of the flight trajectory comparison between the drone and its target. It is evident that there exists a notable discrepancy between the actual flight path of the drone and the anticipated trajectory, which compromises precise control and task execution.
Figure 14 illustrates the trajectory planning outcomes and the physical simulation effects of the method proposed in this study. It is important to note that the maximum speed governed by this method does not surpass 20 m/s, thereby ensuring that the planned speed remains within the drone’s performance capabilities. Furthermore, both the position and velocity trajectory tracking results are highly satisfactory.
Figure 15 offers a comprehensive record of the fluctuations in relative distance and speed between the drone, controlled by the planning outcomes of this paper’s method, and multiple targets during actual flight. The data reveals that at the terminal moment, both the relative distance and speed approximate zero. This suggests that the proposed method is capable of adequately fulfilling the operational requirements of the drone’s payload.
Figure 16 provides a visual representation of the high degree of congruence between the actual flight trajectory of the drone and the anticipated trajectory, nearly achieving a state of superimposition.
It is noteworthy that the task order of the two methods diverges when executing multi-objective close-proximity tasks. This divergence originates from the disparate outcomes of single-task optimal trajectory planning between the two methodologies, resulting in marked differences in the optimization results of combined multi-objective tasks.

7. Conclusions

This research has yielded notable advancements in the trajectory planning for the high-speed flight of quadrotor drones, as well as the interception of unauthorized drones:
  • This article proposes an efficient method for planning the high-speed flight trajectory of quadcopter unmanned aerial vehicles. Based on linearized approximation of the air resistance model, it effectively compensates for the error between the rigid body model with six degrees of freedom and the real high-speed flight conditions, ensuring the high-speed flight effect of the unmanned aerial vehicle under real physical conditions.
  • By linearizing the dynamic model of resistance and utilizing the optimal control Pontryagin principle, the closed form solution of the optimal trajectory motion primitive was obtained, achieving an efficient solution for the optimal trajectory of quadcopter high-speed flight.
  • The effectiveness of the proposed method was verified through physical simulation, and compared to existing methods, the planning results under high-speed flight conditions have a higher accuracy than the actual simulation flight results.
  • The method proposed in this article can provide an accurate estimation of task time and energy consumption indicators for UAV flight tasks in complex high-speed scenarios, and can quickly evaluate UAV performance indicators in specific task scenarios.
  • The method proposed in this article provides a new approach for trajectory planning of quadcopter drones under high-speed flight conditions, which can be widely applied in complex high-speed flight mission scenarios of drones.
Nevertheless, this study is not without its limitations and potential for future enhancements:
  • In real-world applications, drones may be required to work in tandem with other drones to accomplish tasks. Future investigations could explore multi-drone collaborative task scenarios, taking into account factors such as communication, cooperation, and task allocation among the drones to enhance overall task execution efficiency.
  • In real-world scenarios, drones may be required to execute tasks involving larger and more variable targets. Future investigations could delve deeper into intricate situations with extensive targets to ascertain the algorithm’s robustness and efficacy.
  • While this paper primarily addresses the efficiency of interception tasks in trajectory planning, it offers limited discussion on the specifics of sensor and interceptor configurations. Future research could explore the integration of a broader range of sensors and mechanisms into different task contexts using the methodologies presented herein, thereby broadening the system’s versatility across various scenarios.

Author Contributions

Conceptualization, Y.Z. and J.Z.; methodology, Y.Z. and J.Z.; software, Y.Z. and J.Z.; validation, X.G. and Z.H.; formal analysis, Y.Z. and J.Z.; investigation, Y.Z.; resources, X.G. and Z.H.; data curation, Y.Z.; writing—original draft preparation, Y.Z. and J.Z.; writing—review and editing, X.G. and Z.H.; visualization, Y.Z.; supervision, X.G. and Z.H.; project administration, Z.H. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

The raw data supporting the conclusions of this article will be made available by the authors on request.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Castrillo, V.U.; Manco, A.; Pascarella, D.; Gigante, G. A Review of Counter-UAS Technologies for Cooperative Defensive Teams of Drones. Drones 2022, 6, 65. [Google Scholar] [CrossRef]
  2. Swinney, C.J.; Woods, J.C. A Review of Security Incidents and Defence Techniques Relating to the Malicious Use of Small Unmanned Aerial Systems. IEEE Aerosp. Electron. Syst. Mag. 2022, 37, 14–28. [Google Scholar] [CrossRef]
  3. Zhou, B.; Zhang, Y.; Chen, X.; Shen, S. FUEL: Fast UAV Exploration Using Incremental Frontier Structure and Hierarchical Planning. IEEE Robot. Autom. Lett. 2021, 6, 779–786. [Google Scholar] [CrossRef]
  4. Zhou, B.; Xu, H.; Shen, S. RACER: Rapid Collaborative Exploration with a Decentralized Multi-UAV System. IEEE Trans. Robot. 2023, 39, 1816–1835. [Google Scholar] [CrossRef]
  5. Zhou, X.; Wen, X.; Wang, Z.; Gao, Y.; Li, H.; Wang, Q.; Yang, T.; Lu, H.; Cao, Y.; Xu, C.; et al. Swarm of micro flying robots in the wild. Sci. Robot. 2022, 7, eabm5954. [Google Scholar] [CrossRef] [PubMed]
  6. Mueller, M.W.; Hehn, M.; D’Andrea, R. A Computationally Efficient Motion Primitive for Quadrocopter Trajectory Generation. IEEE Trans. Robot. 2015, 31, 1294–1310. [Google Scholar] [CrossRef]
  7. 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. Robot. Auton. Syst. 2021, 149, 103970. [Google Scholar] [CrossRef]
  8. Asadi, M.M.; Gianoli, L.G.; Saussie, D. Optimal Vehicle-Target Assignment: A Swarm of Pursuers to Intercept Maneuvering Evaders Based on Ideal Proportional Navigation. IEEE Trans. Aerosp. Electron. Syst. 2021, 58, 1316–1332. [Google Scholar] [CrossRef]
  9. Choi, J.; Seo, M.-G.; Shin, H.-S.; Oh, H. Adversarial Swarm Defence Using Multiple Fixed-Wing Unmanned Aerial Vehicles. IEEE Trans. Aerosp. Electron. Syst. 2022, 58, 5204–5219. [Google Scholar] [CrossRef]
  10. Tao, H.; Lin, D.; He, S.; Song, T.; Jin, R. Optimal terminal-velocity-control guidance for intercepting non-cooperative maneuvering quadcopter. J. Field Robot. 2022, 39, 457–472. [Google Scholar] [CrossRef]
  11. Valianti, P.; Kolios, P.; Ellinas, G. Energy-Aware Tracking and Jamming Rogue UAVs Using a Swarm of Pursuer UAV Agents. IEEE Syst. J. 2022, 17, 1524–1535. [Google Scholar] [CrossRef]
  12. Valianti, P.; Papaioannou, S.; Kolios, P.; Ellinas, G. Multi-Agent Coordinated Close-in Jamming for Disabling a Rogue Drone. IEEE Trans. Mob. Comput. 2021, 21, 3700–3717. [Google Scholar] [CrossRef]
  13. Chi, P.; Wei, J.; Wu, K.; Di, B.; Wang, Y. A Bio-Inspired Decision-Making Method of UAV Swarm for Attack-Defense Confrontation via Multi-Agent Reinforcement Learning. Biomimetics 2023, 8, 222. [Google Scholar] [CrossRef] [PubMed]
  14. Yu, Y.; Lee, S. Efficient Multi-UAV Path Planning for Collaborative Area Search Operations. Appl. Sci. 2023, 13, 8728. [Google Scholar] [CrossRef]
  15. Qin, B.; Zhang, D.; Tang, S.; Wang, M. Distributed Grouping Cooperative Dynamic Task Assignment Method of UAV Swarm. Appl. Sci. 2022, 12, 2865. [Google Scholar] [CrossRef]
  16. Pérez-González, A.; Benítez-Montoya, N.; Jaramillo-Duque, Á.; Cano-Quintero, J.B. Coverage Path Planning with Semantic Segmentation for UAV in PV Plants. Appl. Sci. 2021, 11, 12093. [Google Scholar] [CrossRef]
  17. Arrizabalaga, J.; Ryll, M. Towards Time-Optimal Tunnel-Following for Quadrotors. In Proceedings of the 39th IEEE International Conference on Robotics and Automation, ICRA 2022, Philadelphia, PA, USA, 23–27 May 2022; pp. 4044–4050. [Google Scholar]
  18. Foehn, P.; Romero, A.; Scaramuzza, D. Time-optimal planning for quadrotor waypoint flight. Sci. Robot. 2021, 6, eabh1221. [Google Scholar] [CrossRef] [PubMed]
  19. Bianchi, D.; Borri, A.; Cappuzzo, F.; Di Gennaro, S. Quadrotor Trajectory Control Based on Energy-Optimal Reference Generator. Drones 2024, 8, 29. [Google Scholar] [CrossRef]
  20. Zhou, X.; Wang, Z.; Ye, H.; Xu, C.; Gao, F. EGO-Planner: An ESDF-Free Gradient-Based Local Planner for Quadrotors. IEEE Robot. Autom. Lett. 2020, 6, 478–485. [Google Scholar] [CrossRef]
  21. Li, B.; Zhang, H.; He, P.; Wang, G.; Yue, K.; Neretin, E. Hierarchical Maneuver Decision Method Based on PG-Option for UAV Pursuit-Evasion Game. Drones 2023, 7, 449. [Google Scholar] [CrossRef]
  22. Jansson, O.; Harris, M.W. A Geometrical, Reachable Set Approach for Constrained Pursuit–Evasion Games with Multiple Pursuers and Evaders. Aerospace 2023, 10, 477. [Google Scholar] [CrossRef]
  23. Song, Y.; Romero, A.; Müller, M.; Koltun, V.; Scaramuzza, D. Reaching the limit in autonomous racing: Optimal control versus reinforcement learning. Sci. Robot. 2023, 8, eadg1462. [Google Scholar] [CrossRef]
  24. Kaufmann, E.; Bauersfeld, L.; Loquercio, A.; Müller, M.; Koltun, V.; Scaramuzza, D. Champion-level drone racing using deep reinforcement learning. Nature 2023, 620, 982–987. [Google Scholar] [CrossRef]
  25. Koenig, N.; Howard, A. Design and use paradigms for Gazebo, an open-source multi-robot simulator. In Proceedings of the 2004 IEEE/RSJ International Conference on Intelligent Robots and Systems, Sendai, Japan, 28 September–2 October 2004; pp. 2149–2154. [Google Scholar]
  26. Zipfel, P.H. Modeling and Simulation of Aerospace Vehicle Dynamics, 3rd ed.; American Institute of Aeronautics and Astronautics (AIAA): Reston, VA, USA, 2014. [Google Scholar]
  27. Tal, E.; Karaman, S. Accurate Tracking of Aggressive Quadrotor Trajectories Using Incremental Nonlinear Dynamic Inversion and Differential Flatness. In Proceedings of the 2018 IEEE Conference on Decision and Control (CDC), Miami Beach, FL, USA, 17–19 December 2018; pp. 4282–4288. [Google Scholar]
  28. Martin, P.; Salaun, E. The true role of accelerometer feedback in quadrotor control. In Proceedings of the 2010 IEEE International Conference on Robotics and Automation (ICRA 2010), Anchorage, AK, USA, 3–7 May 2010; pp. 1623–1629. [Google Scholar]
  29. Mahony, R.; Kumar, V.; Corke, P. Multirotor Aerial Vehicles: Modeling, Estimation, and Control of Quadrotor. IEEE Robot. Autom. Mag. 2012, 19, 20–32. [Google Scholar] [CrossRef]
  30. Hehn, M.; D’Andrea, R. Quadrocopter Trajectory Generation and Control. IFAC Proc. Vol. 2011, 44, 1485–1491. [Google Scholar] [CrossRef]
  31. Weber, R. Dynamic Programming and Optimal Control; University of Cambridge: Cambridge, UK, 2014. [Google Scholar]
Figure 1. Quadrotor dynamics model.
Figure 1. Quadrotor dynamics model.
Applsci 14 07030 g001
Figure 2. Diagram of the interception process of invading drones, where blue represents the interceptor, red represents the intruder, and arrows represent the vector of velocity.
Figure 2. Diagram of the interception process of invading drones, where blue represents the interceptor, red represents the intruder, and arrows represent the vector of velocity.
Applsci 14 07030 g002
Figure 3. Linearization approximation of air resistance for quadcopter drones.
Figure 3. Linearization approximation of air resistance for quadcopter drones.
Applsci 14 07030 g003
Figure 4. Optimal control input trajectory corresponding to different rotor resistance parameters.
Figure 4. Optimal control input trajectory corresponding to different rotor resistance parameters.
Applsci 14 07030 g004
Figure 5. Optimal control input trajectories corresponding to different body resistance parameters.
Figure 5. Optimal control input trajectories corresponding to different body resistance parameters.
Applsci 14 07030 g005
Figure 6. Flowchart for efficient recursive testing of trajectory feasibility.
Figure 6. Flowchart for efficient recursive testing of trajectory feasibility.
Applsci 14 07030 g006
Figure 7. Simulation results of comparison methods under low-speed conditions. The calculation takes 0.003 s.
Figure 7. Simulation results of comparison methods under low-speed conditions. The calculation takes 0.003 s.
Applsci 14 07030 g007
Figure 8. Simulation results of our method under low-speed conditions. The calculation takes 0.004 s.
Figure 8. Simulation results of our method under low-speed conditions. The calculation takes 0.004 s.
Applsci 14 07030 g008
Figure 9. Simulation results of comparison methods under high-speed conditions. The calculation takes 0.003 s.
Figure 9. Simulation results of comparison methods under high-speed conditions. The calculation takes 0.003 s.
Applsci 14 07030 g009
Figure 10. Simulation results of our method under high-speed conditions. The calculation takes 0.004 s.
Figure 10. Simulation results of our method under high-speed conditions. The calculation takes 0.004 s.
Applsci 14 07030 g010
Figure 11. Simulation results of the approach task for five targets (comparative method). The task took 23.29 s.
Figure 11. Simulation results of the approach task for five targets (comparative method). The task took 23.29 s.
Applsci 14 07030 g011
Figure 12. The relative distance and speed of the target in the comparison method.
Figure 12. The relative distance and speed of the target in the comparison method.
Applsci 14 07030 g012
Figure 13. Display of simulation results using comparative methods in 3D views.
Figure 13. Display of simulation results using comparative methods in 3D views.
Applsci 14 07030 g013
Figure 14. Simulation results of the approach task for five targets (our method). The task took 36.45 s.
Figure 14. Simulation results of the approach task for five targets (our method). The task took 36.45 s.
Applsci 14 07030 g014
Figure 15. The relative distance and speed of our method’s target.
Figure 15. The relative distance and speed of our method’s target.
Applsci 14 07030 g015
Figure 16. The presentation of our method simulation results in a 3D view.
Figure 16. The presentation of our method simulation results in a 3D view.
Applsci 14 07030 g016
Table 1. Main parameters of drones.
Table 1. Main parameters of drones.
Initial PositionMaximum Thrust fmaxMaximum Body Rate ωmax [rad/s]Rotor Resistance Coefficient krpBody Resistance Coefficient krb
[0,0,20]30100.30.6
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

Zhang, Y.; Zong, J.; Gao, X.; Hou, Z. An Efficient Trajectory Planning Method for High-Speed Interception of Invasive Drones. Appl. Sci. 2024, 14, 7030. https://doi.org/10.3390/app14167030

AMA Style

Zhang Y, Zong J, Gao X, Hou Z. An Efficient Trajectory Planning Method for High-Speed Interception of Invasive Drones. Applied Sciences. 2024; 14(16):7030. https://doi.org/10.3390/app14167030

Chicago/Turabian Style

Zhang, Yue, Jian’an Zong, Xianzhong Gao, and Zhongxi Hou. 2024. "An Efficient Trajectory Planning Method for High-Speed Interception of Invasive Drones" Applied Sciences 14, no. 16: 7030. https://doi.org/10.3390/app14167030

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

Article Metrics

Article metric data becomes available approximately 24 hours after publication online.
Back to TopTop