System Controlling: 2012

Friday, December 21, 2012

Discrete H infinity filter design

Short introduction

In many application cases where some of the system states can't be measured, we can use a state observer. One solution would be the Kálmán filter which I already presented. Another solution is the $H_\infty$ filter which is robust regarding the unpredictable noise source. In the Kálmán filter not only the noise process needs to be zero mean, but also the $Q$, $R$ covariance matrices have to be known, without them we can't design an appropriate observer. While in the $H_\infty$ filter doesn't make any assumptions about the noise, it minimizes the worst case estimation error.

Discrete $H_\infty$ filter design

We have the following discrete-time system
$$x_{k+1}=A_k x_k+B_k u_k + w_k\\y_k=C_k x_k+D_k u_k+v_k\tag{1}$$
The $1$ system has to be controllable and observable. We would like to achieve a small estimation error $e_k=z_k - \hat{z}_k$ for any $w_k,v_k$. In this case we want to solve the minimax problem as follows:
$$min_xmax_{w,v}J\tag{2}$$
where $J$ is:
$$J=\frac{\sum\limits_{k=0}^{N-1}{\left|\left|z_k - \hat{z}_k\right|\right|_{Q_k}^2}}{\left|\left|x_0 - \hat{x}_0\right|\right|_{P_0}^2+\sum\limits_{k=0}^{N-1}{\left|\left|w_k\right|\right|_{W_k}^2+\left|\left|v_k\right|\right|_{V_k}^2}}\tag{3}$$
Theorem: Let $\gamma>0$ be a prescribed level of noise attenuation. Then there exists a $H_\infty$ filter for $z_k$ if and only if there exists a stabilizing symmetric solution $P_k>0$ to the following discrete-time Ricatti equation:

 $$P_{k+1}=A_kP_k(I-\gamma Q_kP_k+C_k^TV_k^{-1}C_kP_k)^{-1}A_k^T+B_kW_kB_k^T\tag{4}$$
where
$$\hat{x}_{k+1}=A \hat{x}_k+B u_k+K_k(y_k-C_k\hat{x}_k)\tag{5}$$
The $K_k$ is the gain of the $H_\infty$ filter and it is given by:
$$K_k=A_kP_k(I-\gamma Q_kP_k+C_k^TV_k^{-1}C_kP_k)^{-1}C_k^TV_k^{-1}\tag{6}$$
Proof: Xuemin Shen and Li Deng: Game Theory Approach to Discrete $H_\infty$ Filter Design

As you can see the filter gain doesn’t depend from the states of the system so it's possible to calculate offline.

Cpp implementation

On github you can find a C++ implementation of the $H_\infty$ filter, this is only a chunk of the C++ class.
/*
  *@summary: The filter gain calculation
  *@param A: State space model A matrix
  *@param B: State space mode B matrix
  *@return: Filter Gain
  */
 Matrix HINF::calkGain(Matrix A, Matrix B) {
  if (A.rows() != P.cols())
   ERRORH::throwerror("A rows has to be equal with P columns");

  Matrix I = Matrix::Identity(A.cols(), A.cols());

  Matrix L = (I - lambda * Q * P + C.transpose() * V.inverse() * C * P).inverse();

  P = A * P * L * A.transpose() + B * W * B.transpose();

  K = A * P * L * C.transpose() * V.inverse();

  return K;
 }

 /*
  *@summary: Update the state
  *@param A: State space model A matrix
  *@param B: State space mode B matrix
  *@return: The new state
  */
 Matrix HINF::updateState(Matrix A, Matrix B, Matrix u) {
  x = A * x + B * u;
  return x;
 }

 /*
  *@sumary: Estimate the next states
  *@param M: Measured state
  */
 Matrix HINF::estimate(Matrix M) {

  x = x + K * (M - C * x);

  return x;
 }

Readings:


  • Kemin Zhou: ESSENTIALS OF ROBUST CONTROL
  • Xuemin Shen and Li Deng: Game Theory Approach to Discrete $H_\infty$ Filter Design

Sunday, December 2, 2012

MPC implementation in C++

I was really curious about how fast can we calculate the control signal using MPC. Because of this, first I wanted to write a short C code, but finally I end up with C++. because it is easy to overload the operations and more flexible and easier to implement the Matrix operations. Also there are disadvantages just to mention that the std::vector is slower than the C array and C++ can increase the size of the compiled code significantly.

I have to mention that this is my first code in C++, but I already have experience with OOP(Matlab, Python, Java, PHP) and at the University I got the basics of the C. 

For the first test I used the Eigen library which is really straight forward, but where is the challenge if I'm using a libraries instead of writing my own code and learning new OP language. With the Eigen I could achieve around 6e-5s which is really good, but this package is optimized for big matrices, take a look on the benchmark. In my case, the biggest matrix is a 4x4 matrix, which is really small.

In the second test I wrote my own library(you can fork from this on the github), I'm using arrays instead of std::vectors, because it's faster as I mentioned before.
The result of the test:
Runtime

My next step was to test on my Raspberry Pi using ChibiOS/RT(ARM  CPU). In this platform to calculate one control signal took around 2ms which is not really good. In the mean time I also install Arch Linux on the RPI where the runtime was 0.4ms which is a bit better, so I will try to compile the Linux kernel with real time capability.

Finally this is the test code
int main(int argc, char* argv[]) {

 /*
  * Defining the variables
  */
 //Control horizon
 int nc = 4;
 // Prediction horizon
 int np = 4;
 //Control signal 
 Matrix u(1, 1);
 // Sampling time
 double Ts = 5e-5;

 MPC mySysMat(2, 1, 1);
 //Error matrix, just for testing; 

 Matrix DeltaU(np, 1);

 Matrix R = 1e-5
   * Matrix::Identity(mySysMat.C.rows() * nc,
     mySysMat.C.rows() * nc);
 Matrix Q = 1e4 * Matrix::Identity(np, np);

 Matrix x0(2, 1);
 //Reference signal
 Matrix y_ref(100000, 1);
 y_ref.rblock(0, 0, 50000, 1) = 100 * Matrix::Ones(50000, 1);
 y_ref.rblock(50000, 0, 100000, 1) = -100 * Matrix::Ones(50000, 1);

 double start = now();

 //DC motor parameters
 double Rm = 0.35;
 double Km = 0.0296;
 double Ke = 0.0296;
 double b = 6.7 * 10e-5;
 double J = 2.9 * 10e-6;
 double Fc = 0.02;
 double L = 25 * 10e-6;

 /*
  Parsing the input parameters
  */
 for (int i = 1; i < argc; i++) {
  if (i + 1 != argc) // Check that we haven't finished parsing already
   if (!strcmp(argv[i], "-s")) {
    Ts = atof(argv[i + 1]);
   }
  if (!strcmp(argv[i], "-nc")) {
   nc = atoi(argv[i + 1]);
  }
  if (!strcmp(argv[i], "-np")) {
   np = atoi(argv[i + 1]);
  }

  if (!strcmp(argv[i], "-h")) {
#ifdef CMD
   std::cout << "Coming soon..." << std::endl;
#endif

  }
 }

 //Initializing the system matrices
 mySysMat.Fi << 1 - Ts * (Rm / L), -Ts * (Ke / L), Ts * (Km / J), 1
   - Ts * (b / J);

 mySysMat.Ga << Ts * 1 / L, 0;

 mySysMat.C << 0, 1;

 mySysMat.calcMPCFi(np);
 mySysMat.calcMPCGa(np);
 mySysMat.calcMPCGy(np, nc);
#ifdef DEBUG
 std::cout << "Calculation Fi,Ga,Gy took : " << (double) (now() - start)
   << std::endl;
#endif

 Matrix calcT(1, y_ref.rows());
 Matrix u_hist(1, y_ref.rows());
 Matrix w_hist(1, y_ref.rows());

 for (int i = 0; i < y_ref.rows() - np; i++) {

  start = now();
  //Calculating the error

  DeltaU = mySysMat.calcContSig(
    mySysMat.calcError(y_ref.block(i, 0, i + np, 1), x0, u), Q, R);

  u(0, 0) += DeltaU(0, 0);

  //We are not including this in the time measurement
  if (abs(u(0, 0)) > 5)
   u(0, 0) = sgn(u(0, 0)) * 5;

  u_hist(0, i) = u(0, 0);

  w_hist(0, i) = x0(1, 0);
  //Simulating the system
  x0 = mySysMat.Fi * x0 + mySysMat.Ga * u;

  //Storing the calculation time
  calcT(0, i) = (double) (now() - start);

 }
#ifdef DEBUG
 std::cout << "Minimum:" << calcT.min() << std::endl;
 std::cout << "Maximum:" << calcT.max() << std::endl;
#endif

#ifdef PLOT
 Gnuplot g3("lines");
 plot_x(y_ref, Ts, &g3);
 plot_x(w_hist, Ts, &g3);

 Gnuplot g2("lines");
 plot_x(u_hist, Ts, &g2);

 Gnuplot g1("lines");
 plot_x(calcT, Ts, &g1);
 std::cin.get();
#endif

Sunday, November 18, 2012

Model predictive control of brushed DC motor

Motor model

The state space model of a brushed DC motor as follow:
$$A =\left[ {\begin{array}{cc} -\frac{R_{a}}{L_{a}} & -\frac{K_{e}}{L_{a}} &  0 \\ \frac{K_{m}}{J} & -\frac{b}{J} & 0 \\ 0 & 1 & 0 \end{array} } \right] B=\left[ {\begin{array}{cc} \frac{1}{L_{a}} \\ 0 \\ 0 \end{array} } \right] C=\left[ {\begin{array}{cc} 0 \\ 1 \\ 0 \end{array} } \right] D=\left[ {\begin{array}{cc} 0 \end{array} } \right]\tag{1}$$
As you can see, I assumed that the torque is zero. 
Where the states are:
$$\dot{x(t)} =\left[ {\begin{array}{cc} \frac{di}{dt} \\ \frac{d\omega}{dt} \\ \frac{d\theta}{dt} \end{array} } \right]\tag{2}$$

Controller design


I already introduced the MPC controller, please read that first before you continue to read this blog. 
The first step is to determine the Toeplitz matrix:
$$\begin{bmatrix}x_{k+1|k} \\ \vdots \\ x_{k+N_c|k} \\ x_{k+N_c+1|k} \\ \vdots \\ x_{k+N|k} \end{bmatrix}=\begin{bmatrix}\Phi \\ \vdots \\ \Phi^{N_c} \\ \Phi^{N_c+1} \\ \vdots \\ \Phi^N \end{bmatrix}x_k + \begin{bmatrix}\Gamma \\ \vdots \\ \sum_{i=0}^{N_c-1} \Phi^{i} \Gamma\\ \sum_{i=0}^{N_c}\Phi^{i} \Gamma\\ \vdots \\ \sum_{i=0}^{N}\Phi^i \Gamma \end{bmatrix}u_{k-1}\\+ \begin{bmatrix}\Gamma & \cdots & 0 \\ \vdots & \ddots & \vdots \\ \sum_{i=0}^{N_c}\Phi^{i} \Gamma & \cdots & \Phi \Gamma+\Gamma \\ \vdots & \ddots & \vdots \\ \sum_{i=0}^{N-1}\Phi^i \Gamma & \cdots & \sum_{i=0}^{N-N_c}\Phi^i \Gamma \end{bmatrix} \begin{bmatrix}\Delta u_{k+1|k} \\ \vdots \\ \Delta u_{k+N_c-1|k} \end{bmatrix}\tag{1}$$ 
I wrote the following Matlab function to build up the  $\Phi^*$, $\Gamma^*$, $G_y$:
function [FiFi,FiGam,Gy] = getFiFi_FiGa(Fi,Ga,C,N,Nc,n)
    
    FiFi=[]; %ennek a merete N*n x n kell legyen
    
    for i=1:N,    
        FiFi=[FiFi; C*Fi^i]; 
    end
    % FiGam szamitasa
    FiGam=[];
    for i=1:N,
        S=0;
        for j=0:i-1,       
            S=S+C*Fi^j*Ga;    
        end
        FiGam=[FiGam; S];
    end
    
    ng=size(FiGam,1);
    mg=size(FiGam,2);
    % Gy szamitasa
    Gy=zeros(ng,mg*Nc);
    % Gy szamitasa
    for j=1:mg:Nc*mg   % oszlopok         
        Gy(j:end, j:j+mg-1)=FiGam(1:end-j+1,:);
    end

end
To find the optimal control signal we have to solve the following optimization problem $J_k(u,x_k)=\frac{1}{2}\Delta u_k^TH\Delta u_k+f^T\Delta u_k+const$. I already presented the solution of this problem (see Model predictive control). I am going to  implement the calculation of the $\Delta u_k$ optimal control signal in the following example:
for v=1:n-N
    %Error vector
    E=Yref(v:v+N-1)-FiFi*x0-FiGam*u;
    
     deltau=inv(Gy'*Q*Gy+R)*Gy'*Q*E;
     u=u+deltau(1:2);
     for k=1:length(u)
         if(abs(u(k))>lim)
             u(k) = sign(u(k))*lim;
         end
     end
   
    x0 = Fi*x0+Ga*u;
    yt = C*x0;
    
    
    um=[um u];
    ym=[ym;yt];
end;

In the example above I also tried to constrain the control signal by choosing the $lim$ variable to 38. After choosing the values of the noise matrices as follows
  • $Q=eye(N*Nro)*1e4$ where $N$ is the number of the horizon and $Nro$ is the number of the outputs.
  • $R=eye(Nc*Nrin)*1e-5$ where $Nc$ is the number of the control horizon and $Nrin$ is the number of the inputs.
I got these results:
Figure 1. Rotor speed
Figure 2. Control signal
Figure 3. Error between the reference and measured rotor speed
We can reduce the error by increasing or eliminating the constrain of control signal as you can see in $Figure 4$
Figure 4. Error between the reference and measured rotor speed without limiting the control signal
The other solution  of the optimal control signal calculation in Matlab is the built in $quadprog$ function. You can find a simple example below, also you can read the description of this function on the Matlab help page:
H=2*(Gy'*Q*Gy+R);
for v=1:n-N
    %Hiba vektor    
    E=Yref(v:v+N-1)-FiFi*x0-FiGam*u;
    
    f=-2*E'*Q*Gy;        
    
    b = [abs(lim-u(1));
        abs(lim+u(1))];
    A = [1 0 0 0 0 0 0 0;
        -1 0 0 0 0 0 0 0;
        ];
     
    Aeq=[];beq=[];
    
    [deltau,FVAL,EXITFLAG]=quadprog(H,f,A,b,Aeq,beq);
    u=u+deltau(1:2);
    
   
    x0 = Fi*x0+Ga*u;
    yt = C*x0;    
    
    um=[um u0];
    ym=[ym;yt];
    Em = [Em;E];
end;

Appendix

Motor parameters:
    Rm = 0.35;
    Km=0.0296;
    Ke = 0.0296;
    b = 6.7*10e-5;
    J = 2.9*10e-6;
    Fc = 0.02;
    L = 25 *10e-6;
    Ts = 1e-4;

Saturday, November 17, 2012

Model predictive control

Introduction

The Model Predictive Controller (MPC) theory was developed after 1960, being a special case of the optimal control theory. In the MPC theory the dynamic optimization problem will be rewritten as  a static optimization problem. In the MPC theory they are using the varying control horizon theorem. The static optimization problem will be solved at each time step.
The MPC has the following properties:
  • possibility to constrain the control signal
  • adopts the time delays in the system 
  • possibility to compensate the sensors error
  • simple implementations of MIMO and LTI systems
We consider the discrete LTI sytem:
$$x_{k+1}=\Phi_kx_k+\Gamma_ku_k\\y_k=Cx_k\tag{1}$$
The control objective at time $k$ to minimize the following quadratic cost function:
$$J_k(u,x_k)=\sum_{j=1}^N||e_{k+j|k}||^2_{Q_j}+||\Delta u_{k+j-1|k}||^2_{R_j}\tag{2}$$
where
$e_{k}=y_k-y^{ref}_{k}$ is the error between the reference trajectory and the measured trajectory,
$\Delta u_{k+j|k}=u_{k+j|k}-u_{k+j-1|k}$ is the change of the input signal between two steps.  
In the $k$ step we already know the $u_{k-1}$, hence we can write
$$u_{k|k}=\Delta u_{k|k}+u_{k-1}\\u_{k+1|k}=\Delta u_{k+1|k}+\Delta u_{k|k}+u_{k-1} \\ \vdots \\ u_{k+N_c-1|k}=\Delta u_{k+N_c-1|k}+\cdots+\Delta u_{k|k}+u_{k-1} \tag{3}$$
The states predictions will be as follows:
$$x_{k+1|k}=\Phi x_{k|k}+\Gamma \left(\Delta u_{k|k}+u_{k-1}\right) \\ x_{k+2|k}=\Phi^2 x_{k|k}+\left(\Phi+I\right)\Gamma \Delta u_{k|k}+\Gamma u_{k+1|k}+\left(\Phi+I\right)\Gamma u_{k-1|k}\\ \vdots \\x_{k+N_c|k}=\Phi^{N_c} x_{k|k}+\left(\Phi^{N_c-1}+\cdots+\Phi+I\right)\Gamma \Delta u_{k|k}\\+\cdots+\Gamma u_{k+N_c-1|k}+\left(\Phi^{N_c-1}+\cdots+\Phi+I\right)\Gamma u_{k-1|k}\tag{4}$$
After some algebraic operations we can write the equations from above in matrix form:
$$\begin{bmatrix}x_{k+1|k} \\ \vdots \\ x_{k+N_c|k} \\ x_{k+N_c+1|k} \\ \vdots \\ x_{k+N|k} \end{bmatrix}=\begin{bmatrix}\Phi \\ \vdots \\ \Phi^{N_c} \\ \Phi^{N_c+1} \\ \vdots \\ \Phi^N \end{bmatrix}x_k + \begin{bmatrix}\Gamma \\ \vdots \\ \sum_{i=0}^{N_c-1} \Phi^{i} \Gamma\\ \sum_{i=0}^{N_c}\Phi^{i} \Gamma\\ \vdots \\ \sum_{i=0}^{N}\Phi^i \Gamma \end{bmatrix}u_{k-1}\\+ \begin{bmatrix}\Gamma & \cdots & 0 \\ \vdots & \ddots & \vdots \\ \sum_{i=0}^{N_c}\Phi^{i} \Gamma & \cdots & \Phi \Gamma+\Gamma \\ \vdots & \ddots & \vdots \\ \sum_{i=0}^{N-1}\Phi^i \Gamma & \cdots & \sum_{i=0}^{N-N_c}\Phi^i \Gamma \end{bmatrix} \begin{bmatrix}\Delta u_{k+1|k} \\ \vdots \\ \Delta u_{k+N_c-1|k} \end{bmatrix}\tag{5}$$
$$y_{k+j|k}=C x_{k+j|k}\tag{6}$$

From the $5^{th}$ and $6^{th}$ equation we can write the following:
$$y_k=\Phi^*x_k+\Gamma^*u_{k-1}+G_y\Delta u_k\tag{7}$$
And the error is
$$e_k=y^{ref}_k-\Phi^*x_k-\Gamma^*u_{k-1}\tag{8}$$

The idea behind the MPC is to rewrite the dynamic optimisation problem as a static optimization problem:
$$J_k(u,x_k)=||y_k-y^{ref}_k||^2_{Q_j}+||\Delta u_{k}||^2_{R_j}\tag{9}$$
where
$$e_k=\begin{bmatrix}e_{k+1|k} \\ \vdots \\ e_{k+N|k} \end{bmatrix}, \Delta u_k=\begin{bmatrix}\Delta u_{k+1|k} \\ \vdots \\ \Delta u_{k+N_c-1|k} \end{bmatrix}\tag{10}$$
$$Q=\begin{bmatrix}Q_1 & 0 & \cdots & 0 \\ 0 & Q_2 & \cdots & 0 \\ \vdots & \vdots & \ddots & \vdots \\ 0 & 0 & \cdots & Q_N \end{bmatrix}, R=\begin{bmatrix}R_1 & 0 & \cdots & 0 \\ 0 & R_2 & \cdots & 0 \\ \vdots & \vdots & \ddots & \vdots \\ 0 & 0 & \cdots & R_{N_c-1} \end{bmatrix}\tag{11}$$ 
From the $8-9$ equations we can deduce
$$J_k(u,x_k)=||G_y\Delta u_k-E_k||^2_{Q_j}+||\Delta u_{k}||^2_{R_j}\\=\left[\Delta u_k^TG_y^T-E_k^T\right]Q\left[\Delta u_kG_y-E_k\right]+\Delta u_k^TR\Delta u_k\\=\Delta u_k^T\left[G^T_yQG_y+R\right]\Delta u_k-2E^T_kQG_y\Delta u_k+E_k^TQE_k\\=\frac{1}{2}\Delta u_k^TH\Delta u_k+f^T\Delta u_k+const\tag{12}$$
where
$$H= 2\left[G^T_yQG_y+R\right]\tag{13}$$
$$f=-2G_y^TQE_k\tag{14}$$
To get the optimal control signal with the inequality conditions, we have to solve the  $min_{\Delta u_k}\left\{J_k(u,x_k)\right\}$. There is a well know solution of this optimal problem called quadratic programming. In Matlab there is the $quadprog$ function to solve the optimization problem. There is also some C/C++ implementations, one that I know is the ACADO Toolkit. One of the disadvantages of the solution is the time consumption, because of this the sampling time will be bigger therefore it could increase the instability of the system.  
Differentiating (12) the decisions $u_k$ and setting the result equal to zero the optimal control sequence is obtained as seen below:
$$\Delta u_k =\left[G^T_yQG_y+R\right]^{-1}G_y^TQE_k\tag{15}$$
Note that the optimal control deviation ($\Delta u_k$ ) gives offset free control in steady state. The expression above is true if we assume that the control signal changes between two steps is zero. 

Stability check

Hence stability can easily be established a posteriori by checking that the eigenvalues of the closed loop system matrix $\Phi+\Gamma K$ are strictly inside the unit circle, where
$$K=\left[G^T_yQG_y+R\right]^{-1}G_y^TQ\tag{16}$$

$N_c$ is the control horizon
$N$ is the prediction horizon

Wednesday, October 31, 2012

Speed sensorless robust control of PMSM

In this post I will present the speed sensorless control of PMSM. Before You start reading this article please read the following posts, because these articles are related to this topic and I don't detailing here again:
  1. Extended Kalman Filter
  2. Linear Quadratic Regulator
  3. Dynamic model of a PMSM 
The model of the PMSM is nonlinear, to linearise the system I used the state feedback linearisation. The states can be measured or estimated. In this blog I will present a sensorless solution using the extended Kalman filter.

State estimation

For the motor model linearisation I need to know the direct axis, quadratic axis current and the speed of the rotor. 
It has the following system:
$$x_{k+1}=Ax_k+Bu_k+Ew\\y=Cx_k+Du_k\tag{1}$$
Where the states are:
$$\left[\begin{array}{c} i_d \\ i_q  \\ \omega_r  \\ \theta \\ T_L \end{array}\right]\tag{2}$$
Using the $3-8$ equations from the Dynamic model of a PMSM post, I can write the state space model of the PMSM, also I assume that the changes of the mechanical torque is small or it is constant.
$$A = \begin{bmatrix}  -\frac{R}{L_d} & \frac{L_qP\omega_r}{L_d} & 0 & 0 & 0\\ -\frac{L_dP\omega_r}{L_q} & -\frac{R}{L_q} & -\frac{PL_m}{L_q} & 0 & 0 \\ 0 & \frac{3}{2}\frac{P}{J}\left(L_m+\left(L_d-L_q\right)i_d\right) & -\frac{B}{J} & 0 & -\frac{1}{J}\\ 0 & 0 & 1 & 0 & 0\\0 & 0 & 0 & 0 & 0\end{bmatrix}\tag{3}$$
$$B= \begin{bmatrix}\frac{1}{L_d} & 0 \\ 0 & \frac{1}{L_q} \\ 0 & 0\\ 0 & 0\\ 0 & 0\end{bmatrix}\tag{4}$$
The model can be discretized by using the following approach:
$$A_d=e^{AT} \approx I+AT\tag{5} $$
$$B_d=\int_0^T e^{At}B dt \approx BT\tag{6}$$
The discretized discrete state space system matrices is as follows:
$$A_k = \begin{bmatrix}  1-T_s\frac{R}{L_d} & T_s\frac{L_qP\omega_r}{L_d} & 0 & 0 & 0\\ -T_s\frac{L_dP\omega_r}{L_q} & 1-T_s\frac{R}{L_q} & -T_s\frac{PL_m}{L_q} & 0 & 0 \\ 0 & T_s\frac{3}{2}\frac{P}{J}\left(L_m+\left(L_d-L_q\right)i_d\right) & 1-T_s\frac{B}{J} & 0 & -T_s\frac{1}{J}\\ 0 & 0 & T_s & 1 & 0\\0 & 0 & 0 & 0 & 1\end{bmatrix}\tag{7}$$
$$B_k= \begin{bmatrix}\frac{T_s}{L_d} & 0 \\ 0 & \frac{T_s}{L_q} \\ 0 & 0\\ 0 & 0\\ 0 & 0\end{bmatrix}\tag{8}$$
and the Jacobian matrix is:
$$G_k=\begin{bmatrix}  1-T_s\frac{R}{L_d} & T_s\frac{L_qP\omega_r}{L_d} & T_s\frac{L_qPi_q}{L_d} & 0 & 0\\ -T_s\frac{L_dP\omega_r}{L_q} & 1-T_s\frac{R}{L_q} & -T_s\frac{PL_m+L_dPi_d}{L_q} & 0 & 0 \\ T_s\frac{3}{2}\frac{P}{2J}\left(L_d-L_q\right)i_d & T_s\frac{3}{2}\frac{P}{J}\left(L_m+\left(L_d-L_q\right)i_d\right) & 1-T_s\frac{B}{J} & 0 & -T_s\frac{1}{J}\\ 0 & 0 & T_s & 1 & 0\\0 & 0 & 0 & 0 & 1\end{bmatrix}\tag{9}$$

Filter tunning

I used an AC6 Vector Control for an interior Permanent Magnet Synchronous Motor (PMSM) simulink model to simulate and tune the estimators R,Q covariance matrices:
Figure 1.
Choosing the following covariance matrices:
$$Q=diag\left(\begin{array}{c} 1e-3 & 1e-3 & 1e-1 & 1e-9 & 1e-1\end{array}\right)\\R=diag\left(\begin{array}{c}1e3 & 1e3\end{array}\right)\tag{10}$$
the estimated speed is hence:
Rotor speed

Linear Quadratic Regulator

I already wrote a short introduction about the LQR, now I will present only the results. As I mentioned before, to control the system I need to know only the currents and the rotor velocity, so I have the following states:
$$\left[\begin{array}{c} i_d & i_q & w_r\end{array}\right]\tag{11}$$
In this case the state space model is as follows:
$$A_k = \begin{bmatrix}  1-T_s\frac{R}{L_d} & T_s\frac{L_qP\omega_r}{L_d} & 0 \\ -T_s\frac{L_dP\omega_r}{L_q} & 1-T_s\frac{R}{L_q} & -T_s\frac{PL_m}{L_q} \\ 0 & T_s\frac{3}{2}\frac{P}{J}\left(L_m+\left(L_d-L_q\right)i_d\right) & 1-T_s\frac{B}{J}\end{bmatrix}\tag{12}$$
$$B_k= \begin{bmatrix}\frac{T_s}{L_d} & 0 \\ 0 & \frac{T_s}{L_q} \\ 0 & 0\end{bmatrix}\tag{13}$$
$$C=\left[\begin{array}{c} 0 & 0 & 1\end{array}\right]\tag{14}$$
$$D=[0]$$

choosing the LQR state and input weighing matrices in this way:
$$R=\left[\begin{array}{c} 1e-8 & 1e-8 \end{array}\right]\\Q=\left[\begin{array}{c} 1e1 \end{array}\right]\tag{15}$$
and the horizon to 2, the simulation result is the following:
Results
Error between the reference speed and the simulated speed using the LQR controller
LQR rotor speed error(N=2)
The error between the reference and simulated value using the ac6_example
Rotor speed error
As you can see, in the LQR the error is between 1 and -1.5 which is better than the other controller. Still there are possibilities to reduce the error by increasing the number of the horizon and changing the weight matrices.
Here is another result:
LQR rotor speed error(N=10)
Finally, I can put together the estimator and the controller, so I will end up with the following simulink model:
EKF with LQR
And the result by choosing N=2,



The first subplot is the reference speed and the measured speed, the second is the mechanical torque and the third is the error between the reference and the measured signal.





Monday, October 29, 2012

Dynamic model of a PMSM

The two phase equivalent circuit is widely used to analyse the permanent magnet synchronous machine. In this blog I will present the two phase equivalent circuit of the PMSM dynamic model. 
The three phase electrical dynamic equations can be written as:
$$U_a^S=R_sI_a^S+\frac{d\psi_a^S}{dt}\\U_b^S=R_sI_b^S+\frac{d\psi_b^S}{dt}\\U_c^S=R_sI_c^S+\frac{d\psi_c^S}{dt}\tag{1}$$
where the index $S$ denotes the stator coordinate system.
Also the motor model can be express in the rotating coordinate system
$$U^R=R_sI^R+\frac{d\psi^R}{dt}+j\omega\psi^R\tag{2}$$
Now we can write in the two phase equivalent circuit which is rotating with the same frequency as the rotate magnetic field.
$$u_d=R_sI_d+\frac{d\psi_d}{dt}-\omega\psi_q\tag{3}$$
$$u_q=R_sI_q+\frac{d\psi_q}{dt}+\omega\psi_d\tag{4}$$
where
$$\psi_d=L_dI_d+L_m\tag{5}$$
$$\psi_q=L_qI_q\tag{6}$$
The produced torque can be expressed as:
$$T_e=\frac{3P}{2}\left(L_mI_q+(L_d-L_q)I_d\right)I_q\tag{7}$$
and the motor dynamics can be represented by:
$$T_e=J\frac{d\omega_r}{dt}+B\omega_r+T_L\tag{8}$$ 

Coordinate transformation 

Figure 1. PMSM
As you can see in figure 1, the three phase stationary reference frame can be transformed directly into a two phase reference frame using Park's transformation. Let X represent any of the variables (current, voltage, fluxe), the transformation matrix is given by[4]
$$\left[ \begin{array}{c} X_d \\ X_q \\ X_0 \end{array} \right] =\frac{2}{3} \begin{bmatrix} sin(\theta) & sin(\theta-\frac{2\pi}{3}) & sin(\theta+\frac{2\pi}{3}) \\ cos(\theta) & cos(\theta-\frac{2\pi}{3}) & cos(\theta+\frac{2\pi}{3}) \\ \frac{1}{2} & \frac{1}{2} & \frac{1}{2} \end{bmatrix}\left[ \begin{array}{c} X_a \\ X_b \\ X_c \end{array} \right]\tag{9}$$
The transformation can be a combination of two transformations. First the three phase reference frame can be transformed into a two phase reference frame($abc$ to $\alpha\beta$) by replacing $\theta$ with 0
$$\left[ \begin{array}{c} X_\alpha \\ X_\beta \\ X_0 \end{array} \right] =\frac{2}{3} \begin{bmatrix} 0 & -{\sqrt3\over2} & {\sqrt3\over2} \\ 1 & -{1\over2} & -{1\over2} \\ \frac{1}{2} & \frac{1}{2} & \frac{1}{2} \end{bmatrix}\left[ \begin{array}{c} X_a \\ X_b \\ X_c \end{array} \right]\tag{10}$$
The second transformation is a conversion from stationary to rotating reference frame ($\alpha\beta$ to $dq$)
$$\left[ \begin{array}{c} X_d \\ X_q \\ X_0 \end{array} \right] = \begin{bmatrix}  cos(\theta) & sin(\theta) & 0 \\ -sin(\theta) & cos(\theta) & 0 \\ 0 & 0 & 1 \end{bmatrix}\left[ \begin{array}{c} X_\alpha \\ X_\beta \\ X_0 \end{array} \right]\tag{9}$$

Appendix:

$P$ - Pole pairs
$R$ - Stator phase resistance
$L_m$ - Permanent magnets flux
$B$ - Viscous friction coefficient
$J$ - Inertia
$L_d$ - Direct axis inductance
$L_q$ - Quadrature axis inductance
$\omega$ - Angular velocity

Sources:

  1. Dal Y. Ohm: DYNAMIC MODEL OF PM SYNCHRONOUS MOTORS
  2. Wikipedia: dqo transformation
  3. Mohamed S. Zaky: Adaptive and robust speed control of interior permanent magnet synchronous motor drives
  4. Lecture Set 6.pdf

Monday, October 22, 2012

LQ speed regulation of a brushed DC motor

In the following post I will present a speed controller of the brushed DC motor using LQR. I will also introduce the Kalman filter to estimate the motor speed and torque. 
System diagram
I already introduced the state space model of the brushed DC machine, in this post I will introduce only the controller. 

Discrete state tracking linear quadratic regulator

Have the following linear discrete system
$$x_{k+1}=A_kx_k+B_ku_k\\
y_k=H_kx_k\tag{1}$$

Let us presume that $z_k$ is the trajectory what we would like to follow, in this case we have to determine the optimal control signal which optimize the quadratic criterion:
$$
J(u) = min\left[e_N^TFe_N+\sum_k{e_k^TQ_ke_k+\delta u_k^TR_k\delta u_k}\right]\tag{2}
$$
Where  $e=z_k-y_k$ and $\delta u_k=u_k-up_k$.
Bellman's equation of the corresponding control problem is:
$$
J_{min_k}(u) = min\left[e_k^TQ_ke_k+\delta u_k^TR_k\delta u_k+J_{min_{k+1}}(u)\right]\tag{3}
$$
Expressing the cost of termination point as:
$$
J_{min_N}(u)=\left[z_N-H_Nx_N\right]^TF\left[z_N-H_Nx_N\right]\tag{4}
$$Introduce the following expressions:
$$P_N=H_N^TF_NH_N\\ p_{N_0}=z_N^TFz_N\\ g_N^T=-2z_N^TFH_N\tag{5}$$
Where $N$ is the number of the horizon and $k$ is the iteration.
The cost function will be the following:
$$
J_{min_k}(u)=p_{k_0}+g_k^Tx_k+x_k^TP_kx_k\tag{6}
$$
where the Belman's equation is:
$$
J_{min_k}(u)=min\left[e_k^TQ_ke_k+\delta u_k^TR_k\delta u_k+p_{(k+1)_0}+g_{k+1}^Tx_{k+1}+x_{k+1}^TP_kx_{k+1}\right]\tag{7}
$$
Considering that in the $k$ iteration the $u_k$ optimal control minimizes the criterion $J(u)_k$, we can write the following relation
$$u_k=\left[R_k+B_k^TP_{k+1}B_k\right]^{-1}\left[R_kup_k+\frac{1}{2}B_kg_{k+1}-B_k^TP_{k+1}A_kx_k\right]\tag{8} $$
The recursive discrete Ricatti equation is the following:$$P_k=H_k^TQ_kH_k-A_k^TP_{k+1}B_k\left[R_k+B_k^TP_{k+1}B_k\right]^{-1}\\B_k^TP_{k+1}A_k+A_k^TP_{k+1}A_k\tag{9}$$respecting the final condition:
$$P_N=H_N^TF_NH_N\tag{10}$$
We can express the optimal control signal in the following form:
$$u_k=K_kx_k+f_k\tag{11}$$
where
$$K_k=-\left[R_k+B_k^TP_{k+1}B_k\right]^{-1}B_k^TP_{k+1}A_k\tag{12}$$
$$f_k=-\frac{1}{2}\left[R_k+B_k^TP_{k+1}B_k\right]^{-1}\left[B_k^Tg_{k+1}\right]\tag{13}$$
After performing some algebraic calculations, we will end up with the following equation:$$g_k^T=-2z_k^TQ_kH_k+g_{k+1}\left[A_k+B_kK_k\right]^T\tag{14}$$
with boundary condition:
$$g_N^T=-2z_N^TFH_k\tag{15}$$

Results 

The steady state error depends on the number of the horizon ($N$), the accuracy of the system model and the state estimation. Choosing the number of the horizon to five the rotor speed is the following:
 The controller signal is depending of the accuracy of the state estimator

Choosing the number of the horizon more than 15, the steady state error was 0. The number of the horizon, and the limitation of the control signal are influences the overshoot. One of the disadvantages of the LQR is that the optimal signal calculation doesn't include the signal limitation, thus a bigger control signal can be calculated than you can physically achieve.

Python implementation

The Python implementation of the state tracking LQR is under the following link. Feel free to fork. It was harder to implement into Python than Matlab, but finally I succeeded. In the T_DCMotor.py you can find two controller, one is a PID controller
pid  =  PID( KP = 0.2, KI = 100, KD = 0.00001 
for i in range( len( pw ) ):
    #Calculate the error
    error = pw[i] - sw;
    #Calculating the control signal
    u = pid.run( error, Ts = Ts )
    if( abs( u ) > 220 ):
        u = sign( u ) * 220; 

    #Simulating
    ( sw, x ) = dc2.dlsim( u , torque[0, i ] );
    y_out[i, :] = sw
    u_out[i, :] = u 

The other is the LQR state tracker controller with Kalman filter
dlqr = DSTLQR( Ak, Bk, Ck, N )
kf = dKF( x_est, Ak, Bk, H )

for i in range( len( pw ) - N ): 
   #Calculation the optimal control signal
   U = dlqr.calcU( x_est, array( [pw[i:i + N]] ) ) 
   if( abs( U ) > 220 ):
     U = sign( U ) * 220;

   #Simulating
   ( sw, x ) = dc2.dlsim( U, torque[0, i ], Ts = Ts );
   y_out[i, :] = sw
   u_out[i, :] = U

   #Estimating the states
   ( x_est, P, error ) = kf.update( x[0, 0] , U )

   y_est[i, :] = x_est[1]; 

Matlab source code

I used a discrete Kalman filter to estimate the torque and the rotor speed, here is the code of the Kalman filter:
% Created by Róbert Ungurán
% GPLv2
%******************************************************
% Dc motor discrete model
%******************************************************
% Input 
%   I_in - Measured current
%   U_in - Measured voltage
%******************************************************
% Output
%   x_out - Estimated state variables
function x_out = kf(I_in,U_in)

    global Ts  Rm L Ke Kd J Km;
    
    persistent x
    persistent P
    if isempty(x)
        x = [0;0; 0];        
        P = zeros(3);
    end
    % Armature current, rotor speed, Torque
    Ak  =   [1-Ts*(Rm/L)  -Ts*(Ke/L)        0;
            Ts*(Km/J)    1-Ts*(Kd/J)    -Ts/J;
            0               0               1;];

    Bk  =   [Ts*1/L; 0; 0];

    H   =   [1 0 0];
    
    
    R   =   1e-3;
    Q   =   diag([1e-6 1e-2 1e-2]);
    
    
    x   =   Ak*x + Bk*U_in;
   
    P   =   Ak * P * Ak' + Q;
    
   
    % Compute Kalman gain factor:
    S   =   H*P*H'+R;
    K   =   P*H'*inv(S);

    % Correction based on observation:
    error = I_in-H*x;
    x   =   x + K*error;
    P   =   P - K*H*P;
    
    x_out   =   x;
end
The source of the discrete linear quadratic regulator
% Created by Róbert Ungurán
% GPLv2
%******************************************************
% LQR controller of a DC motor
%******************************************************
% Input 
%   I       - Measured current
%   w       - Measured rotor speed
%   w_ref   - Reference rotor speed 
%******************************************************
% Output
%   U - Control signal
function U = mydlqr(I,w,Tl,w_ref)   
  
    global Ts  Rm L Ke Kd J Km N;
    
    x = [I;w;Tl];

    Ak  =   [1-Ts*(Rm/L)  -Ts*(Ke/L)        0;
            Ts*(Km/J)    1-Ts*(Kd/J)    -Ts/J;
            0               0               1;];

    Bk = [Ts*1/L; 0; 0];

    Ck = [0 1 0];

    Dk = [0];   
   
    
    [n,m] = size(Bk);
    [p,n] = size(Ck);
    
    R=eye(m)*0.001;
    Q=eye(p)*10;
    F=Q;
    
    PN = Ck'*F*Ck; 
    gN =  (-2*w_ref(1)'*F*Ck)';    
    
    
    for j=N:-1:1        
        K = (-inv(R+Bk'*PN*Bk)*Bk'*PN*Ak);
        fk = (-1/2)*inv(R+Bk'*PN*Bk)*Bk'*gN;       
        gN = (-2*w_ref(:,N-1)'*Q*Ck+gN'*(Ak+Bk*K))';
        PN = Ck'*Q*Ck-Ak'*PN*Bk*inv(R+Bk'*PN*Bk)*Bk'*PN*Ak+Ak'*PN*Ak;            
    end
     
    U = K*x+fk;
    
end
The main source code
clear all
close all
clc

%% Initialization
global Ts  Rm L Ke Kd J Km N Fc;

Rm  =   0.35;
Km  =   0.0296;
Ke  =   0.0296;
Kd  =   6.7*10e-5;
J   =   2.9*10e-6;
Fc  =   0.02;
L   =   25 *10e-6;
Ts  =   1e-5;
N   =   5;

x       =   [0;0;0];
w_ref   =   [ones(1,1000)*200 ones(1,1000)*400];
torque  =   [ones(1,1500)*2.0 ones(1,500)*1.0];
[n,m]   =   size(w_ref);
u   =   [];
w   =   [];
x_est = [0; 0; 0];
x_est_o = [0; 0; 0];


for i=1:m-N
    %% Calculation the optimal control signal
    %Input Current, Rotation speed, Rotation speed references
    U   =   mydlqr(x_est(1),x_est(2),x_est(3), w_ref(i:i+N));
    if(abs(U) > 380)
        U = sign(U)*380;
    end
    u   =   [u U];
    
    %% Simulation the model
    %Current, Rotation speed, Rotation position    
    [x(1), x(2), x(3)]  =   dc_motor(U, torque(i));
    w   =   [w x(2)];
    %% Estimating the states
    x_est   =   kf(x(1), U);
    
    x_est_o =   [x_est_o x_est];    
    
end

%% Visualization
plot(u);
figure;
plot(x_est_o(3,:));
figure;
hold on;
plot(w_ref, 'b-');
plot(w, 'r-');
plot(x_est_o(2,:), 'g-');
legend('Reference','Simulated', 'Estimated');

Wednesday, October 3, 2012

ACIM speed estimation

In case if we would like to know the induction motor rotor speed, we can use Extended Kalman Filter(EKF) to estimate the unknown states. Here is a good tutorial where you can find more information about the EKF. Also you can read the article on the Wikipedia. I'm using the FOC block in Matlab to get the motor control current, voltage and the angle between the fluxes, just for testing purpose.
I assume that the rotor speed is constant so $\frac{d\omega_r}{dt}=0$. In this case we have the following model
$$
A= \begin{bmatrix} -\frac{R_s+\frac{L_m^2R_r}{L_r^2}}{L_s\sigma} & 0 &  \frac{L_m}{L_s\sigma L_r\tau_r} & \frac{\omega_rL_m}{L_s\sigma L_r} & 0 \\ 0 & -\frac{R_s+\frac{L_m^2R_r}{L_r^2}}{L_s\sigma}  & -\frac{\omega_rL_m}{L_s\sigma L_r} & \frac{L_m}{L_s\sigma L_r\tau_r} & 0 \\ \frac{L_m}{\tau_r} & 0 & -\frac{1}{\tau_r} & -\omega_r & 0 \\ 0 & \frac{L_m}{\tau_r} &   \omega_r & -\frac{1}{\tau_r}  & 0 \\ 0 & 0 & 0 & 0 & 0\end{bmatrix}\tag{1}
$$
$$B=\begin{bmatrix} \frac{1}{L_s\sigma} & 0 \\ 0 & \frac{1}{L_s\sigma} \\ 0 & 0 \\ 0 & 0 \\ 0 & 0 \end{bmatrix}\tag{2}$$

We can discretize the model using the following approach:
$$A_d=e^{AT} \approx I+AT\tag{3} $$
$$B_d=\int_0^T e^{At}B dt \approx BT\tag{4}$$

The Simulink model is the following

In the block above, the second and third module are the Clarke's and Park's transformation, in the previous articles I already defined this transformations. The code of the speed and flux estimator is

function [xx_out,PP_out,error,W]=ekf(I,U,Ts)
% EKF   Extended Kalman Filter  
% induction motor's parameters   
persistent PP;
persistent xx;

if isempty(PP)
    xx = [0 0 0 0 0 ]';
    %[i_alfa , i_beta , Fi_r_alfa , Fi_r_beta , W_r ]
    PP = 1e-2*diag([1 1 1 1 1]);
end
Q =  diag([1e-4 1e-4 1e-9 1e-9 5e-4]);
R =  1e1*diag([1 1]);

L_r=0.479;
L_s=0.423;
L_m=0.421;
R_s=5.27;
R_r=5.07;

tau_r = L_r/R_r;
gamma_r = 1-(L_m^2)/(L_s*L_r);
T_r = R_s+(L_m^2*R_r)/L_r^2;
 
Ak =[ 1-Ts*(T_r/(L_s*gamma_r)),          0,        Ts*(L_m/(L_s*gamma_r*L_r*tau_r)),        Ts*((xx(5)*L_m)/(L_s*gamma_r*L_r)),        0;
    0,                  1-Ts*(T_r/(L_s*gamma_r)), -Ts*((xx(5)*L_m)/(L_s*gamma_r*L_r)),     Ts*(L_m/(L_s*gamma_r*L_r*tau_r)),        0;
    Ts*(L_m/tau_r),                  0,                   1-Ts*(1/tau_r),                  -Ts*xx(5),                                    0;
    0,                      Ts*(L_m/tau_r),                  Ts*xx(5),                      1-Ts*(1/tau_r),                         0;
    0                           0                           0                    0                                           1];

Bk = [Ts/(L_s*gamma_r)              0;
            0                Ts/(L_s*gamma_r);
            0                       0;
            0                       0;
            0                       0];

%Predictor
xx = Ak*xx+Bk*U;


Gk =[ 1-Ts*(T_r/(L_s*gamma_r)),          0,        Ts*(L_m/(L_s*gamma_r*L_r*tau_r)),        Ts*((xx(5)*L_m)/(L_s*gamma_r*L_r)),        Ts*((xx(4)*L_m)/(L_s*gamma_r*L_r));
    0,                  1-Ts*(T_r/(L_s*gamma_r)), -Ts*((xx(5)*L_m)/(L_s*gamma_r*L_r)),     Ts*(L_m/(L_s*gamma_r*L_r*tau_r)),        -Ts*((xx(3)*L_m)/(L_s*gamma_r*L_r));
    Ts*(L_m/tau_r),                  0,                   1-Ts*(1/tau_r),                  -Ts*xx(5),                                    -Ts*xx(4);
    0,                      Ts*(L_m/tau_r),                  Ts*xx(5),                      1-Ts*(1/tau_r),                         Ts*xx(3);
    0                           0                           0                           0                                           1];

H = [1 0 0 0 0;
     0 1 0 0 0;];

PP=Gk*PP*Gk'+Q;

%Coorection
KalG=PP*H'*inv(H*PP*H'+R);
error = I-H*xx;
xx=xx+KalG*(error);
PP=(eye(5)-KalG*H)*PP;

xx_out = xx;
PP_out=PP;

W = xx(5);

I spent a lot of time to tune the filter matrices Q,R, but this is the best result what I got.
I wasn't satisfied with the result above so I extended this model with the torque, in this case the rotor speed can be expressed as follows:
$$
\frac{d\omega_r}{dt} =\frac{3p^2L_m}{8JL_r}\left(i_{sq}\psi_{rd}-i_{sd}\psi_{rq}\right)-\frac{p}{2J}T_l\tag{5}
$$
we assume that the torque is constant or the changes between two sampling time is very small
$$
\frac{dT_l }{dt}=0\tag{6}
$$
In this case the EKF's code is
function [xx_out,PP_out,error,W]=ekf(I,U,Ts)
% EKF   Extended Kalman Filter  
% induction motor's parameters   
persistent PP;
persistent xx;

if isempty(PP)
    xx = [0 0 0 0 0 0]';
    %[i_alfa , i_beta , Fi_r_alfa , Fi_r_beta , W_r ]
    PP = 1e-8*diag([1 1 1 1 1 1]);
end
Q =  diag([1e-3 1e-3 1e-9 1e-9 1e-5 1e-5]);
R =  1e-3*diag([1 1]);

L_r=0.479;
L_s=0.423;
L_m=0.421;
R_s=5.27;
R_r=5.07;
p = 2;
J =0.02;
fv = 0.0038;

m = (3*p^2*L_m)/(8*J*L_r);

tau_r = L_r/R_r;
gamma_r = 1-(L_m^2)/(L_s*L_r);
T_r = R_s+(L_m^2*R_r)/L_r^2;
 
Ak =[ 1-Ts*(T_r/(L_s*gamma_r)),          0,        Ts*(L_m/(L_s*gamma_r*L_r*tau_r)),        Ts*((xx(5)*L_m)/(L_s*gamma_r*L_r)),             0       0;
    0,                  1-Ts*(T_r/(L_s*gamma_r)), -Ts*((xx(5)*L_m)/(L_s*gamma_r*L_r)),     Ts*(L_m/(L_s*gamma_r*L_r*tau_r)),                0       0;
    Ts*(L_m/tau_r),                  0,                   1-Ts*(1/tau_r),                  -Ts*xx(5),                                       0       0;
    0,                      Ts*(L_m/tau_r),                  Ts*xx(5),                      1-Ts*(1/tau_r),                                 0       0;
    -Ts*m*xx(4)                  Ts*m*xx(3)                       0                               0                                   1           (-p*Ts)/(J*2);
           0                    0                               0                               0                                   0               1];

Bk = [Ts/(L_s*gamma_r)              0;
            0                Ts/(L_s*gamma_r);
            0                       0;
            0                       0;
            0                       0;
            0                       0];

%Predictor
xx = Ak*xx+Bk*U;


Gk =[ 1-Ts*(T_r/(L_s*gamma_r)),          0,        Ts*(L_m/(L_s*gamma_r*L_r*tau_r)),        Ts*((xx(5)*L_m)/(L_s*gamma_r*L_r)),        Ts*((xx(4)*L_m)/(L_s*gamma_r*L_r))   0;
    0,                  1-Ts*(T_r/(L_s*gamma_r)), -Ts*((xx(5)*L_m)/(L_s*gamma_r*L_r)),     Ts*(L_m/(L_s*gamma_r*L_r*tau_r)),        -Ts*((xx(3)*L_m)/(L_s*gamma_r*L_r))     0;
    Ts*(L_m/tau_r),                  0,                   1-Ts*(1/tau_r),                  -Ts*xx(5),                                    -Ts*xx(4)                          0;
    0,                      Ts*(L_m/tau_r),                  Ts*xx(5),                      1-Ts*(1/tau_r),                                 Ts*xx(3)                        0;
    -Ts*m*xx(4)              Ts*m*xx(3)                       Ts*m*xx(2)                       -Ts*m*xx(1)                                      1                           (-p*Ts)/(J*2);
    0                               0                           0                           0                           0                                           1];                         
             
H = [1 0 0 0 0 0;
     0 1 0 0 0 0;];

PP = Gk*PP*Gk'+Q;


KalG = PP*H'*inv(H*PP*H'+R);
error = I-H*xx;
xx = xx + KalG*(error);
PP = (eye(6)-KalG*H)*PP;

xx_out = xx;
PP_out = PP;

W = xx(5);

The result is

The error between the measured and the estimated is smaller than the previous model, also it was easier to tune the estimator. The disadvantage of the model, that is has six state which means that the calculations takes longer than the previous model.

Saturday, September 22, 2012

ACIM model in rotor fixed reference frame

In case of a direct torque control we can use the rotor fixed frame, which means that the $\omega_\gamma=0$. In this case we can describe the motor with the following equations(you can find the deduction under the following link)
$$
\begin{bmatrix} u_{sd} \\ u_{sq} \end{bmatrix}=R_r \begin{bmatrix} i_{sd} \\ i_{sq} \end{bmatrix} +\frac{d}{dt}\begin{bmatrix} \psi_{sd} \\ \psi_{sq} \end{bmatrix}\tag{1}
$$
$$\begin{bmatrix} u_{rd} \\ u_{rq} \end{bmatrix}=R_r \begin{bmatrix} i_{rd} \\ i_{rq} \end{bmatrix} +\frac{d}{dt}\begin{bmatrix} \psi_{rd} \\ \psi_{rq} \end{bmatrix}+\omega_r\begin{bmatrix} \psi_{rd} \\ -\psi_{rq} \end{bmatrix}\tag{2}$$
The motor torque can be expressed the rotor flux magnitude $\psi_r$ and stator current component $i_s$
$$
T_e =  \frac{3p L_m}{2 L_r}\left(\psi_{rd}i_{sq}-\psi_{rq}i_{sd}\right)\tag{3}
$$
and the flux equations are the following
$$\begin{bmatrix}\psi_{sd} \\ \psi_{sq}\end{bmatrix}=L_s\begin{bmatrix}i_{sd} \\ i_{sq} \end{bmatrix}+L_m\begin{bmatrix}i_{rd} \\ i_{rq} \end{bmatrix}\tag{4}$$
$$\begin{bmatrix}\psi_{rd} \\ \psi_{rq}\end{bmatrix}=L_m\begin{bmatrix}i_{sd} \\ i_{sq} \end{bmatrix}+L_r\begin{bmatrix}i_{rd} \\ i_{rq} \end{bmatrix}\tag{5}$$
I would like to estimate the rotor fluxes and the electrical motor speed $\omega_r$. In this case there are five state variables $\begin{bmatrix}i_{sd} & i_{sq} & \psi_{rd} & \psi_{rq} & \omega_r \end{bmatrix}$, to get the state variables we have to make a few arithmetic operations.
We would like to get the flux equations, after sorting the $2^{nd}$ equation we will end up with the following
$$\frac{d}{dt}\begin{bmatrix} \psi_{rd} \\ \psi_{rq} \end{bmatrix} = - R_r \begin{bmatrix} i_{rd} \\ i_{rq} \end{bmatrix} - \omega_r\begin{bmatrix} \psi_{rd} \\ -\psi_{rq} \end{bmatrix}+\begin{bmatrix} u_{rd} \\ u_{rq} \end{bmatrix}\tag{6}$$
We can't measure the rotor currents, but we can express the rotor currents using the $5^{th}$ equations.
$$\begin{bmatrix}i_{rd} \\ i_{rq} \end{bmatrix}=\frac{1}{L_r}\begin{bmatrix}\psi_{rd} \\ \psi_{rq}\end{bmatrix}-\frac{L_m}{L_r}\begin{bmatrix}i_{sd} \\ i_{sq} \end{bmatrix}\tag{7}$$
Replacing the rotor currents in the $6^{th}$ expression we will get the rotor flux equations
$$\frac{d}{dt} \begin{bmatrix} \psi_{rd} \\ \psi_{rq} \end{bmatrix} = -R_r \left(\frac{1}{L_r} \begin{bmatrix}\psi_{rd} \\ \psi_{rq} \end{bmatrix}-\frac{L_m}{L_r} \begin{bmatrix}i_{sd} \\ i_{sq} \end{bmatrix}\right) - \omega_r \begin{bmatrix} \psi_{rd} \\ -\psi_{rq} \end{bmatrix} $$ $$ \frac{d}{dt} \begin{bmatrix} \psi_{rd} \\ \psi_{rq} \end{bmatrix} = \frac{L_m}{\tau_r} \begin{bmatrix}i_{sd} \\ i_{sq} \end{bmatrix} + \begin{bmatrix} -\frac{1}{\tau_r} & -\omega_r \\ \omega_r & -\frac{1}{\tau_r} \end{bmatrix} \begin{bmatrix} \psi_{rd} \\ -\psi_{rq} \end{bmatrix}\tag{8} $$
After those arithmetic operation we got the rotor's flux equations, to get the stator's current equations we replace the $1^{st}$ equation's stator fluxes using the $4^{th}$ expressions, also we have to replace in the $4^{th}$ expression the rotor currents, by using the $7^{th}$ equations.
After some arithmetical operation we will get the stator currents
$$ \frac{d}{dt} \begin{bmatrix} i_{sd} \\ i_{sq} \end{bmatrix} = \begin{bmatrix} -\frac{R_s+\frac{L_m^2R_r}{L_r^2}}{L_s\sigma}& 0 \\ 0 & -\frac{R_s+\frac{L_m^2R_r}{L_r^2}}{L_s\sigma}  \end{bmatrix}\begin{bmatrix}i_{sd} \\ i_{sq} \end{bmatrix}\\+\begin{bmatrix} \frac{L_m}{L_s\sigma L_r\tau_r} & \frac{\omega_rL_m}{L_s\sigma L_r} \\ -\frac{\omega_rL_m}{L_s\sigma L_r} & \frac{L_m}{L_s\sigma L_r\tau_r}  \end{bmatrix}\begin{bmatrix}\psi_{rd} \\ \psi_{rq} \end{bmatrix}+\begin{bmatrix} \frac{1}{L_s\sigma} & 0 \\ 0 & \frac{1}{L_s\sigma} \end{bmatrix}\begin{bmatrix} u_{sd} \\ u_{sq} \end{bmatrix}\tag{9} $$
Where
$$
\tau_r=\frac{L_r}{R_r}
$$
and
$$
\sigma=1-\frac{L_m^2}{L_sL_r}
$$
The equations above combined with the Extended Kalman filte can be used to estimate the fluxes and rotor speed. The dynamic model for an induction motor by choosing the stator currents $i_sd$, $i_sq$ and rotor fluxes $\psi_rd$, $\psi_rq$ as state variables, is as follows
$$
\frac{dx}{dt}=Ax(t)+Bu(t)\tag{10}
$$
$$
y(t)=Cx(t)+Du(t)\tag{11}
$$
where
$$
A= \begin{bmatrix} -\frac{R_s+\frac{L_m^2R_r}{L_r^2}}{L_s\sigma} & 0 &  \frac{L_m}{L_s\sigma L_r\tau_r} & \frac{\omega_rL_m}{L_s\sigma L_r} \\ 0 & -\frac{R_s+\frac{L_m^2R_r}{L_r^2}}{L_s\sigma}  & -\frac{\omega_rL_m}{L_s\sigma L_r} & \frac{L_m}{L_s\sigma L_r\tau_r} \\ \frac{L_m}{\tau_r} & 0 & -\frac{1}{\tau_r} & -\omega_r \\ 0 & \frac{L_m}{\tau_r} &   \omega_r & -\frac{1}{\tau_r}  \end{bmatrix}\tag{12}
$$
$$B=\begin{bmatrix} \frac{1}{L_s\sigma} & 0 \\ 0 & \frac{1}{L_s\sigma} \\ 0 & 0 \\ 0 & 0\end{bmatrix}\tag{13}$$
$$C=\begin{bmatrix} 1 & 0 & 0 & 0 \\ 0 & 1 & 0 & 0 \end{bmatrix}\tag{14}$$
$$D=\begin{bmatrix} 0 \end{bmatrix} \tag{15}$$

Wednesday, September 19, 2012

Three-phase induction motor in different reference frames

In order to understand, analyze and control the ac induction motor, a dynamic model is necessary. The significant step forward in the analysis of the three-phase induction motor was the reference frame theory. Using this theory, it is possible to transform the machine dynamic model to a different reference frame.
Figure 1.
The equations of the ACIM's (alternate current induction motor) is easy to deduce from the machine structure and circuits.
The stator equations are the following
$$ u_{sa}=R_si_{sa}+\frac{d\psi_{sa}}{dt}\\
u_{sb}=R_si_{sb}+\frac{d\psi_{sb}}{dt}\\
u_{sc}=R_si_{sc}+\frac{d\psi_{sc}}{dt}\tag{1}
$$
and the rotor equations are the following
$$ u_{ra}=R_ri_{ra}+\frac{d\psi_{ra}}{dt}\\
u_{rb}=R_ri_{rb}+\frac{d\psi_{rb}}{dt}\\
u_{rc}=R_ri_{rc}+\frac{d\psi_{rc}}{dt}\tag{2}
$$
Both the current and the voltage are time dependent. In the three-phase reference frame the motor windings are located at 120 degree. Applying the Clarke transformation on the three phase motor, more info in the previous blog, we can write the three-phase machine equations in two phase
$$ u_{s\alpha}=R_si_{s\alpha}+\frac{d\psi_{s\alpha}}{dt}\\
u_{s\beta}=R_si_{s\beta}+\frac{d\psi_{s\beta}}{dt}\tag{3}
$$
$$ u_{r\alpha}=R_ri_{r\alpha}+\frac{d\psi_{r\alpha}}{dt}\\
u_{r\beta}=R_ri_{r\beta}+\frac{d\psi_{r\beta}}{dt}\tag{4}
$$
The $3^{rd}$ and $4^{th}$ equations are based on two different reference frames, one is the stationary, fixed to the stator, the other is rotating with the rotor at electrical motor speed $\omega_r$. With respect of the $\alpha/\beta$ system, the ACIM can be equally describe by two other perpendicular windings. This transformation is applied to transfer the stator and rotor equation's to a common reference frame named $d/q$ (rotating reference frame). In the common reference frame it is easier to describe the dynamic model and behaviour of the ACIM.There are four reference frames widely used in ACIM analysis, namely he stationary, rotor, synchronous and arbitrary reference frame.

Stationary or stator fixed reference frame


In this case the reference frame speed is 0 and all the variables are referred to the stator fixed reference frame. With the following equation we can describe the current in the d/q reference frame.
$$
i_{rd} = i_{r\alpha}cos\theta-i_{r\beta}sin\theta\\
i_{rq} = i_{r\alpha}sin\theta+i_{r\beta}cos\theta\tag{5}
$$
The matrices of the transformation $T_{-\theta}$ and inverse transformation $T^{-1}_{-\theta}$ are the following
$$
T_{-\theta}=\begin{bmatrix}  cos\theta & -sin\theta \\ sin\theta & cos\theta \end{bmatrix}\tag{6}
$$
$$
T^{-1}_{-\theta}=\begin{bmatrix}  cos\theta & sin\theta \\ -sin\theta & cos\theta \end{bmatrix}\tag{7}
$$
The $6^{th}$ and $7^{th}$ equations also can apply on the voltage and flux, because of this we can transform the $3^{rd}$ and $4^{th}$ equations 
$$ T_{-\theta} \begin{bmatrix} u_{r\alpha} \\ u_{r\beta} \end{bmatrix}=T_{-\theta} R_r \begin{bmatrix} i_{r\alpha} \\ i_{r\beta} \end{bmatrix} +T_{-\theta} \frac{d}{dt} \begin{bmatrix} \psi_{r\alpha} \\ \psi_{r\beta} \end{bmatrix}\tag{9} $$
Because $$T^{-1}_{-\theta}T_{-\theta}=1\tag{10}$$we can multiplying the rotor flux vector, it remain unchanged.
$$\begin{bmatrix} u_{rd} \\ u_{rq} \end{bmatrix}=R_r \begin{bmatrix} i_{rd} \\ i_{rq} \end{bmatrix} +T_{-\theta} \frac{d}{dt}\left(T_{-\theta}^{-1}T_{-\theta} \begin{bmatrix} \psi_{r\alpha} \\ \psi_{r\beta} \end{bmatrix}\right)\\ \begin{bmatrix} u_{rd} \\ u_{rq} \end{bmatrix}=R_r \begin{bmatrix} i_{rd} \\ i_{rq} \end{bmatrix} +T_{-\theta} \frac{d}{dt}\left(T_{-\theta}^{-1} \begin{bmatrix} \psi_{rd} \\ \psi_{rq} \end{bmatrix}\right)\\ \begin{bmatrix} u_{rd} \\ u_{rq} \end{bmatrix}=R_r \begin{bmatrix} i_{rd} \\ i_{rq} \end{bmatrix} +T_{-\theta}T_{-\theta}^{-1} \frac{d}{dt} \begin{bmatrix} \psi_{rd} \\ \psi_{rq} \end{bmatrix}+T_{-\theta} \frac{d}{dt}\left(T_{-\theta}^{-1}\right)\begin{bmatrix} \psi_{rd} \\ \psi_{rq} \end{bmatrix}\tag{11}$$
Where
$$T_{-\theta} \frac{d}{dt}\left(T_{-\theta}^{-1}\right)=T_{-\theta} \left(\frac{d}{d\theta}T_{-\theta}^{-1}\right)\frac{d\theta}{dt}\\=\begin{bmatrix}  0 & cos\theta^2+sin\theta^2 \\ -cos\theta^2-sin\theta^2 & 0 \end{bmatrix}\frac{d\theta}{dt}=\begin{bmatrix}  0 & 1 \\ -1 & 0 \end{bmatrix}\omega_r\tag{12}$$
If we insert the $12^{th}$ equation into the $11^{th}$ equation finally we get the stator and rotor equations in the same, stator fixed reference frame.
$$
\begin{bmatrix} u_{sd} \\ u_{sq} \end{bmatrix}=R_r \begin{bmatrix} i_{sd} \\ i_{sq} \end{bmatrix} +\frac{d}{dt}\begin{bmatrix} \psi_{sd} \\ \psi_{sq} \end{bmatrix}\tag{13}
$$
$$\begin{bmatrix} u_{rd} \\ u_{rq} \end{bmatrix}=R_r \begin{bmatrix} i_{rd} \\ i_{rq} \end{bmatrix} +\frac{d}{dt}\begin{bmatrix} \psi_{rd} \\ \psi_{rq} \end{bmatrix}+\omega_r\begin{bmatrix} \psi_{rd} \\ -\psi_{rq} \end{bmatrix}\tag{14}$$

Rotor fixed reference frame


In this case the common reference is attached to the rotor and it is rotating with the electrical speed $\omega_r$. In this case the transformation matrices are the following,
$$
T_{-\gamma}=\begin{bmatrix}  cos\gamma & sin\gamma \\ -sin\gamma & cos\gamma \end{bmatrix}\tag{15}
$$
$$
T^{-1}_{-\gamma}=\begin{bmatrix}  cos\gamma & -sin\gamma \\ sin\gamma & cos\gamma \end{bmatrix}\tag{16}
$$
Applying the same calculation as in the stator fixed reference frame we will get the following equation,
$$
\begin{bmatrix} u_{sd} \\ u_{sq} \end{bmatrix}=R_r \begin{bmatrix} i_{sd} \\ i_{sq} \end{bmatrix} +\frac{d}{dt}\begin{bmatrix} \psi_{sd} \\ \psi_{sq} \end{bmatrix}+\omega_r\begin{bmatrix} -\psi_{sd} \\ \psi_{sq} \end{bmatrix}\tag{17}
$$
$$\begin{bmatrix} u_{rd} \\ u_{rq} \end{bmatrix}=R_r \begin{bmatrix} i_{rd} \\ i_{rq} \end{bmatrix} +\frac{d}{dt}\begin{bmatrix} \psi_{rd} \\ \psi_{rq} \end{bmatrix}\tag{18}$$

Arbitrary rotating reference frame


By replacing the $-\theta$ with $\gamma-\theta$ we can obtain the rotor variables and rotor equation in arbitrary reference frame. In this case the transformation matrices are the following
$$T_{\gamma-\theta}=\begin{bmatrix} cos\left(\gamma-\theta\right) & sin\left(\gamma-\theta\right) \\ -sin\left(\gamma-\theta\right) & cos\left(\gamma-\theta\right) \end{bmatrix}\tag{19} $$
$$ T^{-1}_{\gamma-\theta}=\begin{bmatrix} cos\left(\gamma-\theta\right) & -sin\left(\gamma-\theta\right) \\ sin\left(\gamma-\theta\right) & cos\left(\gamma-\theta\right) \end{bmatrix}\tag{20}$$
Applying the transformation matrices on the $3^{rd}$ and $4^{th}$ equations we will end up with the following equation in the arbitrary reference frame
$$
\begin{bmatrix} u_{sd} \\ u_{sq} \end{bmatrix}=R_r \begin{bmatrix} i_{sd} \\ i_{sq} \end{bmatrix} +\frac{d}{dt}\begin{bmatrix} \psi_{sd} \\ \psi_{sq} \end{bmatrix}+\omega_\gamma\begin{bmatrix} -\psi_{sd} \\ \psi_{sq} \end{bmatrix}\tag{21}
$$
$$\begin{bmatrix} u_{rd} \\ u_{rq} \end{bmatrix}=R_r \begin{bmatrix} i_{rd} \\ i_{rq} \end{bmatrix} +\frac{d}{dt}\begin{bmatrix} \psi_{rd} \\ \psi_{rq} \end{bmatrix}+\left(\omega_\gamma-\omega_r\right)\begin{bmatrix} -\psi_{rd} \\ \psi_{rq} \end{bmatrix}\tag{22}$$
The stator and rotor fixed reference frame is just a particular case of the arbitrary rotating reference frame.  In the stator fixed reference frame the $\omega_\gamma$ is set to zero yield. If the reference frame is rotating with $\omega_r$ the equations of the rotor reference frame are obtained.

Sunday, September 9, 2012

Clarke coordinate transformation

The Clarke transformation does a magnitude invariant translation from a three-phase system to a two orthogonal system.
In order to understand the Clarke transformation I will introduce the 3-phase induction motor.
Figure 1. 3 phase induction motor windings

Three windings are organized with 120° angle difference in the physical space between each other. On the right side of the figure they are illustrated in a simplified way, where a winding is represented with an inductor.
At a certain time point, for e.g. the currents in the three windings have the directions and values as shown in Figure 2, they could be summarized by using the vector addition. The result is as shown in the figure.
Figure 2.






Referring to Figure 2 we can calculate the sum of the current vectors as:
$$i_s = i_u+i_ve^{{2\pi\over3}j}+i_we^{{4\pi\over3}j}\tag{1}$$
Using the Euler formula:
$$e^{j\omega} = \cos(\omega)+j \sin(\omega)\tag{2}$$
We will get the following equation:
$$i_s = \left(i_ucos(0)+i_vcos\left({2\pi\over3}\right)+i_wcos\left({4\pi\over3}\right)\right)\\+j\left(i_usin(0)+i_vsin\left({2\pi\over3}\right)+i_wsin\left({4\pi\over3}\right) \right)\tag{3}$$
$$i_s = \left(i_u-{1\over2}i_v-{1\over2}i_w\right)+j\left(0+{\sqrt3\over2}i_v-{\sqrt3\over2}i_w\right)\tag{4}$$
 In order to keep constant magnitude of the vectors during the transformation we put a $k_1$ coefficient.
$$i_s={k_1}i_s\tag{5}$$
The real and imaginary parts can be separated and rewritten as:
$$i_\alpha =Re\left(i_s\right)=k_1\left(i_u-{1\over2}i_v-{1\over2}i_w\right)\\
i_\beta =Im\left(i_s\right)=k_1\left(0+{\sqrt3\over2}i_v-{\sqrt3\over2}i_w\right)\tag{6}$$
Adding a zero-axis value
$$i_0={k_1}{k_2}(i_u+i_v+i_w)\tag{7}$$
Using the $6$ and $7$ equation we can write the following transformation:
$$ \left[ \begin{array}{c} i_\alpha \\ i_\beta \\ i_0 \end{array} \right] =k_1 \begin{bmatrix}  1 & -{1\over2} & -{1\over2} \\ 0 & {\sqrt3\over2} & -{\sqrt3\over2} \\ {k_2} & {k_2} & {k_2} \end{bmatrix}\left[ \begin{array}{c} i_u \\ i_v \\ i_w \end{array} \right]\tag{8}$$
Where the $T$ transformation matrix is as follows
$$T=k_1 \begin{bmatrix}  1 & -{1\over2} & -{1\over2} \\ 0 & {\sqrt3\over2} & -{\sqrt3\over2} \\ {k_2} & {k_2} & {k_2} \end{bmatrix}\tag{9}$$
and the inverse $T^{-1}$ transformation matrix is
$$T^{-1}=k_1 \begin{bmatrix}  1 & 0 & {k_2} \\ -{1\over2} & {\sqrt3\over2} & {k_2} \\ -{1\over2}  & -{\sqrt3\over2} & {k_2}  \end{bmatrix}\tag{10}$$
To determine the $k_1$ and $k_2$ we have to solve the following equation
$$
 T^{-1}T=\begin{bmatrix}  1 & 0 & 0 \\ 0 & 1 & 0 \\ 0 & 0 & 1 \end{bmatrix}\tag{11}
$$
Using the $11^th$ equation we can write the following
$$
k_1^2 \begin{bmatrix}  1 & 0 & {k_2} \\ -{1\over2} & {\sqrt3\over2} & {k_2} \\ -{1\over2}  & -{\sqrt3\over2} & {k_2}  \end{bmatrix}\begin{bmatrix}  1 & -{1\over2} & -{1\over2} \\ 0 & {\sqrt3\over2} & -{\sqrt3\over2} \\ {k_2} & {k_2} & {k_2} \end{bmatrix}=\begin{bmatrix}  1 & 0 & 0 \\ 0 & 1 & 0 \\ 0 & 0 & 1 \end{bmatrix}\tag{12}
$$
Solving the $12^th$ equation the $k_1$ and $k_2$ value will be:
$$k_1=\sqrt{2\over3}\tag{13}$$

$$k_2={1\over{\sqrt2}}\tag{14}$$
Replacing $k_1$ and $k_2$ in the $T$ matrix, finally we will get the following transformation matrix
$$T=\sqrt{2\over3} \begin{bmatrix}  1 & -{1\over2} & -{1\over2} \\ 0 & {\sqrt3\over2} & -{\sqrt3\over2} \\ {1\over{\sqrt2}} & {1\over{\sqrt2}} & {1\over{\sqrt2}} \end{bmatrix}\tag{15}$$
No we can test the above transformation matrices, for this purpose I implemented the transformation matrices in python using numpy
def clarke_p_i_i0(self,a,b,c):
        T = sqrt(2./3.)* array([
                              [1., -1./2., -1./2.],
                              [0., sqrt(3.)/2., -sqrt(3.)/2.],
                              [1./sqrt(2.), 1./sqrt(2.), 1./sqrt(2.)]
                              ])
        return  dot(T, array([[a],[b],[c]]));
        
    
def inv_clarke_p_i_i0(self,alpha, beta, Io=0):
        T = sqrt(2./3.)* array([
                              [1., 0., 1/sqrt(2.)], 
                              [-1./2.,  sqrt(3.)/2., 1./sqrt(2.)], 
                              [-1./2.,  -sqrt(3.)/2., 1./sqrt(2.)]
                              ])
        
        return  dot(T, array([[alpha],[beta],[Io]])); 

The output of the transformation and inverse transformation is the following
Figure 3.

Using the following relation
$$
i_u+i_v+i_w=0\tag{16}
$$
so
$$
 i_w = -i_u-i_v\tag{17}
$$
Applying the $17^th$ relation on the $6^th$ equation the value of the $i_\alpha$ will be the following
$$
i_\alpha = i_u-{1\over2}i_v- {1\over2}\left(-i_u-i_v\right)\\
i_\alpha = {3\over2}i_u\tag{18}
$$
applying this to the $i_\beta$ we get the following equation
$$
i_\beta =  {{\sqrt3}\over2}i_u+{\sqrt{3}}i_v\tag{19}
$$
The $18^th$ and $19^th$, applied on voltage and current, is not power invariant, because of this we have to solve the following equation
$$
u_ui_u+u_vi_v+u_wi_w=u_\alpha i_\alpha+u_\beta i_\beta\tag{20}
$$
$$
u_\alpha i_\alpha+u_\beta i_\beta =  {3\over2}u_u {3\over2}i_u+
\left(\sqrt{3\over2}u_u+\sqrt{3}u_b\right) \left(\sqrt{3\over2}i_u+\sqrt{3}i_b\right) \\
={3\over2}\left(u_ui_u+u_vi_v+u_wi_w\right)\tag{21}
$$
So the $2\over3$ scaling factor guarantee the power invariance. Because of the symmetrical distribution of the scaling factor $2\over3$, following equations are used to transform the three-phase reference frame to two-phase reference frame.
$$
i _\alpha={\sqrt{2\over3}}{3\over2}i_v={\sqrt{3\over2}}i_v\tag{22}
$$
and
$$
i_\beta =  {\sqrt{2\over3}}\left({{\sqrt3}\over2}i_u+{\sqrt{3}}i_v\right)\\
={1\over\sqrt2}i_u+{\sqrt2}i_v\tag{23}
$$
Writing the matrix form the equation above
$$
T= \begin{bmatrix} \sqrt{3\over2} & 0 \\ {1\over\sqrt2} &  {\sqrt2} \end{bmatrix}\tag{24}
$$
and the inverse transformation
$$
T^{-1}= \begin{bmatrix} \sqrt{2\over3} & 0 \\ -{1\over\sqrt6} & {1\over\sqrt2} \\
-{1\over\sqrt6} & -{1\over\sqrt2}  \end{bmatrix}\tag{25}
$$
The equation above can apply also for voltage transformation.
Python implementation:
def clarke_p_i(self,a,b):

        """"""

        T = array([
                    [sqrt(3./2.), 0],
                    [1./sqrt(2.), sqrt(2.)]
                ])

        return  dot(T, array([[a],[b]]));

        

def inv_clarke_p_i(self,alpha, beta):

        T = array([
                    [sqrt(2./3.), 0],
                    [-1./sqrt(6.), 1./sqrt(2.)],
                    [-1./sqrt(6.), -1./sqrt(2.)],
                 ])
        
        return dot(T, array([[alpha],[beta]]))
Figure 4.
The transformation matrices mentioned above are power invariant, but also it's possible to write the magnitude invariant transformation. If we replace the $k_1$ and $k_2$ in the $9^{th}$ equation with ${2\over3}$ and ${1\over3}$, the transformation and inverse transformation matrices are the following

$$T={2\over3} \begin{bmatrix}  1 & -{1\over2} & -{1\over2} \\ 0 & {\sqrt3\over2} & -{\sqrt3\over2} \\ 1\over2 & 1\over2 & 1\over2 \end{bmatrix}\tag{26}$$
$$T^{-1}={3\over2} \begin{bmatrix}  {2\over3} & 0 & {1\over2} \\ -{1\over3} & {1\over\sqrt3} & {1\over2} \\ -{1\over3}  & -{1\over\sqrt3} & {1\over2}  \end{bmatrix}\tag{27}
$$
Python implementation: 
def clarke_m_i(self,a,b,c): 
        T = 2./3.* array([
                              [1., -1./2., -1./2.],
                              [0., sqrt(3.)/2., -sqrt(3.)/2.],
                              [1./2., 1./2., 1./2.]
                              ])
        return  dot(T, array([[a],[b],[c]]));
        
 def inv_clarke_m_i(self,alpha, beta, Io):
        T = 3./2.* array([
                              [2./3., 0., 1./2.], 
                              [-1./3.,  1/sqrt(3.), 1./2.], 
                              [-1./3.,  -1/sqrt(3.), 1./2.]
                              ])        
        return  dot(T, array([[alpha],[beta],[Io]]));

Figure 5.

As you see on the $Figure 3.$, $Figure 4.$ the amplitude of the transformation is not invariant, comparing with the $Figure 5.$ where the amplitude is invariant.

You can find an example in the github under the T_CoorTrans.py
Sources:
[1] Fujitsu Coordinate transform
[2] BME - Villamos Hajtások, Villamos Energetika Tanszék
[3] Mircea Popescu - Induction motor modelling for vector control purpose
[4] Prof. Dr.-Ing. Ralph Kennel - Master course Power Electronics