User Tools

Site Tools


pid_control_-_pneumatics_inverted_pendulum

This is an old revision of the document!


PID - Pneumatic Inverted Pendulum

Author: Hyunhee Lee Email: leeh67@unlv.nevada.edu
Date: Last modified on 07/07/2017
Keywords: Pneumatic, Inverted, Pendulum

Motivation and Audience: This tutorial is for studying and analyzing about control mechanism through inverted pendulum. Inverted pendulum mechanism is popularly used in control field.

jpg



Modeling of the Pneumatic inverted pendulum

jpg
There are two encoders in the cart. One is the angular encoder and the other is linear encoder. The angular encoder measures angular displacements of a swing pendulum and the linear encoder measures linear displacements of cart. Arduino controls the output voltage for proportional vale.

Equations of motion

Euler-Lagrange equation is used for derive equations of motion. rip_equ1.jpg
The kinetic energy of the system is rip_equ2.jpg

  • HW. Derive the kinetic energy.

And the potential energy of the system is rip_equ3.jpg
Then the Lagrangian is same as the following. rip_equ4.jpg
From Euler-Lagrange equation, the equations of motion are rip_equ5.jpg
For linear control, we need to linearize the equations about near the equilibrium point (α = 0 ). Assume that α is a small angle. Then, rip_equ6.jpg
Therefore the linearized equations of motion are rip_equ7.jpg

  • HW. Linearize the above nonlinear equations by Taylor expansion.

For state-space representation, the equations are reconstructed. rip_equ8.jpg
It needs to transform the input torque into the motor voltage because the torque can not be used by the input in the lego system. So the following DC motor model is needed to do that. If a motor inductance and viscous damping can be neglected, jpg
where, R, kt, Jm, and kb are a motor resistance, a torque constant, a motor armature inertia, and a back-emf constant, respectively. Assume that an external torque is neglected and then the motor torque is jpg
Let's substitute this motor torque into the equations of motion and set states X. jpg
Therefore, the state-space representation for full-state feedback control is shown jpg

  • HW. Derive a transfer function assuming that an output, y, is a α.

PID control

To control, PID controller is used. jpg
where, ref, k, and u are a reference input, a feedback gain vector, and a control input, respectively. A control law is jpg
, and since we desire that the pendulum keeps upright, the ref is equal to zero. jpg
where k1, k2, k3, and k4 are gains of a swing arm angle, a pendulum angle, a swing arm angular velocity and a pendulum angular velocity.
Now we need to determine these gains.

PID for simulation

Matlab Code

%% PID Control for PIP
clc;
clear;
%syms s;
s = tf('s');
 
m = 0.064;
M = 0.322;
l = 1.22;
g = 9.8;
IP = (m*l^2)/3;
b = 0.23; %0.44
 
num_p = [m*l 0];
denom_p = [(M+m)*(IP+m*l^2)-m^2*l^2 b*(IP+m*l^2) -(M+m)*m*l*g -b*m*g*l];
 
num_c = [(IP+m*l^2) 0 -m*l*g];
denom_c = [(M+m)*(IP+m*l^2)-m^2*l^2 b*(IP+m*l^2) -(M+m)*m*l*g -b*m*g*l 0];
 
 
 
Gp_p = tf(num_p,denom_p);
Gp_c = tf(num_c, denom_c);
H = 1;
 
 
Kp = 30; %%18 70
Ki = 12;  %%5 2
Kd = 18;  %%4 15
 
Cont = (Kp + (Ki*(1/s)) + (Kd*s));
 
C_p1 = Gp_p/(1+Gp_p*Cont);
 
C_p1 = minreal(C_p1);
tn = 0:0.01:15;
syms t
impul(t) = (-0.0597.*exp((-31.9435).*t))-(0.2074.*exp((-0.7377).*t)*2.*cos(((0.1036).*t)-98.263));
yn1 = double( subs(impul, symvar(t), tn)) ;

t = 0:0.01:15;

grid on
plot(tn,yn1)

Arduino code for PID

#define MOTOR OUT_A
#define PNDLM OUT_C
#define FULL_SPEED 100
#define D2R 0.0175 // converts degree to radian
#define R2D 57.2958 // converts radian to degree
 
long prev_tick = 0;
long prev_Mdeg = 0;
long prev_Pdeg = 0;
long Mdeg = 0;
long Pdeg = 0;
long M_diff = 0;
long P_diff = 0;
 
float dt = 0.0;
float GTime = 0.0;
float Mrad = 0.0;
float Prad = 0.0;
float d_Mrad = 0.0;
float d_Prad = 0.0;
float d_Mdeg = 0.0;
float d_Pdeg = 0.0;
float M_errSum = 0.0;
 
char controlU = 0;
 
bool flag_balanceControl = true;
 
byte fileHandle;
 
sub MotorPID(float refRad, float PGain, float IGain, float DGain)
{
   float error = refRad - Mrad;
   float U = PGain*error + IGain*M_errSum - DGain*d_Mrad;
 
   if(U > FULL_SPEED)
   {
      controlU = FULL_SPEED;
   }
   else if(U < -FULL_SPEED)
   {
      controlU = -FULL_SPEED;
   }
   else
   {
      controlU = U;
   }
 
   M_errSum = M_errSum + error - 1.0*(U - controlU);
 
   OnRev(MOTOR, controlU);
}
 
sub MotorOpenLoop(float speed)
{
   if(speed > FULL_SPEED)
   {
      controlU = FULL_SPEED;
   }
   else if(speed < -FULL_SPEED)
   {
      controlU = -FULL_SPEED;
   }
   else
   {
      controlU = speed;
   }
 
   OnRev(MOTOR, controlU);
}
 
task ReadEncoder()
{
   const int w = 4;
   float M_mov[w] = {0.0,};
   float P_mov[w] = {0.0,};
   float sum_Mmov = 0.0;
   float sum_Pmov = 0.0;
   int cnt = 0;
 
   while(true)
   {
      dt = (CurrentTick() - prev_tick)*0.001;
      Mdeg = MotorRotationCount(MOTOR);
      Pdeg = MotorRotationCount(PNDLM);
      M_diff = Mdeg - prev_Mdeg;
      P_diff = Pdeg - prev_Pdeg;
      prev_Mdeg = Mdeg;
      prev_Pdeg = Pdeg;
 
      d_Mdeg = M_diff/dt;
      d_Pdeg = P_diff/dt;
 
      Mrad = Mdeg*D2R;
      Prad = Pdeg*D2R;
 
      d_Mrad = d_Mdeg*D2R;
      d_Prad = d_Pdeg*D2R;
 
      prev_tick = CurrentTick();
      GTime += dt;
 
      Wait(MS_20);
   }
}
 
task BalanceControl()
{
   // A physical motor rotation direction is reversed as a model's rotation direction.
   float Gm_p = -(-7.07106781265702);     //Gain on Motor Position
   float Gp_p = -361.604865668371;        //Gain on Pendulum Position
   float Gm_v = -(-7.20613568524004);     //Gain on Motor Velocity
   float Gp_v = -9.15404034187486;       //Gain on Pendulum velocity
 
   Wait(MS_10);
 
   while(true)
   {
      if(flag_balanceControl == true)
      {
         MotorOpenLoop(Gp_p*Prad + Gp_v*d_Prad + Gm_p*Mrad + Gm_v*d_Mrad);
      }
      Wait(MS_20);
   }
}
 
task Display()
{
   while(true)
   {
      TextOut(0, LCD_LINE1, FormatNum("Frq: %.1f Hz", 1/dt), DRAW_OPT_CLEAR_LINE);
      TextOut(0, LCD_LINE2, FormatNum("P deg: %d", Pdeg), DRAW_OPT_CLEAR_LINE);
      TextOut(0, LCD_LINE3, FormatNum("M deg: %d", Mdeg), DRAW_OPT_CLEAR_LINE);
      TextOut(0, LCD_LINE4, FormatNum("Time: %.3f", GTime), DRAW_OPT_CLEAR_LINE);
      TextOut(0, LCD_LINE5, FormatNum("Flag_B: %d", flag_balanceControl), DRAW_OPT_CLEAR_LINE);
      TextOut(0, LCD_LINE6, FormatNum("Ctrl U: %d", controlU), DRAW_OPT_CLEAR_LINE);
      Wait(MS_200);
   }
}
 
task WriteData()
{
   short bytesWritten;
   string write;
   long cnt = 0;
 
   CreateFile("data_sp.txt", 51200, fileHandle);
 
   while(true)
   {
      ++cnt;
      write = NumToStr(cnt);
      write = StrCat(write, " ", NumToStr(GTime), " ", NumToStr(Mrad), " ", NumToStr(d_Mrad), " ", NumToStr(Prad), " ", NumToStr(d_Prad));
      WriteLnString(fileHandle, write, bytesWritten);
      Wait(MS_5);
   }
}
 
task main()
{
   DeleteFile("data_sp.txt");
 
   prev_tick = CurrentTick();
   Precedes(ReadEncoder, BalanceControl, Display);
   //Precedes(ReadEncoder, Display);
   //Precedes(ReadEncoder, WriteData, Display);
   //Precedes(ReadEncoder, BalanceControl, WriteData, Display);
}
pid_control_-_pneumatics_inverted_pendulum.1499732290.txt.gz · Last modified: 2017/07/10 17:18 by hyunheelee