Skip to main content

METHODS article

Front. Plant Sci., 03 February 2023
Sec. Sustainable and Intelligent Phytoprotection
This article is part of the Research Topic Machine Learning and Artificial Intelligence for Smart Agriculture, Volume II View all 6 articles

Design of anti-load perturbation flight trajectory stability controller for agricultural UAV

Xu WeiXu WeiWu XianYu*Wu XianYu*Liu JiazhenLiu JiazhenYan YashengYan Yasheng
  • Marine replenishment department, Naval Logistics Academy, Tianjin, China

The unmanned aerial vehicle(UAV) used in agricultural fields usually has a load, which affects stability of flight trajectory. This problem is a great technical challenge and critical issue which has fascinated many researchers in this area. This research paper presents a flight dynamics model for agricultural UAV under load condition. The robust T-S fuzzy control method is applied in the attitude angle control part, and the traditional PID controller is used in the position loop control part. Results of simulation depict that the flight trajectory of agricultural UAV can reach certain stability when the load is relatively small.

1 Introduction

UAVs are widely used in pesticide spraying, sowing, pollination and other agricultural fields. Compared with traditional agricultural machinery, UAV has the advantage of high precision and efficiency (Hu et al., 2022). However UAV is a nonlinear, strongly coupled, under-driven system (Wang and Zhou, 2021). In operating processes, load of UAV changes in real time, which affects speed and accuracy of its flight attitude and trajectory stability (Luo et al., 2020). To improve the flight trajectory stability of UAV against load perturbations for different mission requirements has been a research focus for researchers (Qi and Ping, 2018).

A variety of algorithms are designed to control the flight trajectory stability of UAV,such as PID (Li et al., 2016), linear quadratic regulator (LQR) (Dong et al., 2015), H-infinity (Emam and F Ak.Harian, 2016), sliding mode control (Zhou et al., 2016), back-stepping (Shi and Lin, 2018), and adaptive control (Fan D et al., 2018) and so on. Specifically, A PID intelligent fuzzy control system is designed for spraying operation of agricultural UAV (Zheng and Chen, 2021). An on-line trajectory planning method based on the reinforcement learning is designed for UAV trajectory stability control against swing motion of the slung-payload (Xian et al., 2021). A double closed-loop adaptive control strategy is designed to solve the parameter uncertainty and external disturbance in trajectory tracking process of quad-rotor UAV problem (Gao et al., 2021). The adaptive sliding mode control strategy combined with self-anti-perturbation technique is used, considering the effects on flight performance due to sudden load changes caused by loading/unloading and external perturbation in short-distance transportation (An et al., 2018).

In summary, researches on trajectory control of UAV against load perturbation are remarkable, but the previous researches mostly focus on controlling the suspension load swing perturbation, and some of the research still has improving space of trajectory tracking considering the sudden change of load. Therefore, we designed a different controller for agricultural UAV flight trajectory control against load perturbation. In the attitude angle part, robust T-S fuzzy control method is used. And in the position loop, PID controller method is used. The proposed control method is verified by simulation tests. Load change is simulated by mass change of UAV. Results are showed by outputting UAV flight trajectory tracking image and the changes of roll, pitch and yaw angle.

2 Dynamics modelling

To describe the position and attitude of UAV system, two reference coordinate systems are established: inertial coordinate system{E}, and body coordinate system{B} as shown in Figure 1.

FIGURE 1
www.frontiersin.org

Figure 1 Inertial coordinate system and body coordinate system.

1) inertial coordinate system{E},(OE,XE,YE,ZE). It is fixed to the Earth and follows the right-hand rule, forming a right-handed, right-angle coordinate system in the order of “North, West and Sky”, i.e. the axis XE points to the North, the axis YE points to the West, and the axis ZE is perpendicular to the ground and back from the center of the Earth. OE is the origin.

2) body coordinate system{B},(OB,XB,YB,ZB). It is a right-angle coordinate system solidly connected to UAV, following right-hand rule. OB is the origin, located at the center of UAV gravity. The axis XB in symmetry plane of UAV, parallels to UAV design axis and directs to the nose. The axis YB is perpendicular to symmetry plane of UAV and points to the left of the fuselage. The axis ZB is in symmetry plane of UAV, perpendicular to plane XB-YB and points above the fuselage.

The Euler angle Θ=[ϕθψ]T is used to represent the attitude angle vector of UAV in the inertial system{E}, which is defined as follows.

ϕ : Roll angle means rotation angle of UAV body around axis XB, with positive rotation to the right.

θ : Pitch angle means rotation angle of UAV body around axis YB, with positive rotation upward.

ψ : Yaw angle refers to rotation angle of UAV body around axis ZB, with positive rotation to the right.

In the beginning, the above two coordinate systems coincide. Each coordinate vector of {B} can be converted to corresponding coordinate vector of {E} by coordinate transformation and vice versa. Rotation matrix is described by the parameters in Euler angles Θ=[ϕθψ]T. The specific derivation process is as follows.

When rotating around Z-axis in inertial coordinate system, as shown in Figure 2A, the transformation equation is

FIGURE 2
www.frontiersin.org

Figure 2 Coordinate transformation. (A) Rotating around Z-axis. (B) Rotating around Y-axis. (C) Rotating around X-axis.

{x=cos(ψ)x+sin(ψ)yy=sin(ψ)x+cos(ψ)yz=z(1)

The conversion matrix is

R(z,ψ)=[cosψsinψ0sinψcosψ0001](2)

When rotating around Y-axis, as shown in Figure 2B, the transformation equation is

{x=cos(θ)x+sin(θ)yy=yz=sin(θ)x+cos(θ)z(3)

The conversion matrix is

R(y,θ)=[cosθ0sinθ010sinθ0cosθ](4)

When rotating around X-axis, as shown in Figure 2C, the transformation equation is

{x=xy=cos(ϕ)y+sin(ϕ)zz=sin(ϕ)y+cos(ϕ)z(5)

The conversion matrix is

R(x,ϕ)=[1000cosϕsinϕ0sinϕcosϕ](6)

Transformation from {E} to{B} can be achieved by following yaw angle, then pitch angle, and then roll angle. The transformation matrix is equal to chain-multiplication of the matrices obtained from sequential rotations, i.e.

REB=R(x,ϕ)R(y,θ)R(z,ψ)(7)

Substituting equations (2), (4), and (6), into equation (7), rotation matrix from {E} to {B} is obtained: (8); similarly, we can get rotation matrix from {B} to {E}, which is an orthogonal array: (9)

REB=[cosθcosψcosθsinψ0sinϕsinθcosψcosϕsinψsinϕsinθsinψ+cosϕcosψsinϕcosθcosϕsinθcosψ+sinθsinψcosϕsinθsinψsinϕcosψcosϕcosθ](8)
RBE=[cosθcosψsinϕsinθcosψcosϕsinψcosϕsinθcosψ+sinθsinψcosθsinψsinϕsinθsinψ+cosϕcosψcosϕsinθsinψsinϕcosψsinθsinϕcosθcosϕcosθ](9)

According to νE=RBEVB, where velocity under body coordinate system VB=(X˙B,Y˙B,Z˙B), velocity under inertial coordinate system VE=(X˙E,Y˙E,Z˙E). Position state equations can be solved.

Similarly, angular velocity transformation relation from {B} to {E} can be obtained, taking X-axis as an example.

ωE=[ωxωyωz]=R(x,ϕ)R(y,θ)[00ψ˙]+R(x,ϕ)[0θ˙0]+[ϕ˙00]=[10sinθ0cosϕcosθsinϕ0sinϕcosϕcosθ][ϕ˙θ˙ψ˙](10)

Transforming the formula(10) gives angular velocity transformation matrix from {E} to {B}.

[ϕ˙θ˙ψ˙]=[1tanθsinϕtanθcosϕ0cosϕsinϕ0sinϕ/cosθcosϕ/cosθ](11)

The purpose of establishing UAV dynamics model is to analyze the variations of UAV trajectory under external forces and moments. The input of kinetics model is external forces and moments provided by the propeller. The output of kinetics model is velocity and angular velocity, which is input of the kinematics model. Then output of the kinematic model is position and attitude angle. The relationships are as shown in Figure 3.

FIGURE 3
www.frontiersin.org

Figure 3 A rigid body model of UAV flight control.

2.1 Kinetic model

According to Newton-Euler Equations, motion of a rigid body equals translation of centroid plus rotation around centroid. Translation of centroid is described by Newton’s second law, i.e. F=mdvdt, where F is resultant external force; v is velocity. Rotation round centroid is described by Euler equation, i.e. M=Jω˙+ω×Jω, where M is resultant external moment; J is 3×3 inertia matrix, and ω is angular velocity.

Then position dynamics model is υ˙E=fBmgE, where the letter E indicates vectors in {E} and the letter B indicates vectors in {B}. For convenience, force f is converted to Earth coordinate system by left multiplying rotation matrix RBE:υ˙e=RBEfBmgE.

φ, θ, ψ respectively indicate roll angle of X-axis rotation, pitch angle of Y-axis rotation, and yaw angle of Z-axis rotation, i.e., the Euler angle, as shown in Figure 4.

FIGURE 4
www.frontiersin.org

Figure 4 Attitude angle of agricultural UAV.

Expanding the equation and substituting RBE into it can be obtained as

{υ˙x=fm(cosψsinθcosϕ+sinψsinϕ)υ˙y=fm(sinψsinθcosϕsinϕcosψ)υ˙z=fm(cosθcosψ)g(12)

This yields the equations regarding combined external force and velocity——the position kinetic model. Then we talk about the equations regarding combined moment and angular velocity——the attitude kinetic model.

The angular velocity equation is that the body makes a rotational motion around the axis under the combined external moment, so that the UAV attitude Euler angle Θ=[ϕθψ]Tchanges. Moments action that UAV is subjected to when flying mainly includes: aerodynamic effects, inertial counter-torsional moments and gyroscopic moments.

For moment analysis of UAV, the angular motion equation can be obtained according to Euler’s equation as Jω˙B+ωB×JωB=Ga+τ, where, ωB denotes angular velocity in {B}; Ga denotes the gyroscopic moment; τ denotes the counter-torsional moment generated by propeller on the body axis, including roll moment τx around axis Obxb, pitch moment τy around axis Obyb, and the yaw moment τz around axis Obzb.

Regarding ωB , for convenience, the three components ωxb , ωyb , ωzb are denoted by p, q, and r respectively, i.e.

ωB=[ωxbωybωzb]=[pqr](13)

Inertia matrix of UAV in the body coordinate system consists of nine components, denoted as

J=[IxxIxyIxzIyxIyyIyzIzxIzyIzz](14)

where Ixx , Iyy , Izz are moments of inertia, while Ixy , Ixz , Iyz , etc. are products of inertia.

{Ixx=mi(yi2+zi2)=(y2+z2)dmIyy=mi(zi2+xi2)=(z2+x2)dmIzz=mi(xi2+yi2)=(x2+y2)dm(15)
{Ixy=Iyx=mixiyi=(xy)dmIxz=Izx=mixizi=(xz)dmIyz=Izy=miyizi=(yz)dm(16)

Since the UAV structure is uniformly symmetric and the origin of body coordinate system coincides with the centroid. The integral of an odd function in the symmetry region is zero, thus the inertia matrix is

J=[Ixx000Iyy000Izz](17)

The second term on the left side of Euler’s equation can be written as

ωB+JωB=[ijkpqrIxxpIyyqIzzr]=[qr(IzzIyy)pr(IxxIzz)pq(IxxIyy)](18)

Gyroscopic torque Ga : When a motor rotates at high speed, it is equivalent to a gyroscope. A gyroscope spinning at high speed is a very stable individual with the ability to keep its axial direction unchanged. Therefore if an external force tries to change the direction of the gyroscopic axis, a gyroscopic moment will be generated to resist this change.

The equation for the gyroscopic moment is given by Ga=JRPΩ×ϖ , where Ω is the propeller angular velocity vector, ϖ is the rotational angular velocity of motor rotor shaft, and we consider the rotor shaft angular velocity to be equal to the body angular velocity. Gyroscopic moment of the rotor assembly k (with motor and propeller) is Ga,k=JRPΩkb3×ϖ , where b3 is direction of the propeller angular velocity. Because the propeller only has angular velocity in Z-axis direction in {B}, b3=[001]T. JRP is total rotational inertia of the motor rotor and the propeller. Ωk is the kth propeller angular velocity, according to the right-hand rule, the clockwise rotation around z-axis is positive. When k=1, the propeller speed is negative, Ωk=−ϖ1 , the speed of the remaining propellers and so on.

b3×ϖ=(ϖ×)b3=[0rqr0pqp0][001]=[qp0](19)

“× “ denotes the cross operator.

Formula for Ga can be obtained as

Ga=[Ga,ϕGa,θGa,ψ]=JRPωk[qp0]=[qJRP(ϖ1ϖ2+ϖ3ϖ4)pJRP(ϖ1+ϖ2ϖ3+ϖ4)0](19)

Where ϖ1,ϖ2,ϖ3,ϖ4 indicates speed of propellers 1, 2, 3, and 4.

Organizing the above equations, we have

[Ixxp˙Iyyq˙Izzr˙]=[qr(IyyIzz)pr(IzzIxx)pq(IxxIyy)]=[qJRP(ϖ1ϖ2+ϖ3ϖ4)pJRP(ϖ1+ϖ2ϖ3+ϖ4)0]+[τxτyτz](20)

2.2 Kinematic model

The position equation for UAV is p˙E=vE, where p˙E=[xyz]T is coordinate position in {E}, and the expansion yields: [x˙y˙z˙]T=[vxvyvz]T.

Then we use Euler’s angle to express the attitude. The change rate of attitude angle is related to body rotational angular velocity as follows.

Θ˙=[ϕ˙θ˙ψ˙]=W·ωB=[1tanθsinϕtanθcosϕ0cosϕsinϕ0sinϕ/cosθcosϕ/cosθ][pqr](21)

Where Θ=[ϕ˙θ˙ψ˙]T, ωB=[ωxbωybωzb]T=[pqr]TWhen small perturbations happen, i.e., provided that variation of each angle is small, and change rate of attitude angle is approximately equal to the body rotational angular velocity, then we have

[ϕ˙θ˙ψ˙]=[pqr](22)

The rigid-body flight control model of UAV consists of the kinetic model and the kinematic model. According to the above equations, there are

{x¨x=f(cϕsθcψ+sϕsψ)my¨=cϕsθcψsϕsψmU1z¨=cϕcθmU1g(23)
{ϕ¨=IU2+θ˙ψ˙(IyyIzz)Ixxθ¨=IU3+ϕ˙ψ˙(IzzIxx)Iyyψ¨=IU4+ϕ˙ψ˙(IzzIxx)Izz(24)

The following equations can be obtained.

{p˙E=vEv˙E=ge3fmRe3Θ˙=W·ωBJ·ωB=ωB×(J·ωB)+Ga+τ(25)

3 Controller design

3.1 Attitude angle control

The robust T-S fuzzy control method is proposed in attitude angle control part, which demands a linear expression of the nonlinear model. Therefore, we need to build the robust T-S fuzzy control model. A robust T-S fuzzy control system is a linear time-varying system whose matrix depends on a time-varying parameter vector that varies within a known interval.

In order to represent the dynamics of UAV with a set of local linear models, a nonlinear representation of the sector based on the weight and affiliation function is applied to attitude angle. Assuming that the aerodynamic effects including blade grinding, rotor inertia or drag force, are negligible, the attitude angle can be rewritten as a multiple linearized model based on the operating points. The operating points are mainly determined by the roll rate, pitch rate and yaw rate (i.e., the first order derivatives of the corresponding angles), i.e. P=[ϕ˙θ˙ψ˙]. The dynamics linearized model of the attitude angle is

X˙=AiXE+BU(26)

Where XE=[eϕ eϕ˙ eθ eθ˙ eψ eΨ˙ q1 q2 q3]T, U=[U2U3U4]T, q˙=[q˙1q˙2q˙2]T=[eϕeθeψ]T, θref , ψref are given by inverse solution of the position control loop, ψref =0;i=1,2,.,r, r denotes the number of control rates.

The concept of sector nonlinearity is applied to this T-S fuzzy model. If the jth operating point is restricted to αmax and αmin, the weighting function is expressed as follows

ω1j=1ω0j=1αmaxPjαmaxαmin(27)

Then an affiliation function based on the weighting function is defined as

hi=j=1pωijj(28)

where p is the number of operator points and i=1,······,2p , p=3, then r=2p=8. Defining hi>0, Pi is restricted to αmax and αmin. Pi∈[−2,2],rad/s . According to the above equation, we can obtain i=1rhi=1. Using this affiliation function, the linearized model of attitude angle dynamics can be expressed as

X˙=i=1rhiKiXE+BU(29)

where Ki is the controller gain calculated by the robust T-S fuzzy system, i.e., every possible upper and lower bound arrangement of the components in P.

The eight rules of the robust T-S fuzzy system are shown in Table 1.

TABLE 1
www.frontiersin.org

Table 1 T-S control rate.

To design robust T-S fuzzy system controller gain, the robust T-S fuzzy system optimal control problem is expressed as an optimization problem with LMI constraints.

Given the LMI parameters Q=QT≥0,R=RT>0, the optimal performance bound μ>0 (such that J(x, u)<μ), and the decay rate η>0. Then, controller gain Ki calculated by the robust T-S fuzzy system is obtained by solving P∈S9×9 , Wi∈S3×9 , such that μ is minimized while meeting the following LMIs:

{(AiP+BWi)+(AiP+BWi)T+2ηP0trace(Q12P(Q12)T)+trace(Y)μ|YR12Wi(R12Wi)TP|0(30)

Then Ki=−WiP−1 , it guarantees global stability while providing the required transient behavior.

Where

R=[20000.50000.5],Q=I9.

Based on the above LMI pole configuration method and T-S fuzzy system, the attitude angle robust T-S fuzzy controller is designed, and we get the attitude angle control law as

U=[U2U3U4]=i=1rhiKiXE(31)

3.2 Position loop control

For the position loop control part, a PID controller is used, with the error defined as

ei=Xd=XiXiref(32)

Where X=[xyz], denotes the real-time coordinates and attitude angle values of UAV obtained by the sensors, and

Xref=[xrefyrefzref] denotes the desired coordinates of UAV. The desired coordinates of UAV are given by its desired trajectory. The desired attitude angle θref , ψref are given by the following equations.

{ϕref=arcsin(m(Uxsin(Ψ)Uysin(Ψ))U1)θref=arcsin(mUxU1sin(ϕ)cos(Ψ))U1cos(ϕ)cos(Ψ))Ux=cos(ϕ)sin(θ)cos(ψ)+sin(ϕ)sin(Ψ)Uy=cos(ϕ)sin(θ)cos(ψ)sin(ϕ)sin(Ψ)(33)

The error matrix of the position loop is defined as e=[xdydzd]. According to the PID control law, controller for error handling can be written as

u=kpe+kiedt+kddedt(34)

Then the control law of position loop is U1=Ux2+Uy2+(Uzg)2, Ux , Uy , Uz is given by

[UxUyUz]=KPID[xd xd˙ yd yd˙ zd z˙d xdydzd]T(34)

KPID is the control parameter.

4 Simulation verification

The simulation experiments are based on UAV parameters as shown in Table 2. Considering flight trajectory stability of UAV under load perturbation, load perturbation is simulated by mass change of UAV.

TABLE 2
www.frontiersin.org

Table 2 UAV parameters (Shen et al., 2021; Lotufo et al., 2020).

4.1 No change in UAV mass

In this scenario, the UAV mass is 1.121 kg. The flight trajectory of UAV is shown in Figures 5A–D. From these diagrams, we can see that UAV can track the expected flight trajectory well under the designed control algorithm, which reflects good control performance. There is no obvious deviation in the whole, and the real-time tracking of the flight trajectory is realized.

FIGURE 5
www.frontiersin.org

Figure 5 UAV flight trajectory with no mass change. (A) Three-dimensional trajectory of UAV, (B) UAV X-axis trajectory, (C) UAV Y-axis trajectory, (D) UAV Z-axis trajectory.

To further verify tracking performance of UAV under the designed control algorithm, angle variation diagrams are obtained. From Figures 6A–C, it can be seen that in this case, only at the start, roll angle and pitch angle have an angular change. After stabilization change of roll angle and pitch angle is less than ±0.1°. The yaw angle has been maintained at 0°. The designed control algorithm achieves the stability of UAV flight trajectory.

FIGURE 6
www.frontiersin.org

Figure 6 Angle variation of UAV under no-load condition. (A) Variation of roll angle, (B) Variation of pitch angle, (C) variation of yaw angle.

4.2 Small increase in UAV mass

Under this simulation scenario, UAV mass is initially 1.121kg, and changes abruptly to 1.5kg at 10s. The mass change diagram is shown in Figure 7.

FIGURE 7
www.frontiersin.org

Figure 7 Mass change of UAV.

From Figures 8B–D, it can be seen that UAV tracks the desired trajectory well in X and Y axis with small mass increase, consistent with constant UAV mass. While in the vertical direction, a tracking error is generated, but eventually remains smooth. The angle variation diagram is obtained from Figure 8.

FIGURE 8
www.frontiersin.org

Figure 8 UAV flight trajectory with small mass change. (A) Three-dimensional trajectory of UAV, (B) UAV X-axis trajectory, (C) UAV Y-axis trajectory, (D) UAV Z-axis trajectory.

It should be noted that in Figure 8D, when UAV mass changes at small scale at 10s, z-axis trajectory deviates from the desired trajectory at 10-15s. And it does not return to the desired trajectory after the deviation. Mass variation has an influence on z-axis trajectory. So the control method is affected by change of load.

From Figures 9A–C, it can be seen that when small increase of UAV mass happens, the roll angle and pitch angle have an angular change only at start-up. After stabilization the change is less than ±0.1°. The yaw angle has been maintained at 0°. The algorithm can realize control of UAV flight trajectory stability.

FIGURE 9
www.frontiersin.org

Figure 9 Angle variation of agricultural UAV under small load. (A) Variation of roll angle, (B) Variation of pitch angle, (C) Variation of yaw angle.

4.3 Significant increase in UAV mass

Considering a significant increase in UAV mass, the mass of UAV is also initially set to 1.121kg, which makes a significant increase to 1.5kg at 10s, indicating that a perturbation of the load occurs. The mass change diagram is shown in Figure 10.

FIGURE 10
www.frontiersin.org

Figure 10 Significant change of UAV mass.

The simulation gives flight trajectory as in Figure 11A. As can be seen in Figure 11B–D, when a significant increase in UAV mass happens, the UAV shows tracking errors in X and Y axis, which cannot track the desired trajectory well comparing to cases of constant UAV mass and small increase in UAV mass. In the vertical direction, the tracking error is further enlarged in comparison with the case of small UAV mass increase, and overshoot is more obvious.

FIGURE 11
www.frontiersin.org

Figure 11 UAV flight trajectory with significant mass change. (A) Three-dimensional trajectory of UAV, (B) UAV X-axis trajectory, (C) UAV Y-axis trajectory, (D) UAV Z-axis trajectory.

From Figure 12A–C, it can be seen that roll angle and pitch angle have an angular change situation only at start-up when UAV mass increases significantly. After stabilization, the change in roll angle and pitch angle is less than ±0.1°, and the yaw angle has been maintained at 0°. The designed controller can realize the flight trajectory stability under significant load.

FIGURE 12
www.frontiersin.org

Figure 12 Angle variation of UAV under significant load.

4.4 UAV mass change with time

To better reflect effect of load perturbation, UAV mass was designed to change with time. In this scenario, UAV mass is initially 1.121kg, then it increases to 3kg from 10s to 20s. And this weight is maintained until 30s, after which the mass starts to decrease and reaches the initial mass at 40s as shown in Figure 13.

FIGURE 13
www.frontiersin.org

Figure 13 Mass change of UAV.

This case better represents the effect of load perturbation on the stability of UAV flight trajectory, the perturbation shows dynamic changes with time, and this is closer to the real situation. The trajectory in this case is shown in Figure 14A.

FIGURE 14
www.frontiersin.org

Figure 14 UAV flight trajectory with mass change. (A) Three-dimensional trajectory of UAV, (B) UAV X-axis trajectory, (C) UAV Y-axis trajectory, (D) UAV Z-axis trajectory.

From Figures 14B–D, it can be seen that under the condition of time-varying UAV mass, the trajectory of the UAV in X and Y axis can track the desired trajectory well when the mass does not vary much. The tracking error appears when the mass increases more. In the vertical direction, the tracking error of the UAV varies with the UAV mass change.

From Figures 15A–C, it can be seen that roll angle and pitch angle have an angular change only at start-up. After stabilization, the change in roll angle and pitch angle is less than ±0.1°. The yaw angle has been maintained at 0°. The designed controller can realize the flight trajectory stabilization.

FIGURE 15
www.frontiersin.org

Figure 15 Angular variation for UAV under load variation. (A) Variation of roll angle, (B) Variation of pitch angle, (C) Variation of yaw angle.

According to the simulation results, when the UAV has a significant change in mass, i.e., a large load, the UAV will have a significant error in tracking the desired trajectory, especially in the vertical axis direction.

5 Conclusion

In the scenario of small increase in mass, UAV can track the desired trajectory well in X and Y axis, and a tracking error is generated in the vertical direction, but it eventually remains steady. In the scenario of a significant increase in mass, UAV tracked the desired trajectory tracking in X and Y axis, with a bigger tracking error in the vertical direction. In the scenario of time-varying mass, the UAV tracked the desired trajectory well in X and Y axis when the mass did not change much, and tracking errors appeared when the mass increased more. In vertical direction, the tracking error varies with the mass of the UAV.

In summary, taking agricultural UAV as research object, we adopt robust T-S fuzzy control method in attitude angle control part and PID controller in position loop control part to make UAV flight trajectory achieve stability in the simulation environment of load variation. Due to the sudden change of mass, the trajectory of UAV will deviate from the expected path, but its tracking error is small, so that the designed controller can effectively solve the trajectory tracking problem of small variable load against perturbation.

Data availability statement

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

Author contributions

XW: Conceptualization, Methodology, Supervision. WX: Software, Validation. LJ: Writing - Original Draft, Data Curation. YY: Formal analysis, Writing - Review & Editing. All authors contributed to the article and approved the submitted version.

Conflict of interest

The authors declare that the research was conducted in the absence of any commercial or financial relationships that could be construed as a potential conflict of interest.

Publisher’s note

All claims expressed in this article are solely those of the authors and do not necessarily represent those of their affiliated organizations, or those of the publisher, the editors and the reviewers. Any product that may be evaluated in this article, or claim that may be made by its manufacturer, is not guaranteed or endorsed by the publisher.

References

An, Sh, Yuan, S., Li, H. D. (2018). Design of trajectory tracking controller for a quad-rotor UAV with varied payload. Electron. Optics Control 25(3), 59–63. doi: 10.3969/j.issn.1671-637X.2018.03.013

CrossRef Full Text | Google Scholar

Dong, Y., Fu, J., Yu, B., Zhang, Y., Ai, J. (2015). “Position and heading angle control of an unmanned quadrotor helicopter using LQR method”. In Chinese Control Conference, CCC (Vol. 2015-September, pp. 5566–5571) (HangZhou, China: IEEE Computer Society). doi: 10.1109/ChiCC.2015.7260508

CrossRef Full Text | Google Scholar

Emam, M., F Ak.Harian, A. (2016). “Attitude tracking of quadrotor UAV via mixed H2/H, controller: An LMI based approach,” in proceeding of 2016 24th Mediterranean Conference on Control and Automation (MED), (Athens, Greece: IEEE), 390–395. doi: 10.1109/MED.2016.7535919

CrossRef Full Text | Google Scholar

Fan, D., Xing, X., Zhao, Y., Yu, H., University, N. P. (2018). Research on UAV 4D trajectory control based on adaptive fuzzy PID. Comput. Measurement &Control 1), 112–114+119. doi: 10.16526/j.cnki:11-4762/tp.2018.01.027

CrossRef Full Text | Google Scholar

Gao, J., Duan, L. Y., Deng, L. W. (2021). Anti-interference trajectory tracking control of quadrotor UAV. Control Decision 36 (2), 8. doi: 10.13195/j.kzyjc.2019.0875

CrossRef Full Text | Google Scholar

Hu, W. Y., Xi, Y. Q., Yin, X. M. (2022). Research progress on pesticide application technology of agricultural plant protection UAV in China. Modern Agric. Sci. Technol. 10), 5. doi: 10.3969/j.issn.1007-5739.2022.10.027

CrossRef Full Text | Google Scholar

Li, F. L., Li, T. Y., Wang, Y. L. (2016). Flight attitude stability control optimization for quad rotor unmanned air vehicle. Comput. Simulation 33 (10), 43–47. doi: 10.3969/j.issn.1006-9348.2016.10.010

CrossRef Full Text | Google Scholar

Lotufo, M. A., Colangelo, L., Novara, C. (2020). Control design for UAV quadrotors via embedded model control. IEEE Trans. Control Syst. Technol. 28 (5), 1741–1756. doi: 10.1109/TCST.2019.2918750

CrossRef Full Text | Google Scholar

Luo, D. X., Jiang, J., Xu, D. W. (2020). Dual closed-loop trajectory tracking control of quadrotor load UAV. Small Special Electrical Machines 48 (9), 39–44. doi: 10.3969/j.issn.1004-7018.2020.09.011

CrossRef Full Text | Google Scholar

Qi, J. T., Ping, Y. (2018). Survey on flight control technology for hanging load UAV. Unmanned Syst. Technol. 1(1), 83–90. doi: 10.19942/j.issn.2096-5915.2018.01.008

CrossRef Full Text | Google Scholar

Ma, D. L., Xia, Y. Q., Shen, G. H., Jiang, H. R., Hao, C. X. (2021). Practical fixed-time disturbance rejection control for quadrotor attitude tracking. IEEE Trans. Ind. Electron. 68 (8), 7274–7283. doi: 10.1109/TIE.2020.3001800

CrossRef Full Text | Google Scholar

Shi, C., Lin, D. (2018). Adaptive integral backstepping control of quadrotor. Appl. Res. Comput. 35 (11), 3338–3342. doi: 10.3969/j.issn.1001-3695.2018.11.033

CrossRef Full Text | Google Scholar

Wang, H., Zhou, L. (2021). Design of a backstepping integral adaptive controller for quadrotor UAV. Acta Armamentarii 42 (6), 1283–1289. doi: 10.3969/j.issn.1000-1093.2021.06.019

CrossRef Full Text | Google Scholar

Xian, B., Zhang, S. J., Han, X. W., Cai, J. M., Wang, L. (2021). Trajectory planning for unmanned aerial vehicle slung-payload aerial transportation system based on reinforcement learning. J. Jilin University:Engineering Technol. Edition 51 (6), 2259–2267. doi: 10.13229/j.cnki.jdxbgxb20200577

CrossRef Full Text | Google Scholar

Zheng, H., Chen, J. (2021). Optimization analysis of intelligent control system for spraying operation of agricultural plant protection machine. J. Agric. Mechanization Res. 43 (12), 203–206. doi: 10.3969/j.issn.1003-188X.2021.12.036

CrossRef Full Text | Google Scholar

Zhou, X., Liu, R., Zhang, J., Zhang, X. “Stabilization of a Quadrotor With Uncertain Suspended Load Using Sliding Mode Control.” Proceedings of the ASME 2016 International Design Engineering Technical Conferences and Computers and Information in Engineering Conference. Volume 5A: 40th Mechanisms and Robotics Conference. Charlotte, North Carolina, USA: IEEE ASME. doi: 10.1115/DETC2016-60060

Google Scholar

Keywords: agriculture, UAV, trajectory stability, load perturbation, flight control

Citation: Wei X, XianYu W, Jiazhen L and Yasheng Y (2023) Design of anti-load perturbation flight trajectory stability controller for agricultural UAV. Front. Plant Sci. 14:1030203. doi: 10.3389/fpls.2023.1030203

Received: 28 August 2022; Accepted: 23 January 2023;
Published: 03 February 2023.

Edited by:

Shanwen Zhang, Xijing University, China

Reviewed by:

Mohammad Shah Jahan, Sher-e-Bangla Agricultural University, Bangladesh
Xiao Liang, Nankai University, China

Copyright © 2023 Wei, XianYu, Jiazhen and Yasheng. This is an open-access article distributed under the terms of the Creative Commons Attribution License (CC BY). The use, distribution or reproduction in other forums is permitted, provided the original author(s) and the copyright owner(s) are credited and that the original publication in this journal is cited, in accordance with accepted academic practice. No use, distribution or reproduction is permitted which does not comply with these terms.

*Correspondence: Wu XianYu, wuxianyu88@126.com

Disclaimer: All claims expressed in this article are solely those of the authors and do not necessarily represent those of their affiliated organizations, or those of the publisher, the editors and the reviewers. Any product that may be evaluated in this article or claim that may be made by its manufacturer is not guaranteed or endorsed by the publisher.