Given the linear state-space equations: and , we define the state for the Quanser Aero Experiment as
x=\begin{bmatrix} \theta(t), & \psi (t), & \dot{\theta}(t), & \dot\psi(t) \end{bmatrix}^T \tag{38}
the output vector as y= \begin{bmatrix} \theta(t), & \psi(t), & \dot{\theta}(t), & \dot{\psi}(t) \end{bmatrix}^T \tag{39}
and the control variables as
u=\begin{bmatrix} V_\theta & V_\psi\end{bmatrix}^T \tag{40}
where and are the pitch and yaw angles, respectively, and and are the motor voltages applied to the pitch and yaw rotors (i.e. the main and tail rotors). Using the equations of motion in Equations (1) and (2), the state-space matrices are
A=\begin{bmatrix} 0&0&1&0\\ 0 &0&0&1\\ -K_{\theta}/J_\theta & 0& -D_\theta/J_\theta& 0 \\ 0 &0 &0&-D_\psi/J_\psi \end{bmatrix} \tag{41.a}
B=\begin{bmatrix} 0& 0\\ 0&0\\ K_{\theta\theta}/J_\theta & K_{\theta\psi}/J_\theta \\ K_{\psi\theta}/J_{\psi} & K_{\psi\psi}/J_\psi \end{bmatrix} \tag{41.b}
C=\begin{bmatrix} 1&0&0&0\\ 0&1&0&0 \\ 0&0&1&0 \\ 0&0&0&1\end{bmatrix} \tag{41.c}
D=\begin{bmatrix} 0&0\\ 0&0 \\ 0&0\\ 0 & 0\end{bmatrix} \tag{41.d}
In this section, a state-feedback controller is designed to regulate the pitch and yaw angles of the Quanser Aero Experiment to desired angles. Using the previous state-space model, we can find a control gain based on the coupled dynamics to stabilize the system. The control gains are computed using Linear-Quadratic Regulator (LQR) theory. The general state-feedback control is illustrated in Figure 11. The state-feedback controller is defined
u=K(x_d-x) \tag{42}
x_d=\begin{bmatrix}\theta_d, & \psi_d, & 0,&0\end{bmatrix} ^ T\tag{43}
u=\begin{bmatrix} V_\theta&V_\psi\end{bmatrix} ^ T\tag{44}
u=K(x_d-x)=k_{p,\theta}(\theta_d-\theta)+k_{p,\psi}(\psi_d-\psi)-k_{d,\theta}\dot\theta-k_{d,\psi}\dot\psi \tag{46}
The state-space matrices derived in Equation (41) are entered in the State-Space block in SIMULINK and the control gain is set to the MATLAB variable K.
Using parameters from Part A, obtain state-space matrices of the system neglecting coupling effect.
Build the SIMULINK model of the system
Check whether your controller meets the desired specifications.
Save the data and plot the closed-loop system response for pitch and yaw
Now, use system matrices with coupling effect and use the controller without coupling
Repeat steps 4-6
The closed-loop response in this step does not have to meet the desired specifications
Build the SIMULINK model of the system
Repeat steps 4-6
Check whether your controller meets the desired specifications.
Save the data and plot the closed-loop system response for pitch and yaw
What happened when you neglect the coupling effect?
In this section, the state-feedback control is implemented on the Quanser Aero Experiment using the q_aero_2dof_lqr_control SIMULINK diagram shown in Figure 12 with QUARC.
Download the file into the quanser_aero folder that was used for Week 1.
Unlock both pitch and yaw axes to enable the full 2 DOF motion.
Open q_aero_2dof_lqr_control SIMULINK file.
Use pitch command (10 deg) only by changing Amp_y to zero.
Copy aerolqrrsp.mat
to your own folder and rename it as nocouple_pitch_only.
Examine the obtained closed-loop response and see if it matches the desired specifications.
Use a yaw command (45 deg) only by changing Amp_p to zero.
Run SIMULINK
Copy aero_lqr_rsp.mat
to your own folder and rename it as nocouple_yaw_only.
Examine the obtained closed-loop response and see if it matches the desired specifications
Use both pitch and yaw command
Run SIMULINK
Copy aerolqrrsp.mat to your own folder and rename it as nocouple_pitch_yaw.
Examine the obtained closed-loop response and see if it matches the desired specifications
Repeat above Pitch Only, Yaw Only and both Yaw and Pitch runs and rename the files as couple_####_###.
Close the Simulink. DO NOT SAVE THE CHANGE!
Did your controller successfully meet the specs? If not, why?
How does the coupling affect the performance of the controller?
How can we improve the controller?
where is the state defined in Equation (38)
is the reference command (or setpoint) state with the desired pitch and yaw angles, and , and
is the control input where is the front/pitch motor voltage and is the tail/yaw motor voltage.
Linear Quadratic Regulator (LQR) optimization can be used for finding the control gain parameters of the Quanser Aero Experiment flight control. Given the state-space representation, the LQR algorithm computes a control law to minimize the performance criterion or cost function:J=\int_0^\infty(x_{\rm ref}-x(t))^TQ(x_{\rm ref}-x(t))+u(t)^TRu(t)dt. \tag{45}
The design matrices and hold the penalties on the deviations of state variables from their setpoint and the control actions, respectively. When an element of is increased, therefore, the cost function increases the penalty associated with any deviations from the desired setpoint of that state variable, and thus the specific control gain will be larger. When the values of the matrix are increased, a larger penalty is applied to the aggressiveness of the control action, and the control gains are uniformly decreased.
Since there are four states , , and two control variables, . The setpoint, (Equation 43) is given above the control strategy used to minimize cost function J is thus given by
Various control software already has LQR optimization routines that can be used to generate the state feedback control gain . In order for the closed-loop response to satisfy certain time-domain specifications, the closed-loop system is typically simulated using its dynamic model, in software, first. This is an iterative process. By adjusting the weighting matrices and and then running the simulation, we can find a control that satisfies the user's requirements. Further, we must ensure that the control signal is smooth (i.e. does not chatter) and does not surpass the limits of the actuator.
LQR is used to find the state-feedback control gain ( is matrix) that will stabilize the Quanser Aero Experiment to the user's desired pitch and yaw angles. Our desired closed-loop response should match the following specifications. Use MATLAB command K = lqr(A,B,Q,R)
to obtain gain, , matrix.
Steady-state error: pitch ≤ 2 , yaw ≤ 2 .
Peak time: ≤ 2 s.
Percent Overshoot: ≤ 7.5%.
No actuator saturation: ≤ 24V and ≤ 24V .
Design , and . To start with try with following , and .
Q = diag([200 75 0 0 ]);
R = 0.01*eye(2,2);
K = lqr(A,B,Q,R)
Simulate the closed-loop response of the system with pitch-only command: . (Make sure to change deg to rad in SIMULINK)
Simulate the closed-loop response of the system with yaw only command: . (Make sure to change deg to rad in SIMULINK)
Simulate the closed-loop response of the system with pitch and yaw command: and . (Make sure to change deg to rad in SIMULINK)
If it fails to meet the specifications, tune and/or to meet the specifications
Now, design , and with the coupling effect
If it fails to meet the specifications, tune and/or to meet the specifications
Is there any systematic way to design and ?
Steady-state error: pitch ≤ 2 , yaw ≤ 2 .
Peak time: ≤ 2 s.
Percent Overshoot: ≤ 7.5%.
No actuator saturation: ≤ 24V and ≤ 24V .
Use the gain obtained in Part B. neglecting the coupling effect.
To build the model, click the down arrow on Monitor & Tune under the Hardware tab and then click Build for monitoring . This generates the controller code.
Click Connect button under Monitor & Tune and then run SIMULINK by clicking Start .
Use the gain obtained in Part B. with the coupling effect.