DAC_flex_controlInfotech2009

Page 1

Disturbance Accommodating Based Flexible System Control Steve Rogers Penn State – Applied Research Laboratory 814.867.1831 Scr12 @arl.psu.edu

Abstract Flexible systems in aerospace many times experience the negative effects of elastic structural modes within their control systems. Most control systems are based on rigid body models. Adverse effects occur when the slower or primary structural modes are within the control system bandwidth. Many times this condition results in uncontrolled oscillations. Flexible system control is based on estimation and then attenuation of the disturbances. Although this may be an effective approach it does not take advantage of the disturbance energy available to reduce the amount of control effort. In certain aerospace systems it is advantageous to utilize disturbance energy, if possible, to reduce control energy usage. One approach is based on Disturbance Accommodating Control (DAC) and is called Disturbance Utilization Control (DUC) 123. DUC employs optimal control theory to design controllers that make optimal utilization of disturbances. DAC/DUC approaches utilize linear models of the plant and disturbance. Optimal statespace control methods, such as LQR or H∞ are used to generate a control system utilizing the disturbance state estimations along with the plant state estimates. Generally, the fixed system model is known and may be used in an observer design to estimate the disturbance. Effective disturbance estimation in the usage of DAC theory requires an input and an output signal based on the input/output model used. An observer system is designed for estimation. The paper will develop the general concepts of DAC/DUC and show an application to flexible disturbance accommodation/utilization. Keywords: disturbance accommodation control, observer design, flexible system control

Introduction Power, weight, and volume concerns influence markedly aerospace designs. As more and more composite materials are utilized in aerospace structures the flexible modes become lower and lower. In the past the lower flexible modes were ignored in control system design because they were significantly higher than the control system bandwidth. This is now not always the case, especially with long duration mission UAV designs where weight must be minimized. If the rigid body model may be used in the control law design 1 American Institute of Aeronautics and Astronautics AIAA-2009-2049


and the remainder of the flexible dynamics treated as unmodeled dynamics Disturbance Accommodation Control (DAC) theory1-4 may be used for the design. DAC theory is based on the assumption that disturbances may be represented as continuous waveforms. That being the case, the disturbances may then be cast in a state space form. This is not an unreasonable assumption considering the vibration modes of the typical wing surface. The disturbance will enter the control system as a smooth sinusoidal waveform. The disturbance representation will be used to estimate the disturbance states, which then may be used to offset the waveform disturbance in the control law. The typical state space disturbance representation is: w(t ) = H (t ) z + L(t ) x dz = D (t ) z + M (t ) x + σ (t ) dt

where z plays the role of the state of the disturbance w. Generally L and M are 0, since the plant state contributions are 0. H is associated with the assumed form of the disturbance. D reflects the waveform-mode patterns of the disturbance w. σ is an impulse sequence. The above disturbance model may be used to describe disturbances in the following plant state space model. dx(t ) = A(t ) x(t ) + B (t )u (t ) + F (t ) w(t ) dt y (t ) = C (t ) x(t ) + E (t )u (t ) + G (t ) w(t )

where x is the state vector, u is the input vector, y is the measurement vector and w is the disturbance vector. A, B, F, C, E, and G are matrices of the appropriate size. By incorporating the above state space formulations we can derive a composite system. d dt

x   A + FL z  =  M   

y = [ C + GL

FH x  B  0  +  u +      D  z   0  σ 

x  GH ]   + Eu z 

E = 0 = L = M is usually the case, and then the composite system becomes: d dt

x   A z  = 0   

FH x  B  0  + u +  D  z   0  σ 

x  GH ]   z 

y = [C

With the above formulation we can consider a state space observer. 2 American Institute of Aeronautics and Astronautics AIAA-2009-2049


DAC State Space Observer and DAC Control Laws An observer is designed because the disturbance states and possibly some of the other states are not measurable. The state space form of the observer may be written as d dt

 xˆ   A  zˆ  =  0   

 FH   xˆ  B  +  u + L1 y − [ C    D   zˆ   0  

 xˆ  GH ]    zˆ 

The hats indicate estimate and L1 is a matrix of appropriate size selected to stabilize the error dynamics of the observer. We may divide the control law into two parts: one by standard design (for example, pole placement or lqr) and the other selected to counter the disturbance estimate w. u = us + uw

where us is from standard practice and uw selected to counter the disturbance as below. ˆ = −FHzˆ Bu w = −Fw dzˆ ˆ = Hzˆ = Dzˆ, w dt

If we consider the disturbance to be a series of random steps we may write D and H as D = 0 and H = 1 or dzˆ ˆ = 1zˆ = 0, w dt

If we consider the disturbance as a series of ramps we have dzˆ ˆ = Hzˆ = Dzˆ, w dt 0 1  D = , H = [1 0 0

0]

For sinusoids we may write dzˆ ˆ = Hzˆ = Dzˆ , w dt 0 1 0  D = 0 0 1, H = [1  0 0 0 

0

0]

3 American Institute of Aeronautics and Astronautics AIAA-2009-2049


With this approach the DAC control contribution is of the form Bu w = −Fzˆ . If the sampling rate is sufficiently fast the above three disturbance representations will work for the vast majority of applications. If the principal flexible vibration mode is known it may be incorporated into the above structure as shown below. It is assumed to be an oscillator with the form: s 2 + w 2 = σ . Thus, we have: dzˆ ˆ = Hzˆ = Dzˆ, w dt 1  0 D = , H = [1 2 0 − w 

0]

Whenever the principal flexible mode is known the above structure may be combined with any one or more of the others to estimate the composite disturbance signal. The above concepts decentralize the control law which works well under most circumstances. Another interesting concept is to utilize the disturbance state estimates within the context of a state space control law such as LQR or H∞. This utilizes the composite state estimates in the control law instead of simply canceling the disturbance estimate. Thus, the approach is called Disturbance Utilization Control (DUC). The observer development is identical to that of DAC above. The distinction between DAC and DUC lies in the control calculation. Please see Appendix B for matlab code.

Controller Configuration Model-based control laws may be applied in different ways. Figure 1 below shows the conventional control configuration. The block ‘K’ is the model-based stabilizing controller and block ‘G’ is the system to be controlled. The signals ‘di’ indicate disturbance signals or noise for the process and measurement. For single degree of freedom design formulations this is normally the placement if it has integral action. If loop-shaping is involved it is desirable to keep the weighting functions separate from the control system. Figure 2 shows an alternative configuration with the controller in the feedback loop. The signal ‘r’ is the reference signal and ‘d2’ is the measurement noise. The conventional configuration shown in Figure 1 has been known to give larger amounts of overshoot than the configuration shown in Figure 2. The formulation shown in Figure 2 has the same motivation as in classical PID where the derivative feedback term is not directly feed with the error signal.

4 American Institute of Aeronautics and Astronautics AIAA-2009-2049


Figure 1. Typical Control Law Configuration

Figure 2. Alternative Control Law Configuration

H∞ Approach The usual solution is to iteratively determine the minimum γ that satisfies the control objectives. While this produces satisfactory control, an alternative approach is used here for H∞ control. γmin is found by the following equation [ref. 5-8]:

Note that λmax is the maximum eigenvalue. X and Z are the matrix solutions of the riccati equations below: 5 American Institute of Aeronautics and Astronautics AIAA-2009-2049


- Control Algebraic Riccati Equation - Filtering Algebraic Riccati Equation With the above information the central controller ‘K’ is given below [ref. 5-8].

Thus far, the above procedure only addresses stability and robustness, but doesn’t give the designer a mechanism to achieve performance objectives. Referring to Figure 2 again, the block ‘K’ may be considered a part of an inner control loop. We may then construct an outer loop with a separate controller that is designed to achieve the control objectives as in Figure 3.

Figure 3 Inner/Outer Control Loop to Achieve Performance Objectives

6 American Institute of Aeronautics and Astronautics AIAA-2009-2049


The block ‘PI’ may now be designed by classical control means, including rise time, settling time, phase/gain margin, pole placement, etc. The block ‘PI’ refers to a matrix of transfer functions that are appropriately designed to achieve control objectives. A simple example of a design process for a single-input single-output unstable plant is given in Appendix A.

Simulation The above two concepts (DAC and DUC) were applied to a simple rigid model with a sinusoidal disturbance. The state space model is shown below. The output is the pitch rate. The disturbance is assumed to be injected along with the control signal. A = [-0.313 56.7 0 -0.0139 -0.426 0 0 56.7 0]; B = [0.232 0.0203 0]'; C1 = [0 0 1]; D1 = 0; Gp = ss(A,B,C1,D1);

In both cases the observer was designed by pole placement and the control law was an LQR and designed using matlab’s lqr command. The simulink high-level block diagram is shown below in Figure 4. The matlab code for DAC and DUC is given in Appendix B. 1/z y(n)=Cx(n)+Du(n) U(E) U x(n+1)=Ax(n)+Bu(n) u DAC Selector

1 s+1

Gp Plant Add2

T ransfer Fcn

Out1

Dist

1/z y(n)=Cx(n)+Du(n) U(E) U x(n+1)=Ax(n)+Bu(n) DUC Selector1 Add4

Gp Plant1 Add1

Figure 4 Simulink diagram of the Experiment The disturbance is added to the plant control input. The feedback control input is returned to the observer via a delay to prevent an algebraic loop. The setpoint stream is passed through a simple lag filter. This setpoint filter may be designed to meet design criteria such as rise time. Simulation results follow.

7 American Institute of Aeronautics and Astronautics AIAA-2009-2049


Figure 5 DAC Simulation Results For Moderate Disturbance

Figure 6 DUC Simulation Results For Moderate Disturbance 8 American Institute of Aeronautics and Astronautics AIAA-2009-2049


Figure 7 DAC Simulation Results For Large Disturbance

Figure 8 DUC Simulation Results For Large Disturbance 9 American Institute of Aeronautics and Astronautics AIAA-2009-2049


In all cases in Figures 5 through 8 the plots signals are: plot 1) setpoint and pitch measurement response, plot 2) disturbance and disturbance estimate, and plot 3) composite control input. The three-state disturbance model was used in all cases. Figures 5 and 6 above show the DAC and DUC results for a moderate size sinusoidal disturbance. In this case DAC and DUC perform tracking about the same and in both cases the disturbance estimate seemed to track the actual estimate well. In Figures 7 and 8 the DUC method performed noticeably better with both a more complex and higher amplitude disturbance. In the latter case the disturbance consisted of a sinusoid plus random magnitude steps. By taking advantage of the additional disturbance states the DUC approach was able to attenuate the effects of the disturbance and track better. This is the impact of full information in the DUC as opposed to partial information in the DAC approach.

Conclusions Two disturbance accommodating methods – DAC and DUC – were developed and applied to a pitch control system with sinusoidal disturbances. The DUC method is a full information state space approach to control of a system with a disturbance. The DAC method relies on disturbance estimation and cancellation. With the extra information the DUC method is able to accommodate more complex disturbance signals. Both DAC and DUC may be applied with LQR or pole placement state space methods. Future work includes application to more complex/realistic simulations with eventual extension to aerospace systems.

References 1. M. Mohajer and C. D. Johnson, ‘A New Approach to Decentralized Control of Large-Scale Systems’, Proceedings of the Seventeenth Southeastern Symposium on System Theory, p 252-6, 1985. 2. C. D. Johnson, ‘Theory of disturbance-accommodation controllers’, Control and Dynamic Systems; Advances in Theory & Applications, v. 12, Academic Press, USA, 1976. 3. S. Rogers, A Comparison Study of Several Control Algorithms for Disturbance Rejection Capability, 1996, PhD Dissertation, Kansas State University. 4. L. Fan etal, ‘Decentralized Control of Power Systems Using Disturbance Accommodation Techniques,’ Proceeding 2001 American Control Conference, pp 799-804, vol 2. 5. R. A. Hyde, H∞ Aerospace Control Design, 1996, Springer. 6. K. Glover and D.C. McFarlane, “Robust stabilization of normalized coprime factor plant descriptions with H∞-bounded uncertainty,” IEEE Transactions on Automatic Control, 34(8):821-830, August, 1989. 7. D.C. McFarlane, Robust Controller Design Using Normalized Coprime Factor Plant Descriptions, PhD thesis, University of Cambridge, 1988. 8. D.-W. Gu, P. Hr. Petkov and M. M. Konstantinov, Robust Control Design with Matlab, 2005, Springer-Verlag, London, UK.

10 American Institute of Aeronautics and Astronautics AIAA-2009-2049


Appendix A

Optimal Gamma Approach for H∞ Design Ideas from Hyde - H∞ Aerospace Control Design Hyde_ex1.m

Background Given a minimal realization [A,B,C,0] of a controllable and observable plant the optimal gamma may be directly computed as follows: 1. A'X + XA - XBB'X + C'C = 0 2. AZ + ZA' - ZC'CZ + BB' = 0 3. gam_min = sqrt(1 + eig_max(XZ));

The central controller is given by 1. K = [A + HC + gam*gam*BB'X/W1',-H; gam*gam*B'X/W1',0]; 2. W1 = I + XZ - gam*gam*I; 3. H = -ZC'

Preliminaries save_system('Hyde_mdl') close_system('Hyde_mdl') clc warning off close all clear all dbstop if error

Model Definition num = -10;den = -[-1 2 20]; % unstable pole sys = zpk(num,den,100); [A,B,C,D] = zp2ss(num,den,100);

Hinf Minimum Gamma Design X = care(A,B,C'*C); % control algebraic Riccati Equation Z = care(A',C',B*B');% filter algebraic Riccati Equation gam_min = sqrt(1 + max(eig(X*Z))); gam = gam_min; % get γmin, then check a variety of larger γ values gam = [gam,ceil(gam_min)]; gam = [gam,1.5*gam_min]; gam = [gam,2*gam_min]; gam = [gam,6,10];

Hinf Control Design chek = []; PIC = zpk(-1.2,0,0.15); PIC1 = zpk(-1,0,.3)*zpk(-1,-0.5,1); % PIC1 = zpk(-[,1); for gamiter = gam W1 = eye(size(X)) + X*Z + gamiter*gamiter*eye(size(X)); H = -Z*C'; Ahinf = A + H*C - gamiter*gamiter*B*B'*X*inv(W1'); Hinf_contr = ss(Ahinf,-H,gamiter*gamiter*B'*X*inv(W1'),0);

11 American Institute of Aeronautics and Astronautics AIAA-2009-2049


open_system('Hyde_mdl') sim('Hyde_mdl',50) chek = [chek,sum(abs(yout(:,1)-yout(:,2)))]; pause(1)

% end figure plot(gam,chek,'r*'),grid on xlabel('gamma') ylabel('RMS error') gamiter = gam(1); W1 = eye(size(X)) + X*Z + gamiter*gamiter*eye(size(X)); H = -Z*C'; Ahinf = A + H*C - gamiter*gamiter*B*B'*X*inv(W1'); Hinf_contr = ss(Ahinf,-H,gamiter*gamiter*B'*X*inv(W1'),0);

Simulink screen of control systems

12 American Institute of Aeronautics and Astronautics AIAA-2009-2049


Comparison plot of Absolute error sums for a given scenario using different Îł values

SVD Plot figure sigma(sys*Hinf_contr,Hinf_contr*sys);grid on

13 American Institute of Aeronautics and Astronautics AIAA-2009-2049


Pole-Zero Plot figure pzmap(feedback(sys*Hinf_contr,1)),grid on

14 American Institute of Aeronautics and Astronautics AIAA-2009-2049


Step Plot figure Oloop1 = feedback(sys*Hinf_contr,1)*PIC1; Oloop = PIC*feedback(sys,Hinf_contr); step(feedback(Oloop1,1),feedback(Oloop,1)),grid on legend('Oloop1','Oloop','Location','Best')

Root Locus Plot figure rlocus(Oloop),grid on title('Oloop') % figure % rlocus(Oloop1),%sgrid % title('Oloop1')

15 American Institute of Aeronautics and Astronautics AIAA-2009-2049


Appendix B – DAC/DUC Design D = [0 1 0;0 0 1;0 0 0]; H = [1 0 0]; A2 = A*1;B2 = B*1;C2 = C1*1;D1 = 0; Ad = [A2 B2*H;zeros(3,3),D]; Bd = [B2;zeros(3,1)]; Cd = [C2 zeros(1,3)]; Gpd = c2d(Gp, T); Phi = Gpd.a; Gam = Gpd.b;

% DAC design polydes = [1.0000 22.2644 39.4342 28.1849 0.0000] ; Ldac = place(Ad',Cd',roots(polydes))'; Ad1 = Ad; Ad1 = Ad - Ldac*Cd; % eig(Ad1),roots(polydes) Bd1 = [Bd,Ldac]; Q = diag([xin(7:9)]); K = dlqr(Phi,Gam,Q,1); Cd1 = [-K -H]; sys = ss(Ad1,Bd1,[Cd1;eye(6)],zeros(7,2)); dacsys = c2d(sys,T);

6.5013

16 American Institute of Aeronautics and Astronautics AIAA-2009-2049

0.1072


% DUC design polydes = [1.0000 133.7961 349.2616 347.9551 103.6295 0.0048 0.0000] ; Ldac = place(Ad',Cd',roots(polydes))'; Ad1 = Ad; Ad1 = Ad - Ldac*Cd; % eig(Ad1),roots(polydes) Bd1 = [Bd,Ldac]; Bd(4:6) = B2;Bd(6) = B2(2); K1 = lqr(Ad,Bd,Q,1); Cd1 = -K1; sys = ss(Ad1,Bd1,[Cd1;eye(6)],zeros(7,2)); dacsys = c2d(sys,T);

Appendix C

DAC Flexible Study flex_DAC_paper.m

Model Definition

Longitudinal Dynamics ----------------------State vector: x = [u w q theta h Omega] Input vector: u = [elevator throttle] Output vector: y = [Va alpha q theta h] State matrix: Alon Control matrix: Blon Observation matrix: Clon Lateral-directional Dynamics -----------------------------State vector: x = [v p r phi psi] Input vector: u = [aileron rudder] Output vector: y = [beta p r phi psi] State matrix: Alat Control matrix: Blat Observation matrix: Clat

Preliminaries clc clear all close all dbstop if error save_system('aerosonde_scr') close_system('aerosonde_scr') load aerosonde_linmod load aero_optim_params dsys = abs(dsys); sys_lat = ss(Alat,Blat,Clat,zeros(5,2)); sys_lon = ss(Alon,Blon,Clon,zeros(5,2));

Observer Longitudinal lqr Design Qlon = eye(size(Alon)); [nr nc] = size(Clon);

17 American Institute of Aeronautics and Astronautics AIAA-2009-2049


Rolon = 0.6*eye(nr); Llon = lqr(Alon',Clon',Qlon,Rolon);

Longitudinal lqr control design

Qlon = diag(dsys(1:8)); Rlon = diag(dsys(9:10)); Alon1 = Alon; Alon = [Alon(1,:);-Clon(1,:);Alon(2:end,:);-Clon(5,:)]; Alon = [Alon(:,1),zeros(8,1),Alon(:,2:end),zeros(8,1)]; Blon = [Blon(1,:);[0 0];Blon(2:end,:);[0 0]]; Klon = lqr(Alon,Blon,Qlon,Rlon); % Check poles for stability

Longitudinal Observer eigenvalues eig(Alon1-Llon'*Clon), ans = -4.3081 -4.3081 -4.1050 -4.1050 -1.2383 -2.8805

+10.0568i -10.0568i + 3.9378i - 3.9378i

Longitudinal Controller eigenvalues eig(Alon-Blon*Klon) ans = -39.2026 -4.2437 -4.2437 -1.3229 -1.3229 -0.1974 -0.0119 -0.0021

+10.0753i -10.0753i + 1.4226i - 1.4226i

Add Altitude & airspeed integrators to Longitudinal Control Law Clon = [Clon(:,1),zeros(5,1),Clon(:,2:end),zeros(5,1)]; Clon = [Clon(1,:);[0 1 0 0 0 0 0 0];Clon(2:end,:);... [0 0 0 0 0 0 0 1]]; Llon = [Llon(:,1),zeros(5,1),Llon(:,2:end),zeros(5,1)]; Llon = [Llon(1,:);[0 1 0 0 0 0 0 0];Llon(2:end,:);... [0 0 0 0 0 0 0 1]]; contr_lonsys = ss(Alon-Llon'*Clon,Llon',-Klon(1:2,:),... zeros(2,7));

Lateral lqr Observer Design

Qlat = eye(size(Alat)); [nr nc] = size(Clat); Rolat = 0.6*eye(nr); Llat = lqr(Alat',Clat',Qlat,Rolat);

18 American Institute of Aeronautics and Astronautics AIAA-2009-2049


Lateral lqr Control Design

Qlat = diag(dsys(11:15)); Rlat = diag(dsys(16:17)); Klat = lqr(Alat,Blat,Qlat,Rlat); % Check eigenvalues

Lateral Observer eigenvalues eig(Alat-Llat'*Clat), ans = -19.2194 -1.6405 -1.6405 -1.3166 -1.3166

+ + -

5.5394i 5.5394i 0.1848i 0.1848i

Lateral Controller eigenvalues eig(Alat-Blat*Klat) ans = 1.0e+002 * -4.3226 -0.0044 -0.0180 -1.1354 + 1.1306i -1.1354 - 1.1306i

Setup for Simulation contr_latsys = ss(Alat-Llat'*Clat,Llat',-Klat,zeros(2,5)); open_system('aerosonde_scr') open_system('aerosonde_scr/Controller') assignin('base','contr_lonsys',contr_lonsys); assignin('base','contr_latsys',contr_latsys); set_param('aerosonde_scr/Controller/TAS-SP','Seed',... int2str(50)) set_param('aerosonde_scr/Controller/psi-SP','Seed',... int2str(85)) sim('aerosonde_scr',600)

19 American Institute of Aeronautics and Astronautics AIAA-2009-2049


Simulink Model of Aerosonde UAV

Longitudinal and Lateral Control System in Simulink

20 American Institute of Aeronautics and Astronautics AIAA-2009-2049


Altitude in Meters Tracking Results

Airspeed Tracking in meters/second

Psi (heading) Tracking in radians

21 American Institute of Aeronautics and Astronautics AIAA-2009-2049


Turn static files into dynamic content formats.

Create a flipbook
Issuu converts static files into: digital portfolios, online yearbooks, online catalogs, digital photo albums and more. Sign up and create your flipbook.