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?
The Quanser Aero Experiment can be configured as a conventional dual-rotor helicopter, as shown in Figure 1. The front rotor that is horizontal to the ground predominantly affects the motion about the pitch axis while the back or tail rotor mainly affects the motion about the yaw axis (about the shaft).
The tail rotor in helicopters is also known as the anti-torque rotor because it is used to reduce the torque that the main rotor generates about the yaw. Without this, the helicopter would be difficult to stabilize about the yaw axis. Because the rotors on the Quanser Aero Experiment are the same size and equidistant from each other, the tail rotor also generates a torque about the pitch axis. As a result, both the front and back/tail rotors generate a torque on each other.
The free-body diagram of the Quanser Aero Experiment is illustrated in Figure 2.
The following conventions are used for the modeling:
The equations of motion can be approximated after neglecting reaction torques from the rotors:
J_\theta\ddot{\theta}+D_\theta\dot{\theta}+K_\theta\theta=\tau_\theta \tag{1}
J_\psi\ddot{\psi}+ D_\psi\dot{\psi}=\tau_\psi \tag{2}
where the torques acting on the pitch and yaw axes are
\tau_\theta = K_{\theta \theta} V_{\theta} + K_{\theta \psi} V_{\psi} \tag{3}
\tau_\psi = K_{\psi \theta} V_{\theta} + K_{\psi \psi} V_{\psi} \tag{4}
The parameters used in the EOMs above are:
The total moment of inertia acting about the pitch and yaw axes are
J_\theta=J_{\rm body}+2J_{\rm prop} \tag{5}
J_\psi=J_{\rm body}+2J_{\rm prop}+J_{\rm yoke} \tag{6}
The step response of a first-order transfer function
Y(s) = \displaystyle \frac{K}{\tau s+1}U(s) \tag{7}
y(t_1)=y_1=(1-e^{-1})(y_{\rm ss}-y_0) +y_0 \tag{8a}
In this case we need to find
y(t_1)=y_1=e^{-1}(y_0 - y_{\rm ss})+ y_{ss} \tag{8b}
The free-oscillatory equation of motion of a second-order system is described by
J\ddot{\alpha}+D\dot{\alpha}+K\alpha =0 \tag{9}
The prototype second-order equation is defined
s^2+2\zeta\omega_ns+\omega_n^2 \tag{11}
\omega_n^2=\displaystyle\frac{K}{J}\tag{12}
2\zeta\omega_n=\displaystyle\frac{D}{J} \tag{13}
The period of the oscillations in a system response can be found using the equation
T_{\rm osc}=\displaystyle\frac{t_n-t_1}{n-1} \tag{14}
\omega_d=\displaystyle \frac{2\pi}{T_{\rm osc}} \tag{15}
and the undamped natural frequency is
\omega_n=\displaystyle\frac{\omega_d}{\sqrt{1-\zeta^2}} \tag{16}
The damping ratio of a second-order system can be found from its response. For a typical second-order underdamped system, the subsidence ratio (i.e. decrement ratio) is defined as
\delta = \displaystyle\frac{1}{n-1}\ln\frac{O_1}{O_n} \tag{17}
\zeta= \displaystyle\frac{\delta}{\sqrt{4\pi^2+\delta^2}} \tag{18}
Pitch Axis: By locking the yaw axis (using the Allen key supplied), this allows us to focus on the 1 DOF pitch-only system. Apply a short step voltage to mimic an impulse and get the free-oscillation response of the pitch. Remark that the impulse response is second-order free-oscillation response. The resulting 1 DOF pitch-only equations of motion is
J_\theta\ddot{\theta}+D_\theta\dot{\theta}+K_\theta\theta=0 \tag{19}
Taking its Laplace transform gives
J_\theta\left(\Theta(s)s^2-\theta(0^-)-\dot{\theta}(0^-)\right)+D_\theta\left(\Theta(s)-\theta(0^-)\right)+K_\theta\Theta(s)=0 \tag{20}
\Theta(s)=\displaystyle\frac{J_\theta}{J_\theta s^2+D_\theta s+K_\theta}\theta(0^-)=\frac{J_\theta D_\theta}{s^2+D_\theta/J_\theta +K_\theta/J_\theta}\theta(0^-) \tag{21}
The pitch free-oscillation transfer function matches the prototype second-order transfer function in Equation (10) Based on the measured damping ratio and natural frequency of the response, the friction (or stiffness) of the system is
K_\theta=J_\theta\omega_n^2 \tag{22}
and the viscous damping is
D_\theta=2\zeta\omega_nJ_\theta \tag{23}
Yaw Axis: The 1 DOF yaw-only equations of motion is
J_\psi\ddot\psi+D_\psi\dot\psi=0 \tag{24}
In terms of angular rate, the equation becomes
J_\psi\dot\omega_\psi(t)+D_\psi\omega_\psi(t)=0 \tag{25}
J_\theta(\Omega_\psi(s)s-\omega_\psi(0^-))+D_\psi\Omega_\psi(s)=0 \tag{26}
and solving for the speed we get
\Omega_\psi(s)=\displaystyle \frac{J_\psi}{J_\psi s+D_\psi}\omega_\psi(0^-)=\frac{J_\psi/D_\psi}{J_\psi/D_\psi s+1}\omega_\psi(0^-) \tag{27}
The yaw free-oscillation transfer function matches the prototype first-order transfer function in Equation (7). Based on the measured time constant of the response, its damping can be found with
D_\psi=\displaystyle\frac{J_\psi}{\tau} \tag{28}
By locking the yaw axis, this allows us to focus on the 1 DOF pitch-only system, i.e., eliminating any motion introduced in the yaw axis when applying a voltage to the pitch rotor. The equations of motion for the 1-DOF actuated system is
J_\theta\ddot\theta+D_\theta\dot\theta+K_\theta\theta=K_{\theta\theta}V_\theta \tag{29}
Solving for the thrust gain we get
K_{\theta\theta}=\displaystyle \frac{J_\theta\ddot\theta+D_\theta\dot\theta+K_\theta\theta}{V_\theta} \tag{30}
J_\psi\ddot\psi+D_\psi\dot\psi=K_{\psi\psi}V_\psi \tag{31}
or,
J_\psi\dot\omega_\psi+D_\psi\omega_\psi=K_{\psi\psi}V_\psi \tag{32}
K_{\psi\psi}=\displaystyle\frac{J_\psi\dot\omega_\psi+D_\psi\omega_\psi}{V_\psi} \tag{33}
J_\theta\ddot\theta+D_\theta\dot\theta+K_\theta\theta=K_{\theta\psi}V_\psi \tag{34}
K_{\theta\psi}=\displaystyle\frac{J_\theta\dot\omega_\theta+D_\theta\omega_{\theta}}{V_\psi} \tag{35}
Similarly, to identify the cross-torque gain parameter that is generated about the yaw axis from a pitch torque (i.e. voltage applied to the front rotor), we have the equation
J_\psi\ddot\psi+D_\psi\dot\psi=K_{\psi\theta}V_\theta \tag{36}
and the gain can be found using
K_{\psi\theta}=\displaystyle\frac{J_{\psi}\dot\omega_\psi+D_\psi\omega_{\psi}}{V_\theta} \tag{37}
First download the zip file below and extract it in the desktop:
1) Lock the yaw axis to enable motions about the pitch axis only. (place the allen key to lock yaw axis and make sure that the pitch axis is free to rotate, loosen two screws)
2) Open the q_aero_free_osc_response_pitch SIMULINK file.
3) Select a (-20) V impulse
4) Select simulation time 30 sec.
7) Copy aero_pitch_free_osc_rsp.mat
to your folder.
Data is saved in following order:
1: Time (s)
2: Pitch input (V)
3: Pitch position (rad)
4: Pitch speed (rad/s)
8) Close the SIMULINK model. DO NOT SAVE THE CHANGE
1) Unlock the yaw axis
2) Lock the pitch axis
3) Open the q_aero_free_osc_response_yaw SIMULINK file.
4) Apply an impulse of 20V to the tail rotor
5) Select simulation time 10 sec.
8) Copy aero_yaw_free_osc_rsp.mat
to your folder
Data is saved in following order:
1: Time (s)
2: Yaw input (V)
3: Yaw position (rad)
4: Yaw speed (rad/s)
5: Yaw acceleration (rad/s^2)
9) Close the SIMULINK model. DO NOT SAVE THE CHANGE.
1) Open the q_aero_step_response_yaw SIMULINK file.
2) Select a step voltage 15V
3) Select simulation time 40 sec.
6) Copy aero_yaw_step_rsp.mat
to your folder
Data is saved in following order:
1: Time
2: Yaw input (V)
3: Yaw position (rad)
4: Yaw Speed (rad/s)
7) Close the SIMULINK model. DO NOT SAVE THE CHANGE.
1) Unlock both the pitch and yaw axes to enable the full 2 DOF motion.
2) Open the q_aero_step_response_pitch_from_yaw SIMULINK file.
3) Select yaw step voltage to 12V and pitch to 0V.
4) Select simulation time 40 sec.
A pitch up motion must be seen due to torque from the tail rotor.
7) Copy aero_pitch_from_yaw_step_rsp.mat
to your folder
Data is saved in following order:
1: Time (s)
2: Yaw input (V)
3: Pitch Position (rad)
4: Pitch Speed (rad/s)
8) Close the SIMULINK model. DO NOT SAVE THE CHANGE.
1) Open the q_aero_step_response_yaw_from_pitch SIMULINK file.
2) Select pitch step voltage to 12V and yaw to 0V.
3) Select simulation time 40 sec.
A yaw motion must be seen due to torque from front motor.
6) Copy aero_yaw_from_pitch_step_rsp.mat
to your folder
Data is saved in following order:
1: Time (s)
2: Pitch input (V)
3: Yaw Position (rad)
4: Yaw Speed (rad/s)
7) Close the SIMULINK model. DO NOT SAVE THE CHANGE.
Find the natural frequency and damping ratio from the impulse response of the pitch axis (HINT: first find the peaks and use equation 16, 17, and 18). Then find the stiffness and viscous damping coefficient about the pitch axis (Hint: equation 22,23).
The Quanser Aero Experiment can be configured as a conventional dual-rotor helicopter, as shown in Figure 1. The front rotor that is horizontal to the ground predominantly affects the motion about the pitch axis while the back or tail rotor mainly affects the motion about the yaw axis (about the shaft).
The tail rotor in helicopters is also known as the anti-torque rotor because it is used to reduce the torque that the main rotor generates about the yaw. Without this, the helicopter would be difficult to stabilize about the yaw axis. The rotors on the Quanser Aero Experiment are the same size and equidistant from each other, the tail rotor also generates a torque about the pitch axis. As a result, both the front and back/tail rotors generate torques on each other.
The Quanser 2D AERO is designed with its mass distribution well balanced from the front and back rotors such that its center of gravity is at the mid-point between the two rotors. However, a vertical offset of the cg location is included to result in pitch stiffness from the pendulum effect as depicted in the Figure.
The free-body diagram of the Quanser Aero Experiment is illustrated in Figure 2.
The following conventions are used for the modeling:
The equations of motion can be approximated as:
J_\theta\ddot{\theta}+D_\theta\dot{\theta}+K_\theta\theta=\tau_\theta \tag{1}
J_\psi\ddot{\psi}+ D_\psi\dot{\psi}=\tau_\psi \tag{2}
where the torques acting on the pitch and yaw axes are
\tau_\theta = K_{\theta \theta} V_{\theta} + K_{\theta \psi} V_{\psi} \tag{3}
\tau_\psi = K_{\psi \theta} V_{\theta} + K_{\psi \psi} V_{\psi} \tag{4}
The parameters used in the EOMs above are:
The total moment of inertia acting about the pitch and yaw axes are
J_\theta=J_{\rm body}+2J_{\rm prop} \tag{5}
J_\psi=J_{\rm body}+2J_{\rm prop}+J_{\rm yoke} \tag{6}
The step response of a first-order transfer function
Y(s) = \displaystyle \frac{K}{\tau s+1}U(s) \tag{7}
y(t_1)=y_1=(1-e^{-1})(y_{\rm ss}-y_0) +y_0 \tag{8a}
To find the time constant from first-order response from an impulse (or short step) as depicted in Figure 4, find the time it takes for the response to reach 37% of its initial pulse response.
In this case we need to find
y(t_1)=y_1=e^{-1}(y_0 - y_{ss})\tag{8b}
The free-oscillatory equation of motion of a second-order system is described by
J\ddot{\alpha}+D\dot{\alpha}+K\alpha =0 \tag{9}
The prototype second-order equation is defined
s^2+2\zeta\omega_ns+\omega_n^2 \tag{11}
\omega_n^2=\displaystyle\frac{K}{J}\tag{12}
2\zeta\omega_n=\displaystyle\frac{D}{J} \tag{13}
The period of the oscillations in a system response can be found using the equation
T_{\rm osc}=\displaystyle\frac{t_n-t_1}{n-1} \tag{14}
\omega_d=\displaystyle \frac{2\pi}{T_{\rm osc}} \tag{15}
and the undamped natural frequency is
\omega_n=\displaystyle\frac{\omega_d}{\sqrt{1-\zeta^2}} \tag{16}
The damping ratio of a second-order system can be found from its response. For a typical second-order underdamped system, the subsidence ratio (i.e. decrement ratio) is defined as
\delta = \displaystyle\frac{1}{n-1}\ln\frac{O_1}{O_n} \tag{17}
\zeta= \displaystyle\frac{\delta}{\sqrt{4\pi^2+\delta^2}} \tag{18}
Pitch Axis: By locking the yaw axis (using the Allen key supplied), this allows us to focus on the 1 DOF pitch-only system. Apply a short step voltage to mimic an impulse and get the free-oscillation response of the pitch. Remark that the impulse response is second-order free-oscillation response. The resulting 1 DOF pitch-only equations of motion is
J_\theta\ddot{\theta}+D_\theta\dot{\theta}+K_\theta\theta=0 \tag{19}
Taking its Laplace transform gives
J_\theta\left(\Theta(s)s^2-\theta(0^-)-\dot{\theta}(0^-)\right)+D_\theta\left(\Theta(s)-\theta(0^-)\right)+K_\theta\Theta(s)=0 \tag{20}
\Theta(s)=\displaystyle\frac{J_\theta}{J_\theta s^2+D_\theta s+K_\theta}\theta(0^-)=\frac{J_\theta D_\theta}{s^2+D_\theta/J_\theta +K_\theta/J_\theta}\theta(0^-) \tag{21}
The pitch free-oscillation transfer function matches the prototype second-order transfer function in Equation (10) Based on the measured damping ratio and natural frequency of the response, the friction (or stiffness) of the system is
K_\theta=J_\theta\omega_n^2 \tag{22}
and the viscous damping is
D_\theta=2\zeta\omega_nJ_\theta \tag{23}
Yaw Axis: The 1 DOF yaw-only equations of motion is
J_\psi\ddot\psi+D_\psi\dot\psi=0 \tag{24}
In terms of angular rate, the equation becomes
J_\psi\dot\omega_\psi(t)+D_\psi\omega_\psi(t)=0 \tag{25}
J_\theta(\Omega_\psi(s)s-\omega_\psi(0^-))+D_\psi\Omega_\psi(s)=0 \tag{26}
and solving for the speed we get
\Omega_\psi(s)=\displaystyle \frac{J_\psi}{J_\psi s+D_\psi}\omega_\psi(0^-)=\frac{J_\psi/D_\psi}{J_\psi/D_\psi s+1}\omega_\psi(0^-) \tag{27}
The yaw free-oscillation transfer function matches the prototype first-order transfer function in Equation (7). Based on the measured time constant of the response, its damping can be found with
D_\psi=\displaystyle\frac{J_\psi}{\tau} \tag{28}
By locking the yaw axis, this allows us to focus on the 1 DOF pitch-only system, i.e., eliminating any motion introduced in the yaw axis when applying a voltage to the pitch rotor. The equations of motion for the 1-DOF actuated system is
J_\theta\ddot\theta+D_\theta\dot\theta+K_\theta\theta=K_{\theta\theta}V_\theta \tag{29}
Solving for the thrust gain we get
K_{\theta\theta}=\displaystyle \frac{J_\theta\ddot\theta+D_\theta\dot\theta+K_\theta\theta}{V_\theta} \tag{30}
J_\psi\ddot\psi+D_\psi\dot\psi=K_{\psi\psi}V_\psi \tag{31}
or,
J_\psi\dot\omega_\psi+D_\psi\omega_\psi=K_{\psi\psi}V_\psi \tag{32}
K_{\psi\psi}=\displaystyle\frac{J_\psi\dot\omega_\psi+D_\psi\omega_\psi}{V_\psi} \tag{33}
J_\theta\ddot\theta+D_\theta\dot\theta+K_\theta\theta=K_{\theta\psi}V_\psi \tag{34}
K_{\theta\psi}=\displaystyle\frac{J_\theta\dot\omega_\theta+D_\theta\omega_{\theta}}{V_\psi} \tag{35}
Similarly, to identify the cross-torque gain parameter that is generated about the yaw axis from a pitch torque (i.e. voltage applied to the front rotor), we have the equation
J_\psi\ddot\psi+D_\psi\dot\psi=K_{\psi\theta}V_\theta \tag{36}
and the gain can be found using
K_{\psi\theta}=\displaystyle\frac{J_{\psi}\dot\omega_\psi+D_\psi\omega_{\psi}}{V_\theta} \tag{37}
First download the zip file below and extract it in the desktop:
1) Lock the yaw axis to enable motions about the pitch axis only. (place the allen key to lock yaw axis and make sure that the pitch axis is free to rotate, loosen two screws)
2) Open the q_aero_free_osc_response_pitch SIMULINK file.
3) Impulse of -20V for 1.5s.
4) Select simulation time 30 sec.
7) Copy aero_pitch_free_osc_rsp.mat
to your folder.
Data is saved in following order:
1: Time (s)
2: Pitch input (V)
3: Pitch position (rad)
4: Pitch speed (rad/s)
5: Pitch acceleration (rad/s^2)
8) Close the SIMULINK model. DO NOT SAVE THE CHANGE
1) Open the q_aero_step_response_pitch SIMULINK file.
2) Select a step voltage 24V, (amplitude to 24)
3) Select simulation time 30 sec.
6) Copy aero_pitch_step_rsp.mat
to your folder.
Data is saved in following order:
1: Time
2: Pitch input (V)
3: Pitch position (rad)
4: Pitch Speed (rad/s)
7) Close the SIMULINK model. DO NOT SAVE THE CHANGE.
1) Unlock the yaw axis
2) Lock the pitch axis
3) Open the q_aero_free_osc_response_yaw SIMULINK file.
4) Apply an impulse of 20V to the tail rotor for 1s.
5) Select simulation time 10 sec.
8) Copy aero_yaw_free_osc_rsp.mat
to your folder
Data is saved in following order:
1: Time (s)
2: Yaw input (V)
3: Yaw position (rad)
4: Yaw speed (rad/s)
5: Yaw acceleration (rad/s^2)
9) Close the SIMULINK model. DO NOT SAVE THE CHANGE.
1) Open the q_aero_step_response_yaw SIMULINK file.
2) Select a step voltage 15V
3) Select simulation time 60 sec.
6) Copy aero_yaw_step_rsp.mat
to your folder
Data is saved in following order:
1: Time
2: Yaw input (V)
3: Yaw position (rad)
4: Yaw Speed (rad/s)
7) Close the SIMULINK model. DO NOT SAVE THE CHANGE.
1) Unlock both the pitch and yaw axes to enable the full 2 DOF motion.
2) Open the q_aero_step_response_pitch_from_yaw SIMULINK file.
3) Select yaw step voltage to 12V and pitch to 0V.
4) Select simulation time 40 sec.
A pitch up motion must be seen due to torque from the tail rotor.
7) Copy aero_pitch_from_yaw_step_rsp.mat
to your folder
Data is saved in following order:
1: Time (s)
2: Yaw input (V)
3: Pitch Position (rad)
4: Pitch Speed (rad/s)
8) Close the SIMULINK model. DO NOT SAVE THE CHANGE.
1) Open the q_aero_step_response_yaw_from_pitch SIMULINK file.
2) Select pitch step voltage to 12V and yaw to 0V.
3) Select simulation time 40 sec.
A yaw motion must be seen due to torque from front motor.
6) Copy aero_yaw_from_pitch_step_rsp.mat
to your folder
Data is saved in following order:
1: Time (s)
2: Pitch input (V)
3: Yaw Position (rad)
4: Yaw Speed (rad/s)
7) Close the SIMULINK model. DO NOT SAVE THE CHANGE.
Find the natural frequency and damping ratio from the impulse response of the pitch axis (HINT: first find the peaks and use equation 16, 17, and 18). Then find the stiffness and viscous damping coefficient about the pitch axis (Hint: equation 22,23).
K_{\psi\psi}=\displaystyle\frac{J_\psi\dot\omega_\psi+D_\psi\omega_\psi}{V_\psi} \tag{33}
K_{\theta\psi} = \displaystyle\frac{\theta_{ss}K_{\theta}}{V_\psi} \tag{39}
K_{\psi\theta}=\displaystyle\frac{J_\psi\dot\omega_\psi+D_\psi\omega_\psi}{V_\theta} \tag{33}
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.
The helicopter is horizontal and parallel with the ground when the pitch angle is zero, i.e., .
The pitch angle increases positively, , when the front rotor is moved upwards and the body rotates clockwise (CW) about the Y axis.
The yaw angle increases positively, , when the body rotates counter-clockwise (CCW) about the Z axis.
Pitch increases, , when the front rotor voltage is positive .
Yaw increases, , when the back (or tail) rotor voltage is positive, .
When voltage is applied to the pitch motor, , the speed of rotation results in a force, that acts normal to the body at a distance from the pitch axis. The rotation of the propeller generates a torque about the pitch rotor motor shaft which is in turn seen about the yaw axis. Thus, rotating the pitch propeller does not only cause motion about the pitch axis but also about the yaw axis. As described earlier, that is why conventional helicopters include a tail, or anti-torque, rotor to compensate for the torque generated about the yaw axis by the large, main rotor.
Similarly, the yaw motor causes a force that acts on the body at a distance from the yaw axis as well as a torque about the pitch axis.
: the total moment of inertia about the pitch axis
: the damping about the pitch axis
: the stiffness about the pitch axis
: the total moment of inertia about the yaw axis
: the damping about the pitch axis
: torque thrust gain from the pitch rotor
: torque thrust gain from the yaw rotor
: cross-torque thrust gain acting on the pitch from the yaw rotor
: cross-torque thrust gain acting on the yaw from the pitch rotor
: voltage applied to the pitch rotor
: voltage applied to the yaw rotor motor
Expressing the rotor as a single-point mass, the inertia acting about the pitch or yaw axis from a single rotor is . Modeling the helicopter body as a cylinder rotating about its center, the inertia is . Finally, the forked yoke that rotates about the yaw axis can be approximated as a cylinder rotating about its center as well and expressed as . Evaluating the moment of inertia using the parameters listed in the Quanser Aero Experiment User Manual gives:
where K is the DC or steady-state gain and τ is the time constant as illustrated in Figure 3. This is for a system with and .
To obtain the time constant from the response, find the time it takes to reach or 63% of its final steady-state value:
The time constant is , where is the start time of the step and is the time it takes to reach 63% of the final value, as illustrated in Figure 3.
To find the time constant from first-order response from an impulse (or short step) as depicted in Figure 4, find the time it takes for the response to reach or 37% of its final steady-state value.
and the time constant is
is shown in Figure 4. Assuming the initial conditions , the Laplace transform of Equation (9) is \alpha(s)=\displaystyle{\frac{\alpha_0/J}{s^2+D/Js+K/J}} \tag{10}
where is the damping ratio and is the natural frequency. Equating the characteristic equation in Equation (10) to this gives
where is the time of the oscillation, is the time of the first peak, and is the number of oscillations considered. From this, the damped natural frequency (in radians per second) is
where is the peak of the first oscillation and is the peak of the oscillation. Note that > , as this is a decaying response. The damping ratio can then be found using
The viscous damping coefficients acting about the pitch and yaw axes, and in Equation (1) and Equation (2), can be found from the free-oscillation response. The free-oscillation response about the pitch and about the yaw are different, however.
Assuming the initial velocity is zero, , and solving for position we get
where . Taking its Laplace transform
Remark that this is the thrust torque gain parameter. To force thrust gain would be , where is the distance between the helicopter pivot and the center of the pitch rotor. Similarly, to find the thrust gain acting on the yaw axis only system, lock the pitch axis, and apply a voltage to the tail rotor. This system is represented by
where is the angular rate of the yaw axis. The yaw torque thrust gain is
The cross-torque thrust parameters, and in Equation (3) and (4), represent the coupling between the axes. To find the cross-torque acting on the pitch axis from a torque applied to the tail rotor, unlock both pitch and yaw axes such that it is free to move in 2 DOF, apply a voltage to the tail rotor, and examine the response of the pitch. The equations representing these dynamics when , are
Putting this in terms of angular rate, , and solving for the gain we get
5) 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.
6) Click Connect button under Monitor & Tune and then run SIMULINK by clicking Start .
6) 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.
7) Click Connect button under Monitor & Tune and then run SIMULINK by clicking Start .
4) 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.
5) Click Connect button under Monitor & Tune and then run SIMULINK by clicking Start .
5) 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.
6) Click Connect button under Monitor & Tune and then run SIMULINK by clicking Start .
4) 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.
5) Click Connect button under Monitor & Tune and then run SIMULINK by clicking Start .
Find the time constant from the yaw pulse response and obtain the damping . Use First-order impulse decaying response. To find the time constant, examine the decaying response that starts at an initial maximum speed and settle down to 0 rad/s (use equation 8b). If data obtained does not fully shows the 37% try estimate the value by curve fitting.
Find the thrust and cross-torque thrust gain parameters by performing discrete derivative to peak values or from the steady state of step response.
The system is in static equilibrium when it is horizontal and parallel to the ground with zero pitch angle. Any change in pitch angle gives rise to a restoring moment from the pendulum effect given by restoring pitch moment due to pitch angle change =
The helicopter is horizontal and parallel with the ground when the pitch angle is zero, i.e., .
The pitch angle increases positively, , when the front rotor is moved upwards and the body rotates clockwise (CW) about the Y axis.
The yaw angle increases positively, , when the body rotates counter-clockwise (CCW) about the Z axis.
Pitch increases, , when the front rotor voltage is positive .
Yaw increases, , when the back (or tail) rotor voltage is positive, .
When voltage is applied to the pitch motor, , the speed of rotation results in a force, that acts normal to the body at a distance from the pitch axis. The rotation of the propeller generates a torque about the pitch rotor motor shaft which is in turn seen about the yaw axis. Thus, rotating the pitch propeller does not only cause motion about the pitch axis but also about the yaw axis. As described earlier, that is why conventional helicopters include a tail, or anti-torque, rotor to compensate for the torque generated about the yaw axis by the large, main rotor.
Similarly, the yaw motor causes a force that acts on the body at a distance from the yaw axis as well as a torque about the pitch axis.
: the total moment of inertia about the pitch axis
: the damping about the pitch axis
: the stiffness about the pitch axis
: the total moment of inertia about the yaw axis
: the damping about the pitch axis
: torque thrust gain from the pitch rotor
: torque thrust gain from the yaw rotor
: cross-torque thrust gain acting on the pitch from the yaw rotor
: cross-torque thrust gain acting on the yaw from the pitch rotor
: voltage applied to the pitch rotor
: voltage applied to the yaw rotor motor
Expressing the rotor as a single-point mass, the inertia acting about the pitch or yaw axis from a single rotor is . Modeling the helicopter body as a cylinder rotating about its center, the inertia is . Finally, the forked yoke that rotates about the yaw axis can be approximated as a cylinder rotating about its center as well and expressed as . Evaluating the moment of inertia using the parameters listed in the Quanser Aero Experiment User Manual gives:
where K is the DC or steady-state gain and τ is the time constant as illustrated in Figure 3. This is for a system with and .
To obtain the time constant from the response, find the time it takes to reach or 63% of its final steady-state value:
The time constant is , where is the start time of the step and is the time it takes to reach 63% of the final value, as illustrated in Figure 3.
and the time constant is
is shown in Figure 4. Assuming the initial conditions , the Laplace transform of Equation (9) is \alpha(s)=\displaystyle{\frac{\alpha_0/J}{s^2+D/Js+K/J}} \tag{10}
where is the damping ratio and is the natural frequency. Equating the characteristic equation in Equation (10) to this gives
where is the time of the oscillation, is the time of the first peak, and is the number of oscillations considered. From this, the damped natural frequency (in radians per second) is
where is the peak of the first oscillation and is the peak of the oscillation. Note that > , as this is a decaying response. The damping ratio can then be found using
The viscous damping coefficients acting about the pitch and yaw axes, and in Equation (1) and Equation (2), can be found from the free-oscillation response. The free-oscillation response about the pitch and about the yaw are different, however.
Assuming the initial velocity is zero, , and solving for position we get
where . Taking its Laplace transform
Remark that this is the thrust torque gain parameter. To force thrust gain would be , where is the distance between the helicopter pivot and the center of the pitch rotor. Similarly, to find the thrust gain acting on the yaw axis only system, lock the pitch axis, and apply a voltage to the tail rotor. This system is represented by
where is the angular rate of the yaw axis. The yaw torque thrust gain is
The cross-torque thrust parameters, and in Equation (3) and (4), represent the coupling between the axes. To find the cross-torque acting on the pitch axis from a torque applied to the tail rotor, unlock both pitch and yaw axes such that it is free to move in 2 DOF, apply a voltage to the tail rotor, and examine the response of the pitch. The equations representing these dynamics when , are
Putting this in terms of angular rate, , and solving for the gain we get
5) 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.
6) Click Connect button under Monitor & Tune and then run SIMULINK by clicking Start .
4) 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.
5) Click Connect button under Monitor & Tune and then run SIMULINK by clicking Start .
6) 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.
7) Click Connect button under Monitor & Tune and then run SIMULINK by clicking Start .
4) 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.
5) Click Connect button under Monitor & Tune and then run SIMULINK by clicking Start .
5) 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.
6) Click Connect button under Monitor & Tune and then run SIMULINK by clicking Start .
4) 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.
5) Click Connect button under Monitor & Tune and then run SIMULINK by clicking Start .
Find the time constant from the yaw pulse response and obtain the damping . Use First-order impulse decaying response. To find the time constant, examine the decaying response that starts at an initial maximum speed and settle down to 0 rad/s (use equation 8b). If data obtained does not fully shows the 37% of try estimate the value by curve fitting.
Find the thrust and cross-torque thrust gain parameters K_{\theta\theta} = \displaystyle\frac{\theta_{ss}K_{\theta}}{V_\theta} \tag{38}
Hint: can be obtained by using MATLAB function diff(psi_dot)/h, where h is sampling time. Compute by using the psi_ddot(start:end), psi_dot(start:end) and V_psi(start:end) from start to end of step input. Do matrix division and you should get one value.