AE4610
  • Welcome
  • Experiments
  • Lab 0: MATLAB & SIMULINK
  • Lab 1: Rotary Servo Base
    • A. Integration (Week 1)
    • B. Modeling (Week 1)
    • C. Control Design (Week 2)
    • D. Controller Implementation & Evaluation (Week 3)
  • Lab 2: 3 DOF Gyroscope
    • A & B. Modeling and Control Design (Week 1)
    • C. Controller Implementation (Week 2)
  • Lab 3: Rotary Flexible Link
    • A. System Identification (Week 1)
    • B & C. Control Design and Controller Implementation (Week 2)
  • Lab 4: Rotary Inverted Pendulum
    • A & B. Modeling and Balance Control
    • C. Swing-up Control (Demo)
  • Final Project
  • Archive
    • Old Lab 1 Model Validation
    • Problem Set
    • DC Motor
    • Lab 1: Rotary Servo Base (Older Version)
      • A. Integration (Week 1)
      • B. Modelling (Week 1)
      • C. Position Control (Week 2)
    • Quadcopter
    • Gyroscope
    • Inverted Pendulum
    • 3DOF Helicopter
    • Torsional Pendulum
    • Aero LQR
      • A. System Identification
      • A. System Identification (Week 1) last check
      • B. Control Design & Implementation (Week 2)
    • Rotary Gyro
      • Rotary Gyro
    • 2 DOF AERO
      • A. System Identification
      • B. Control Design
      • C. Controller Implementation
    • Copy of Lab 4: Rotary Inverted Pendulum
      • Week 1
      • Week 2
Powered by GitBook
On this page
  • Objective
  • Equipment
  • A. Modeling
  • Rotary Inverted Pendulum Model
  • Model Convention
  • Nonlinear Equations of Motion
  • Linearization
  • Linearization of Inverted Pendulum Equations
  • Analysis: Modeling
  • B. Balance Control
  • Specification
  • Stability
  • Controllability
  • Companion Matrix
  • Pole Placement Theory
  • Desired Poles
  • Simulation Model with Feedback
  • B.1 Experiment: Designing the Balance Control
  • B.2 Experiment: Simulating the Balance Control
  • B.3 Experiment: Implementing the Balance Controller
  • Results for Report
  • A) Modeling
  • B.1) Balance Control Design
  • B.2) Balance Control Simulation
  • B.3) Balance Controller Implementation
  • Questions for Report
  • A) Modeling
  • B.1) Balance Control Design
  • Appendix
  • Table A Main Rotary Servo Base Unit Specifications
  • Reference

Was this helpful?

Export as PDF
  1. Lab 4: Rotary Inverted Pendulum

A & B. Modeling and Balance Control

Objective

The objectives of this laboratory experiment are as follows:

  1. Obtain the linear state-space representation of the rotary pendulum system.

  2. Design a controller that balances the pendulum in its upright position using Pole Placement.

  3. Simulate the closed-loop system to ensure the given specifications are met.

  4. Implement the balance controller on the Quanser Rotary Pendulum system and evaluate its performance.

Equipment

A. Modeling

This experiment involves modeling of the rotary inverted pendulum.

Rotary Inverted Pendulum Model

A picture of the rotary servo base with rotary pendulum module is shown in Fig 1. The numbered components in Fig. 1 are listed in Table 1 along with the numerical values of the system parameters in Table 2.

Table 1 Rotary Pendulum components (Figure 1)

ID#
Component

1

Rotary Servo

2

Thumbscrews

3

Rotary Arm

4

Shaft Housing

5

Shaft

6

Pendulum T-Fitting

7

Pendulum Link

8

Pendulum Encoder Connector

9

Pendulum Encoder

Table 2 Main Parameters associated with the Rotary Pendulum module

Symbol
Description
Value
Unit

Mass of pendulum

0.127

Total length of pendulum

0.337

Distance from pivot to center of mass

0.156

Pendulum moment of intertia about center of mass

0.0012

Pendulum viscous damping coeffi­cient as seen at the pivot axis

0.0024

Mass of rotary arm with two thumb screws

0.257

Rotary arm length from pivot to tip

0.216

Rotary arm length from pivot to center of mass

0.0619

Rotary arm moment of inertia about its center of mass

9.98 x 10^-4

Rotary arm viscous damping coeffi­cient as seen at the pivot axis

0.0024

Rotary arm moment of inertia about pivot

0.0020

Pendulum encoder resolution

4096

Model Convention

A simplified form of the inverted pendulum system used in the development of the mathematical model is shown in Figure 2. The rotary arm pivot is attached to the Rotary Servo system. The arm has a length of L_\rm{r}, a moment of inertia of J_\rm{r}, and its angle, θ\bm\thetaθ, increases positively when it rotates counterclockwise (CCW). The servo (and thus the arm) should turn in the CCW direction when the control voltage is positive, i.e. V_\rm{m} > 0.

The pendulum link is connected to the end of the rotary arm. It has a total length of LpL_pLp​ and its center of mass is at {L_\rm{p}}/{2} . The moment of inertia about its center of mass is J_\rm{p}. The inverted pendulum angle, α\bm\alphaα, is zero when it is perfectly upright in the vertical position and increases positively when rotated CCW.

Nonlinear Equations of Motion

Instead of using classical (Newtonian) mechanics, the Lagrange method is used to find the equations of motion of the system. This systematic method is often used for more complicated systems such as robot manipulators with multiple joints.

Specifically, the equations that describe the motions of the rotary arm and the pendulum with respect to the servo motor voltage, i.e., the dynamics, are obtained using the Euler-Lagrange equation:

ddt∂L∂qi˙−∂L∂qi=Qi(1)\frac{d}{dt}\frac{\partial L}{\partial \dot{q_i}} - \frac{\partial L}{\partial q_i} = Q_i \qquad \qquad \tag{1}dtd​∂qi​˙​∂L​−∂qi​∂L​=Qi​(1)

The variables qi\bm q_iqi​'s are called generalized coordinates.θi\theta_iθi​'s are called generalised force and L is the Langrangian (difference between Kinetic and Potential energies of the system). For this system let

q(t)=[θ(t)α(t)]T(2)q(t) =\begin{bmatrix} \theta(t) & \alpha(t) \end{bmatrix}^T \qquad \qquad \tag{2}q(t)=[θ(t)​α(t)​]T(2)

where, as shown in Figure 2, θ(t)\theta(t)θ(t) is the rotary arm angle and α(t)\alpha(t)α(t) is the inverted pendulum angle. The corresponding angular rates are

q˙(t)=[dθ(t)dtdα(t)dt]T(3)\dot{q}(t)=\begin{bmatrix} \displaystyle \frac{d\theta(t)}{dt} & \displaystyle\frac{d\alpha(t)}{dt} \end{bmatrix} ^T \qquad \qquad \tag{3}q˙​(t)=[dtdθ(t)​​dtdα(t)​​]T(3)

With the generalized coordinates defined, the Euler-Lagrange equations for the rotary pendulum system are

ddt∂L∂θ˙−∂L∂θ=Q1(4a)\frac{d}{dt} \frac{\partial L}{\partial \dot{\theta}} - \frac{\partial L}{\partial \theta} = Q_1 \qquad \qquad \tag{4a}dtd​∂θ˙∂L​−∂θ∂L​=Q1​(4a)
ddt∂L∂α˙−∂L∂α=Q2(4b)\frac{d}{dt}\frac{\partial L}{\partial \dot{\alpha}} - \frac{\partial L}{\partial \alpha} = Q_2 \qquad \qquad \tag{4b}dtd​∂α˙∂L​−∂α∂L​=Q2​(4b)

The Lagrangian of the system is described by

L=T−V(5)L = T - V \qquad \qquad \tag{5}L=T−V(5)

where TTT is the total kinetic energy of the system and VVV is the total potential energy of the system. Thus the Lagrangian is the difference between a system’s kinetic and potential energies.

The generalized forces QiQ_iQi​ are used to describe the nonconservative forces (e.g. friction) applied to a system with respect to the generalized coordinates. In this case, the generalized force acting on the rotary arm is

Q1=τ−Brθ˙(6a)Q_1 = \tau - B_\mathrm{r}\dot{\theta} \qquad \qquad \tag{6a}Q1​=τ−Br​θ˙(6a)

and acting on the pendulum is

Q2=−Bpα˙(6b)Q_2 = -B_\mathrm{p}\dot{\alpha} \qquad \qquad\tag{6b}Q2​=−Bp​α˙(6b)

Once expressions for the kinetic and potential energy are obtained and the Lagrangian is found, then the task is to compute various derivatives to get the EOMs. After going through this process, the nonlinear equations of motion for the Rotary Pendulum are:​

(mpLr2+14mpLp2−14mpLp2cos⁡2(α)+Jr)θ¨−(12mpLpLrcos⁡(α))α¨+(12mpLp2sin⁡(α)cos⁡(α))θ˙α˙+(12mpLpLrsin⁡(α))α˙2=τ−Brθ˙(7)\displaystyle\left (m_pL_r^2 + \frac{1}{4}m_pL_p^2 - \frac{1}{4}m_pL_p^2 \cos^2(\alpha)+J_r \right )\ddot{\theta} - \left (\frac{1}{2}m_pL_pL_r\cos(\alpha) \right)\ddot{\alpha} \\+ \displaystyle\left(\frac{1}{2}m_pL_p^2\sin(\alpha)\cos(\alpha)\right)\dot{\theta}\dot{\alpha} + \left( \frac{1}{2}m_pL_pL_r\sin(\alpha)\right)\dot{\alpha}^2 = \tau - B_r\dot{\theta} \qquad \qquad \tag{7}(mp​Lr2​+41​mp​Lp2​−41​mp​Lp2​cos2(α)+Jr​)θ¨−(21​mp​Lp​Lr​cos(α))α¨+(21​mp​Lp2​sin(α)cos(α))θ˙α˙+(21​mp​Lp​Lr​sin(α))α˙2=τ−Br​θ˙(7)
(−12mpLpLrcos⁡(α))θ¨+(Jp+14mpLp2)α¨−(14mpLp2cos⁡(α)sin⁡(α))θ˙2−12mpLpgsin⁡(α)=−Bpα˙(8)\displaystyle{\left(-\frac{1}{2}m_pL_pL_r\cos(\alpha) \right)\ddot{\theta} + \left(J_p + \frac{1}{4}m_pL_p^2 \right) \ddot{\alpha} - \left(\frac{1}{4} m_pL_p^2\cos(\alpha)\sin(\alpha)\right)\dot{\theta}^2} \\ -\frac{1}{2} m_pL_pg\sin(\alpha) = -B_p\dot{\alpha} \qquad \qquad \tag{8}(−21​mp​Lp​Lr​cos(α))θ¨+(Jp​+41​mp​Lp2​)α¨−(41​mp​Lp2​cos(α)sin(α))θ˙2−21​mp​Lp​gsin(α)=−Bp​α˙(8)
τ=ηgKgηmkt(Vm−Kgkmθ˙)Rm(9)\tau = \displaystyle\frac{\eta_gK_g\eta_mk_t(V_m - K_gk_m\dot{\theta})}{R_m} \qquad \qquad \tag{9}τ=Rm​ηg​Kg​ηm​kt​(Vm​−Kg​km​θ˙)​(9)

Linearization

Linearization of a nonlinear function about a selected point is obtained by retaining upto first order term in the Taylor Series expansion of the function about the selected point. For example, linearization of a two variable nonlinear function f(z) where

z=[z1z2]Tz = \begin {bmatrix} z_1 & z_2\end {bmatrix}^Tz=[z1​​z2​​]T

about the point

z0=[ab]Tz_0 = \begin {bmatrix} a & b\end {bmatrix}^Tz0​=[a​b​]T

can be written as

flin(z)=f(z0)+∂f(z)∂z1∣z=z0(z1−a)+∂f(z)∂z2∣z=z0(z2−b)f_{lin}(z) = f(z_0) + \frac{\partial f(z)}{\partial z_1}\Bigr|_{z = z_0} (z_1 - a)+\frac{\partial f(z)}{\partial z_2}\Bigr|_{z=z_0}(z_2 - b)flin​(z)=f(z0​)+∂z1​∂f(z)​​z=z0​​(z1​−a)+∂z2​∂f(z)​​z=z0​​(z2​−b)

​

Linearization of Inverted Pendulum Equations

The nonlinear equations of the inverted pendulum system obtained as Equations (7) and (8) are linearized about the equilibrium point with the pendulum in the upright position, i.e.,

θo=0\theta_o = 0θo​=0, αo=0\alpha_o = 0αo​=0, θ˙o=0\dot{\theta}_o = 0θ˙o​=0, α˙o=0\dot{\alpha}_o = 0α˙o​=0, θ¨o=0\ddot{\theta}_o = 0θ¨o​=0, α¨o=0\ddot{\alpha}_o = 0α¨o​=0

Linearization of Equation (7) about the above equilibrium state gives

(Jr+mpLr2)θ¨−12mpLpLrα¨=kVm−bθ˙−Brθ˙(10)(J_r + m_pL_r^2)\ddot{\theta} - \frac{1}{2}m_pL_pL_r\ddot{\alpha} = kV_m-b\dot{\theta} - B_r\dot{\theta} \quad\quad (10)(Jr​+mp​Lr2​)θ¨−21​mp​Lp​Lr​α¨=kVm​−bθ˙−Br​θ˙(10)

where, from Equation(9) the servo motor torque coefficient kkk is

k=ηgKgηmktRmk = \frac{\eta_gK_g\eta_mk_t}{R_m}k=Rm​ηg​Kg​ηm​kt​​

and the back emf coefficient bbb is

b=ηgKg2ηmktkmRmb = \frac{\eta_gK_g^2\eta_mk_tk_m}{R_m}b=Rm​ηg​Kg2​ηm​kt​km​​

Likewise, linearization of Equation (8) about the equilibrium point with the pendulum in the upright position gives

−12mpLpLrθ¨+(Jp+14mpLp2)α¨−12mpLpgα=−Bα˙(11)-\frac{1}{2}m_pL_pL_r\ddot{\theta} + (J_p + \frac{1}{4}m_pL_p^2)\ddot{\alpha} - \frac{1}{2}m_pL_pg\alpha= -B\dot{\alpha} \quad \quad (11)−21​mp​Lp​Lr​θ¨+(Jp​+41​mp​Lp2​)α¨−21​mp​Lp​gα=−Bα˙(11)

where ggg is the acceleration due to gravity. Note that the negative sign of the gravity torque (α\alphaα term) in Equation 11 indicates negative stiffness with the pendulum in the vertically upright position.

Equations (10) and (11) can be arranged in the matrix form as

[M][θ¨α¨]+[D][θ˙α˙]+[K][θα]=[k0]Vm(12)[M]\begin{bmatrix}\ddot{\theta} \\ \ddot{\alpha} \end{bmatrix} +[D] \begin{bmatrix}\dot{\theta} \\ \dot{\alpha} \end{bmatrix} + [K] \begin{bmatrix}\theta \\ \alpha \end{bmatrix} = \begin{bmatrix}k \\ 0 \end{bmatrix}V_m \quad \quad (12)[M][θ¨α¨​]+[D][θ˙α˙​]+[K][θα​]=[k0​]Vm​(12)

Where mass matrix MMM, damping matrix DDD, and the stiffness matrix KKK become

[M]=[(Jr+mpLr2)−12mpLpLr−12mpLpLr(Jp+14mpLp2)][M] = \begin{bmatrix} (J_r + m_pL_r^2) & -\frac{1}{2}m_pL_pL_r \\ -\frac{1}{2}m_pL_pL_r & (J_p + \frac{1}{4}m_pL_p^2) \end{bmatrix}[M]=[(Jr​+mp​Lr2​)−21​mp​Lp​Lr​​−21​mp​Lp​Lr​(Jp​+41​mp​Lp2​)​]
[D]=[b+Br00Bp][D] = \begin{bmatrix} b+B_r & 0 \\ 0 & B_p \end{bmatrix}[D]=[b+Br​0​0Bp​​]
[K]=[000−12mpLpg][K] = \begin{bmatrix} 0 & 0 \\ 0 & -\frac{1}{2}m_pL_pg \end{bmatrix}[K]=[00​0−21​mp​Lp​g​]

Defining the state vector xxx, output vector yyy and the control input uuu as

x=[θαθ˙α˙]T,y=[θα]T,u=Vmx = \begin{bmatrix} \theta & \alpha & \dot{\theta} & \dot{\alpha}\end{bmatrix}^T , \quad y = \begin{bmatrix} \theta & \alpha \end{bmatrix}^T, \quad u = V_mx=[θ​α​θ˙​α˙​]T,y=[θ​α​]T,u=Vm​

Equation (12) can be rewritten in state space form as

x˙=Ax+Bu(13)\dot{x} = Ax + Bu \quad \quad (13)x˙=Ax+Bu(13)
y=Cx+Du(14)y = Cx + Du \quad \quad (14)y=Cx+Du(14)

where the system state matrix AAA, control matrix BBB, output matrix CCCand the feedthrough of input to the output matrix DDD become

A=[O2×2I2×2−[M]−1[K]−[M]−1[D]]A = \begin{bmatrix} O_{2\times2} & I_{2\times2} \\ -[M]^{-1}[K] & -[M]^{-1}[D] \end{bmatrix} A=[O2×2​−[M]−1[K]​I2×2​−[M]−1[D]​]
B=[O2×1M−1[k0]]B = \begin{bmatrix} O_{2\times1} \\ M^{-1} \begin{bmatrix} k \\0 \end{bmatrix} \end{bmatrix}B=​O2×1​M−1[k0​]​​
C=[10000100]C = \begin{bmatrix} 1 & 0 & 0 & 0 \\ 0 & 1 & 0 & 0 \end{bmatrix}C=[10​01​00​00​]
D=[00]D = \begin{bmatrix} 0 \\ 0 \end{bmatrix}D=[00​]

Analysis: Modeling

  1. Download the Part 1.zip file and extract the folder contents.

  2. Note down your state-space matrices for your report. Note: You may want to cross-check the state-space matrix with TAs before proceeding to balance control.

  3. Find the open-loop poles of the system. Hint: Use eig(A).

B. Balance Control

Specification

The control design and time-response requirements are: Specification 1: Damping ratio: 0.6 < ζ\zetaζ < 0.8 Specification 2: Natural frequency: 3.5 rad/s < \omega_\rm{n} < 4.5 rad/s Specification 3: Maximum pendulum angle deflection: ∣α∣|\alpha|∣α∣ < 15 deg. Specification 4: Maximum control effort / voltage: |V_\rm{m}| < 10 V. The necessary closed-loop poles are found from specifications 1 and 2. The pendulum deflection and control effort requirements (i.e. specifications 3 and 4) are to be satisfied when the rotary arm is tracking a ±20\pm 20±20 degree angle square wave.

Stability

The stability of a system can be determined from its poles ([1]):

  • Stable systems have poles only in the left-half of the complex plane.

  • Unstable systems have at least one pole in the right-half of the complex plane and/or poles of multiplicity greater than 1 on the imaginary axis.

  • Marginally stable systems have one pole on the imaginary axis and the other poles in the left-half of the complex plane.

The poles are the roots of the system’s characteristic equation. From the state-space, the characteristic equation of the system can be found using

det(sI−A)=0(15)\mathrm{det}(sI - A) = 0 \qquad \qquad\tag{15}det(sI−A)=0(15)

where det()\mathrm{det}()det()is the determinant of a matrix, sss is the Laplace operator, and III is the identity matrix. These are the eigenvalues of the system matrix AAA.

Controllability

If the control input uuu of a system can take each state variable, xix_ixi​ where i=1...ni = 1 ... ni=1...n, from an initial state to a final state in finite time then the system is controllable, otherwise it is uncontrollable ([1]).

Rank Test The system is controllable if the rank of its controllability matrix

T=[B AB A2B ... An−1B](16)T = [B \ AB \ A^2B \ ... \ A^{n-1}B] \qquad \qquad \tag{16}T=[B AB A2B ... An−1B](16)

equals the number of states in the system, i.e.

rank(T)=n(17)\mathrm{rank}(T) = n \qquad \qquad \tag{17}rank(T)=n(17)
rank(T)=n(17)\mathrm{rank}(T) = n \qquad \qquad \tag{17}rank(T)=n(17)

Companion Matrix

For a controllable system with nxn system matrix A and nx1 control matrix B. The companion matrices of A and B are

A~=[01…0000…00⋮⋮⋱⋮⋮00…01−a1−a2…−an−1−an](18)\tilde{A} = \begin{bmatrix} 0 & 1 & \dots & 0& 0 \\ 0 & 0 & \dots & 0& 0 \\ \vdots & \vdots & \ddots & \vdots& \vdots \\ 0 & 0 & \dots & 0& 1 \\ -a_1 & -a_2 & \dots & -a_{n-1}& -a_n \end{bmatrix} \qquad \qquad \tag{18}A~=​00⋮0−a1​​10⋮0−a2​​……⋱……​00⋮0−an−1​​00⋮1−an​​​(18)

and

B~=[0⋮1](19)\tilde{B} = \begin{bmatrix} 0\\\vdots\\ \\1 \end{bmatrix} \qquad \qquad \tag{19}B~=​0⋮1​​(19)

Where a1,a2,...ana_1, a_2, ...a_na1​,a2​,...an​ are the coefficients of the characteristic equation of the system matrix A written as

s^n + a_ns^{n-1} + a_{n-1}s^{n-2} +a_2s + a_1 = 0\tag{20}

sn+ansn−1+an−1sn−2+...+a2s+a1=0s^n + a_ns^{n-1} + a_{n-1}s^{n-2} + ...+a_2s + a_1 = 0 sn+an​sn−1+an−1​sn−2+...+a2​s+a1​=0

Now define W,

W=TT~−1(20)W = T\tilde{T}^{-1} \qquad \qquad \tag{20}W=TT~−1(20)

where TTT is the controllability matrix defined in Equation 16 and

T~=[B~A~B~⋯A~n−1B~](21)\tilde{T} = \begin{bmatrix}\tilde{B} & \tilde{A}\tilde{B} & \cdots & \tilde{A}^{n-1}\tilde{B}\end{bmatrix} \qquad \qquad \tag{21} T~=[B~​A~B~​⋯​A~n−1B~​](21)

Then

W−1AW=A~(22)W^{-1}AW = \tilde{A} \qquad \qquad \tag{22}W−1AW=A~(22)

and

W−1B=B~(23)W^{-1}B = \tilde{B} \qquad \qquad \tag{23}W−1B=B~(23)

Pole Placement Theory

If (A,B)(A,B)(A,B) are controllable, then pole placement can be used to design the controller. Given the control law u=−Kxu = -Kxu=−Kx, the state-space model of Equation (13) becomes

x˙=Ax+B(−Kx)=(A−BK)x(25)\dot{x} = Ax + B(-Kx) =(A - BK)x \qquad \qquad \tag{25} x˙=Ax+B(−Kx)=(A−BK)x(25)

We can generalize the procedure to design a gain KKK for a controllable (A,B)(A,B)(A,B) system as follows:

Step 1 Find the companion matrices A~\tilde{A}A~ and B~\tilde{B}B~. Compute W=TT~−1W = T\tilde{T}^{-1}W=TT~−1. Step 2 Compute K~\tilde{K}K~ to assign the poles of A~−B~K~\tilde{A} - \tilde{B}\tilde{K}A~−B~K~ to the desired locations.

A~−B~K~=[01…0000…00⋮⋮⋱⋮⋮00…01−a1−k1~−a2−k2~…−an−1−kn−1~−an−kn~](26)\tilde{A} - \tilde{B}\tilde{K}= \begin{bmatrix} 0 & 1 & \dots & 0& 0 \\ 0 & 0 & \dots & 0& 0 \\ \vdots & \vdots & \ddots & \vdots& \vdots \\ 0 & 0 & \dots & 0& 1 \\ -a_1-\tilde{k_1} & -a_2-\tilde{k_2} & \dots & -a_{n-1}-\tilde{k_{n-1}}& -a_n -\tilde{k_n} \end{bmatrix} \qquad \qquad \tag{26}A~−B~K~=​00⋮0−a1​−k1​~​​10⋮0−a2​−k2​~​​……⋱……​00⋮0−an−1​−kn−1​~​​00⋮1−an​−kn​~​​​(26)

Step 3 Find K=K~W−1K = \tilde{K}W^{-1}K=K~W−1 to get the feedback gain for the original system (A,B)(A,B)(A,B). Remark-1: It is important to do the K~→K\tilde{K} \rightarrow KK~→K conversion. Remember that (A,B)(A,B)(A,B) represents the actual system while the companion matrices A~\tilde{A}A~ and B~\tilde{B}B~ do not.

Remark-2: The entire control design procedure using the pole placement method can be simply done in MATLAB using the function called 'place' or 'acker'. For a selected desired set of closed loop poles DP, the full state feedback gain matrix KKK is obtained from

>> K = acker(A,B,DP);

Desired Poles

p1=−σ+jωd(27a)p_1 = -\sigma + j\omega_d \qquad \qquad \tag{27a} p1​=−σ+jωd​(27a)

and

p2=−σ−jωd(27b)p_2 = -\sigma - j\omega_d \qquad \qquad \tag{27b} p2​=−σ−jωd​(27b)

where​ σ=ζωn\sigma = \zeta\omega_nσ=ζωn​ and ωd=ωn1−ζ2\omega_d = \omega_n \sqrt{1-\zeta^2}ωd​=ωn​1−ζ2​ is the damped frequency. The remaining closed-loop poles, p3p_3p3​ and p4p_4p4​, are placed along the real-axis to the left of the dominant poles, as shown in Figure 3.

Simulation Model with Feedback

The feedback control loop that balances the rotary pendulum is illustrated in Figure 4. The reference state is defined as

xd=[θd 0 0 0]⊺(28)x_d = [\theta_d \ 0\ 0\ 0]^ \intercal \qquad \qquad \tag{28}xd​=[θd​ 0 0 0]⊺(28)

where θd\theta_dθd​ is the desired rotary arm angle. The controller is

u=K(xd−x)(29)u = K(x_d - x) \qquad \qquad \tag{29}u=K(xd​−x)(29)

Note that if xd=0x_d = 0xd​=0 then u=−Kxu = -Kxu=−Kx, which is the control used in the pole-placement algorithm.

When running this on the actual system, the pendulum begins in the hanging, downward position. We only want the balance control to be enabled when the pendulum is brought up around its upright vertical position. The controller is therefore

u={K(xd−x)∣x2∣<ϵ 0otherwise(30)u = \begin{cases} K(x_d - x) & |x_2| <\epsilon \\\ 0 & \text{otherwise} \end{cases} \qquad \qquad \tag{30}u={K(xd​−x) 0​∣x2​∣<ϵotherwise​(30)

where ϵ\epsilonϵ is the angle about which the controller should engage. Also x2x_2x2​ is the pendulum angle. For example if ϵ=10\epsilon = 10ϵ=10 degrees, then the control will begin when the pendulum is within ±10 degrees of its upright position, i.e. when ∣x2∣<10|x_2| < 10∣x2​∣<10 degrees.

B.1 Experiment: Designing the Balance Control

  1. Select ζ\zetaζ and ωn\omega_nωn​ from the table below. Ensure to choose a different set of values from your groupmates

    Parameter
    1
    2
    3
    4
    5
    6
    7
    8
    3.75
    4
    4.25
    3.75
    4.25
    3.75
    4
    4.25
    0.65
    0.65
    0.65
    0.7
    0.7
    0.75
    0.75
    0.75
  2. In the same rotpen_part1_student.mlx live script, go to the Balance Control section. Enter the chosen zeta and omega_n values.

  3. Determine the locations of the two dominant poles p1p_1p1​ and p2p_2p2​ based on the specifications and enter their values in the MATLAB live script. Ensure that the other poles are placed at p3 = -30 and p4 = -40. Hint: Use Equation 27.

  4. Find gain K using a predefined Compensator Design MATLAB command K = acker(A,B,DP), which is based on pole-placement design. Note: DP is a row vector of the desired poles found in Step 3.

For sanity check, if you use damping ratio of 0.7 and natural frequency of 4 rad/s, you should get around K = [-12 63 -5.5 7].

B.2 Experiment: Simulating the Balance Control

  1. Run rotpen_part1_student.mlx live script. Ensure the gain K you found is loaded in the workspace (type K matrix in the command window).

  2. Open and run the s_rotpen_bal.mdl for 10 seconds. The responses in the scopes shown in Figure 6 were generated using an arbitrary feedback control gain. Note: When the simulation stops, the last 10 seconds of data is automatically saved in the MATLAB workspace to the variables data_theta, data_alpha, and data_Vm.

  3. Save the data corresponding to the simulated response of the rotary arm, pendulum, and motor input voltage obtained using your obtained gain K. Note: The time is stored in the data_theta(:,1) vector, the desired and measured rotary arm angles are saved in the data_theta(:,2) and data_theta(:,3) arrays. Similarly, the pendulum angle is stored in the data_alpha(:,2) vector, and the control input is in the data_Vm(:,2) structure.

B.3 Experiment: Implementing the Balance Controller

In this section, the state-feedback control that was designed and simulated in the previous sections is run on the actual Rotary Pendulum device.

Experiment Setup

The q_rotpen_bal_student SIMULINK diagram shown in Figure 7 is used to run the state-feedback control on the Quanser Rotary Pendulum system. The Rotary Pendulum Interface subsystem contains QUARC blocks that interface with the DC motor and sensors of the system. The feedback developed in the previous section is implemented using a Simulink Gain block.

  1. Download the Part 2.zip file, extract the folder contents and open the part2setup.m script.

  2. Open the q_rotpen_bal_student SIMULINK diagram.

  3. As shown in Figure 7, the SIMULINK diagram is incomplete. Add the necessary blocks from the Simulink library to implement the balance control.

    • You need to add a switch logic to implement Equation 30. Use Multi-port switch with 2 data points and zero-based contiguous. The output from the compare to constant block will be 0 if false and 1 if true. Check your block with TA.

    • Ensure that you connect the final signal going into the u(V) terminal of the Rotary Pendulum Interface, which is also connected to the u scope terminal.

  4. Turn ON the power amplifier.

  5. Ensure the pendulum is in the hanging down position, with the rotary arm aligned with the 0 marking, and is motionless.

  6. Once it is running, manually bring up the pendulum to its upright vertical position. You should feel the voltage kick-in when it is within the range where the balance control engages. Once it is balanced, the controller will introduce the ±20 degree rotary arm rotation.

  7. The response should look similar to your simulation. Once you have obtained a response, click on the STOP button to stop the controller (data is saved for the last 10 seconds, so stop SIMULINK around 18-19 seconds once the response looks similar to Figure 8).

    CAUTION Be careful, as the pendulum will fall down when the controller is stopped.

  8. Similar to the simulation Simulink model, the response data will be saved to the workspace. Copy and paste into your group's folder. Ensure that the data variables have 10 seconds of data saved.

Results for Report

A) Modeling

  1. The linear state-space representation of the rotary inverted pendulum system, i.e., AAA, BBB, CCC and DDD matrices (numerical values).

  2. Open-loop poles of the system.

B.1) Balance Control Design

  1. Chosen ζ\zetaζ and ωn\omega_nωn​ based on design specifications.

  2. Corresponding locations of the two dominant poles p1p_1p1​ and p2p_2p2​.

  3. Gain vector KKK.

B.2) Balance Control Simulation

  1. Plots of the commanded position of the rotary arm (θc\theta_cθc​), simulated responses of the rotary arm (θ\thetaθ), pendulum (α\alphaα), and motor input voltage (VmV_mVm​) generated using your obtained gain K.

B.3) Balance Controller Implementation

Questions for Report

A) Modeling

  1. Did you expect the stability of the inverted pendulum to be as what was determined? Justify.

B.1) Balance Control Design

For the questions below, calculations and intermediate steps must be shown.

  1. Determine the controllability matrix TTT of the system. Is the inverted pendulum system controllable? Hint: Use Equation 17.

  2. Using the open-loop poles, find the characteristic equation of AAA. Hint: The roots of the characteristic equation are the open-­loop poles.

  3. Determine the controllability matrix T~\tilde{T}T~ of the companion system.

  4. Determine the transformation matrix WWW.

  5. Check if A~=W−1AW\tilde{A} = W^{-1}AWA~=W−1AW and B~=W−1B\tilde{B} = W^{-1}BB~=W−1B with the obtained matrices.

Appendix

Table A Main Rotary Servo Base Unit Specifications

Motor nominal input voltage

6.0 V

Motor armature resistance

2.6 Ω ± 12%

Motor armature inductance

0.18 mH

Motor current-torque constant

7.68 × 10−3 N-m/A ± 12%

Motor back-emf constant

7.68 × 10−3 V/(rad/s) ± 12%

High-gear total gear ratio

70

Motor efficiency

0.69 ± 5%

Gearbox efficiency

0.90 ± 10%

rotor Rotor moment of inertia

3.90 × 10−7 kg-m2 ± 10%

High-gear equivalent moment of inertia without external load

1.823 × 10−3 kg-m2

High-gear Equivalent viscous damping coefficient

0.015 N-m/(rad/s)

Mass of bar load

0.038 kg

Length of bar load

0.1525 m

Mass of disc load

0.04 kg

Radius of disc load

0.05 m

Maximum load mass

5 kg

Maximum input voltage frequency

50 Hz

Maximum input current

1 A

Maximum motor speed

628.3 rad/s

Reference

[1] Norman S. Nise. Control Systems Engineering. John Wiley & Sons, Inc., 2008.

[2] Bruce Francis. Ece1619 linear systems, 2001.

PreviousLab 4: Rotary Inverted PendulumNextC. Swing-up Control (Demo)

Last updated 2 months ago

Was this helpful?

​

​

​

​

​

​

​

​

​

​

​

​

​

​

​See in the Appendix for a description of the corresponding Rotary Servo parameters (e.g., such as the back-emf constant, kmk_mkm​k_\rm{m}). Our control variable is the input servo motor voltage, VmV_mVm​V_\rm{m}. Opposing the applied torque is the viscous friction torque, or viscous damping, corresponding to the term BrB_\mathrm{r}Br​. Since the pendulum is not actuated, the only force acting on the link is the damping. The viscous damping coefficient of the pendulum is denoted by BpB_\mathrm{p}Bp​.

The torque applied at the base of the rotary arm (i.e. at the load gear) is generated by the servo motor as described by the equation 7. Refer to in the Appendix for the Rotary Servo parameters.

In the equations above, note that O2×2O_{2\times2}O2×2​ is a 2×22 \times 22×2 matrix of zeros, O2×1O_{2\times1}O2×1​ is a 2×12 \times 12×1 matrix of zeros, and I2×2I_{2 \times 2} I2×2​ is a 2×22\times22×2 identity matrix. Using the parameters of the system listed in and the appendix , the linear model matricesAAA and BBB can be computed.

Open rotpen_part1_student.mlx live script and run the Modelling section. It will automatically load the parameters required for the state-space representation, and subsequently generate the A, B, C and D matrices required for the upcoming analysis. Please refer to and for additional information regarding the parameters. Note: The representative C and D matrices have already been included. The actuator dynamics have been added to convert your state-space matrices to be in terms of voltage. Recall that the input of the state-space model is the torque acting at the servo load gear. However, we control the servo input voltage instead of control torque directly. The script uses the voltage torque relationship given in Equation 9 to transform torque to voltage.

The rotary inverted pendulum system has four poles. As depicted in Figure 3, poles p1p_1p1​ and p2p_2p2​ are the complex conjugate dominant poles and are chosen to satisfy the natural frequency, ωn\omega_nωn​, and the damping ratio, ζ\zetaζ, as given in the s. Let the conjugate poles be

(rad/s)

The s_rotpen_bal SIMULINK diagram shown in Figure 5 is used to simulate the closed-loop response of the Rotary Pendulum using the state-feedback control described in with the control gain K found above. The Signal Generator block generates a 0.1 Hz square wave (with an amplitude of 1). The Amplitude (deg) gain block is used to change the desired rotary arm position. The state-feedback gain K is set in the Control Gain gain block and is read from the MATLAB workspace. The SIMULINK State-Space block reads the A, B, C, and D state-space matrices that are loaded in the MATLAB workspace. The Find State X block contains high-pass filters to find the angular rates of the rotary arm and pendulum.

Measure the pendulum deflection and voltage used. Are the given satisfied?

Go to the 'Balance Control' section and put the gain K you found in . Run the script.

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.

Press Connect button under Monitor & Tune and Press Start .

Are satisfied? Justify using the measured maximum pendulum deflection and motor input voltage values.

From , plots of the commanded position of the rotary arm (θc\theta_cθc​), experimental responses of the rotary arm (θ\thetaθ), pendulum (α\alphaα), and motor input voltage (u(Vm)u(V_m)u(Vm​)) generated using the chosen gain K.

Are satisfied? Justify using the measured maximum pendulum deflection and motor input voltage values.

Based on your open-loop poles found in , is the system stable, marginally stable, or unstable?

Instead of using det(sI−A)=0\mathrm{det}(sI - A) = 0 det(sI−A)=0, characteristic polynomials can also be found using MATLAB function .

Find the corresponding companion matrices A~\tilde{A}A~ and B~\tilde{B}B~ . Hint: For A~\tilde{A}A~ , use the characteristic equation of A found in and Equation 19. For B~\tilde{B}B~, use Equation 20.

Using the locations of the two dominant poles, p1p_1p1​ and p2p_2p2​, based on the (), and the other poles at p3=−30p_3 = -30p3​=−30 and p4=−40p_4 = -40p4​=−40, determine the desired closed-loop characteristic equation. Hint: The roots of the closed-loop characteristic equation are the closed-­loop poles.

When applying the control u=−K~xu = -\tilde{K}xu=−K~x to the companion form, it changes (A~,B~)(\tilde{A}, \tilde{B})(A~,B~) to (A~−B~K~,B~)(\tilde{A}-\tilde{B}\tilde{K}, \tilde{B})(A~−B~K~,B~). Find the gain K~\tilde{K}K~ that assigns the poles to their new desired location. Hint: Use Equation 26 and find the corresponding characteristic equation. Compare this equation with the desired closed-loop characteristic equation found in to determine the gain vector K~\tilde{K}K~.

Once you have found K~\tilde{K}K~, find KKK using .

Compare the gain vector KKKcalculated using Pole Placement Theory () with the gain vector KKK obtained using MATLAB ().

kg\mathrm{kg}kg
m\rm{m}m
m\rm{m}m
kg⋅m2\rm{kg \cdot m^2}kg⋅m2
N⋅m⋅s/rad\rm{N\cdot m\cdot s/rad}N⋅m⋅s/rad
kg\rm{kg}kg
m\rm{m}m
m\rm{m}m
kg⋅m2\rm{kg \cdot m^2}kg⋅m2
N⋅m⋅s/rad\rm{N\cdot m\cdot s/rad}N⋅m⋅s/rad
kg⋅m2\rm{kg\cdot m^2}kg⋅m2
counts/rev\rm{counts/rev}counts/rev
wnw_nwn​
ζ\zetaζ
VnomV_{\rm{nom}}Vnom​
poly()
Table A
Table A
Table 2
Table A
Table 2
Table A
Specification
Balance Control
specifications
Step 4 of Designing the Balance Control experiment
Design Specifications 3 and 4
Step B.3.10
Design Specifications 3 and 4
Result A.2
Question B.1.2
specifications
Result B.1.1
Question B.1.7
Step 3 in Pole Placement Theory
Question B.1.9
Result B.1.3
m_\rm{p}
L_\rm{p}
l_\rm{p}
J_\rm{p,cm}
B_\rm{p}
m_\rm{arm}
L_\rm{r}
l_\rm{arm}
J_\rm{arm,cm}
B_\rm{r}
J_\rm{arm}
K_\rm{enc}
R_\rm{m}
L_\rm{m}
k_\rm{t}
k_\rm{m}
K_\rm{g}
\eta_\rm{m}
\eta_\rm{g}
J_\rm{m}
J_\rm{eq}
B_\rm{eq}
m_\rm{b}
L_\rm{b}
m_\rm{d}
r_\rm{d}
m_\rm{max}
f_\rm{max}
l_\rm{max}
\omega_\rm{max}
19KB
Part 1.zip
archive
75KB
Part 2.zip
archive
Figure 1 Rotary servo base with Rotary Pendulum module
Figure 2 Rotary inverted pendulum conventions
Figure 3 Desired closed-loop pole locations
Figure 4 State-feedback control loop
Figure 5: s_rotpen_bal SIMULINK diagram used to simulate the state-feedback control
Figure 6: Balance control simulation
Figure 7. q_rotpen_bal_student SIMULINK diagram can be used to run balance controller
Figure 8. Experiment balance control response example