111 KiB
Diagonal control using the SVD and the Jacobian Matrix
- Introduction
- Gravimeter - Simscape Model
- Introduction
- Gravimeter Model - Parameters
- System Identification
- Decoupling using the Jacobian
- Decoupling using the SVD
- Verification of the decoupling using the "Gershgorin Radii"
- Verification of the decoupling using the "Relative Gain Array"
- Obtained Decoupled Plants
- Diagonal Controller
- Closed-Loop system Performances
- Robustness to a change of actuator position
- Choice of the reference frame for Jacobian decoupling
- SVD decoupling performances
- Analytical Model
- Diagonal Stiffness Matrix for a planar manipulator
- Diagonal Stiffness Matrix for a general parallel manipulator
- Stewart Platform - Simscape Model
- Introduction
- Simscape Model - Parameters
- Identification of the plant
- Decoupling using the Jacobian
- Decoupling using the SVD
- Verification of the decoupling using the "Gershgorin Radii"
- Verification of the decoupling using the "Relative Gain Array"
- Obtained Decoupled Plants
- Diagonal Controller
- Closed-Loop system Performances
This report is also available as a pdf.
Introduction ignore
In this document, the use of the Jacobian matrix and the Singular Value Decomposition to render a physical plant diagonal dominant is studied. Then, a diagonal controller is used.
These two methods are tested on two plants:
- In Section sec:gravimeter on a 3-DoF gravimeter
- In Section sec:stewart_platform on a 6-DoF Stewart platform
Gravimeter - Simscape Model
<<sec:gravimeter>>
Introduction
In this part, diagonal control using both the SVD and the Jacobian matrices are applied on a gravimeter model:
- Section sec:gravimeter_model: the model is described and its parameters are defined.
- Section sec:gravimeter_identification: the plant dynamics from the actuators to the sensors is computed from a Simscape model.
- Section sec:gravimeter_jacobian_decoupling: the plant is decoupled using the Jacobian matrices.
- Section sec:gravimeter_svd_decoupling: the Singular Value Decomposition is performed on a real approximation of the plant transfer matrix and further use to decouple the system.
- Section sec:gravimeter_gershgorin_radii: the effectiveness of the decoupling is computed using the Gershorin radii
- Section sec:gravimeter_rga: the effectiveness of the decoupling is computed using the Relative Gain Array
- Section sec:gravimeter_decoupled_plant: the obtained decoupled plants are compared
- Section sec:gravimeter_diagonal_control: the diagonal controller is developed
- Section sec:gravimeter_closed_loop_results: the obtained closed-loop performances for the two methods are compared
- Section sec:robustness_actuator_position: the robustness to a change of actuator position is evaluated
- Section sec:choice_jacobian_reference: the choice of the reference frame for the evaluation of the Jacobian is discussed
- Section sec:decoupling_performances: the decoupling performances of SVD is evaluated for a low damped and an highly damped system
Gravimeter Model - Parameters
<<sec:gravimeter_model>>
The model of the gravimeter is schematically shown in Figure fig:gravimeter_model.
The parameters used for the simulation are the following:
l = 1.0; % Length of the mass [m]
h = 1.7; % Height of the mass [m]
la = l/2; % Position of Act. [m]
ha = h/2; % Position of Act. [m]
m = 400; % Mass [kg]
I = 115; % Inertia [kg m^2]
k = 15e3; % Actuator Stiffness [N/m]
c = 2e1; % Actuator Damping [N/(m/s)]
deq = 0.2; % Length of the actuators [m]
g = 0; % Gravity [m/s2]
System Identification
<<sec:gravimeter_identification>>
%% Name of the Simulink File
mdl = 'gravimeter';
%% Input/Output definition
clear io; io_i = 1;
io(io_i) = linio([mdl, '/F1'], 1, 'openinput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/F2'], 1, 'openinput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/F3'], 1, 'openinput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Acc_side'], 1, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Acc_side'], 2, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Acc_top'], 1, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Acc_top'], 2, 'openoutput'); io_i = io_i + 1;
G = linearize(mdl, io);
G.InputName = {'F1', 'F2', 'F3'};
G.OutputName = {'Ax1', 'Ay1', 'Ax2', 'Ay2'};
The inputs and outputs of the plant are shown in Figure fig:gravimeter_plant_schematic.
More precisely there are three inputs (the three actuator forces):
\begin{equation} \bm{\tau} = \begin{bmatrix}\tau_1 \\ \tau_2 \\ \tau_2 \end{bmatrix} \end{equation}And 4 outputs (the two 2-DoF accelerometers):
\begin{equation} \bm{a} = \begin{bmatrix} a_{1x} \\ a_{1y} \\ a_{2x} \\ a_{2y} \end{bmatrix} \end{equation}We can check the poles of the plant:
-0.12243+13.551i |
-0.12243-13.551i |
-0.05+8.6601i |
-0.05-8.6601i |
-0.0088785+3.6493i |
-0.0088785-3.6493i |
As expected, the plant as 6 states (2 translations + 1 rotation)
size(G)
State-space model with 4 outputs, 3 inputs, and 6 states.
The bode plot of all elements of the plant are shown in Figure fig:open_loop_tf.
Decoupling using the Jacobian
<<sec:gravimeter_jacobian_decoupling>>
Consider the control architecture shown in Figure fig:gravimeter_decouple_jacobian.
The Jacobian matrix $J_{\tau}$ is used to transform forces applied by the three actuators into forces/torques applied on the gravimeter at its center of mass:
\begin{equation} \begin{bmatrix} \tau_1 \\ \tau_2 \\ \tau_3 \end{bmatrix} = J_{\tau}^{-T} \begin{bmatrix} F_x \\ F_y \\ M_z \end{bmatrix} \end{equation}The Jacobian matrix $J_{a}$ is used to compute the vertical acceleration, horizontal acceleration and rotational acceleration of the mass with respect to its center of mass:
\begin{equation} \begin{bmatrix} a_x \\ a_y \\ a_{R_z} \end{bmatrix} = J_{a}^{-1} \begin{bmatrix} a_{x1} \\ a_{y1} \\ a_{x2} \\ a_{y2} \end{bmatrix} \end{equation}We thus define a new plant as defined in Figure fig:gravimeter_decouple_jacobian. \[ \bm{G}_x(s) = J_a^{-1} \bm{G}(s) J_{\tau}^{-T} \]
$\bm{G}_x(s)$ correspond to the $3 \times 3$ transfer function matrix from forces and torques applied to the gravimeter at its center of mass to the absolute acceleration of the gravimeter's center of mass (Figure fig:gravimeter_decouple_jacobian).
The Jacobian corresponding to the sensors and actuators are defined below:
Ja = [1 0 -h/2
0 1 l/2
1 0 h/2
0 1 0];
Jt = [1 0 -ha
0 1 la
0 1 -la];
And the plant $\bm{G}_x$ is computed:
Gx = pinv(Ja)*G*pinv(Jt');
Gx.InputName = {'Fx', 'Fy', 'Mz'};
Gx.OutputName = {'Dx', 'Dy', 'Rz'};
size(Gx) State-space model with 3 outputs, 3 inputs, and 6 states.
The diagonal and off-diagonal elements of $G_x$ are shown in Figure fig:gravimeter_jacobian_plant.
It is shown at the system is:
- decoupled at high frequency thanks to a diagonal mass matrix (the Jacobian being evaluated at the center of mass of the payload)
- coupled at low frequency due to the non-diagonal terms in the stiffness matrix, especially the term corresponding to a coupling between a force in the x direction to a rotation around z (due to the torque applied by the stiffness 1).
The choice of the frame in this the Jacobian is evaluated is discussed in Section sec:choice_jacobian_reference.
Decoupling using the SVD
<<sec:gravimeter_svd_decoupling>>
In order to decouple the plant using the SVD, first a real approximation of the plant transfer function matrix as the crossover frequency is required.
Let's compute a real approximation of the complex matrix $H_1$ which corresponds to the the transfer function $G(j\omega_c)$ from forces applied by the actuators to the measured acceleration of the top platform evaluated at the frequency $\omega_c$.
wc = 2*pi*10; % Decoupling frequency [rad/s]
H1 = evalfr(G, j*wc);
The real approximation is computed as follows:
D = pinv(real(H1'*H1));
H1 = pinv(D*real(H1'*diag(exp(j*angle(diag(H1*D*H1.'))/2))));
0.0092 | -0.0039 | 0.0039 |
-0.0039 | 0.0048 | 0.00028 |
-0.004 | 0.0038 | -0.0038 |
8.4e-09 | 0.0025 | 0.0025 |
Now, the Singular Value Decomposition of $H_1$ is performed: \[ H_1 = U \Sigma V^H \]
[U,S,V] = svd(H1);
-0.78 | 0.26 | -0.53 | -0.2 |
0.4 | 0.61 | -0.04 | -0.68 |
0.48 | -0.14 | -0.85 | 0.2 |
0.03 | 0.73 | 0.06 | 0.68 |
-0.79 | 0.11 | -0.6 |
0.51 | 0.67 | -0.54 |
-0.35 | 0.73 | 0.59 |
The obtained matrices $U$ and $V$ are used to decouple the system as shown in Figure fig:gravimeter_decouple_svd.
The decoupled plant is then: \[ \bm{G}_{SVD}(s) = U^{-1} \bm{G}(s) V^{-H} \]
Gsvd = inv(U)*G*inv(V');
size(Gsvd) State-space model with 4 outputs, 3 inputs, and 6 states.
The 4th output (corresponding to the null singular value) is discarded, and we only keep the $3 \times 3$ plant:
Gsvd = Gsvd(1:3, 1:3);
The diagonal and off-diagonal elements of the "SVD" plant are shown in Figure fig:gravimeter_svd_plant.
Verification of the decoupling using the "Gershgorin Radii"
<<sec:gravimeter_gershgorin_radii>>
The "Gershgorin Radii" is computed for the coupled plant $G(s)$, for the "Jacobian plant" $G_x(s)$ and the "SVD Decoupled Plant" $G_{SVD}(s)$:
The "Gershgorin Radii" of a matrix $S$ is defined by: \[ \zeta_i(j\omega) = \frac{\sum\limits_{j\neq i}|S_{ij}(j\omega)|}{|S_{ii}(j\omega)|} \]
Verification of the decoupling using the "Relative Gain Array"
<<sec:gravimeter_rga>>
The relative gain array (RGA) is defined as:
\begin{equation} \Lambda\big(G(s)\big) = G(s) \times \big( G(s)^{-1} \big)^T \end{equation}where $\times$ denotes an element by element multiplication and $G(s)$ is an $n \times n$ square transfer matrix.
The obtained RGA elements are shown in Figure fig:gravimeter_rga.
The RGA-number is also a measure of diagonal dominance:
\begin{equation} \text{RGA-number} = \| \Lambda(G) - I \|_\text{sum} \end{equation}Obtained Decoupled Plants
<<sec:gravimeter_decoupled_plant>>
The bode plot of the diagonal and off-diagonal elements of $G_{SVD}$ are shown in Figure fig:gravimeter_decoupled_plant_svd.
Similarly, the bode plots of the diagonal elements and off-diagonal elements of the decoupled plant $G_x(s)$ using the Jacobian are shown in Figure fig:gravimeter_decoupled_plant_jacobian.
Diagonal Controller
<<sec:gravimeter_diagonal_control>> The control diagram for the centralized control is shown in Figure fig:centralized_control_gravimeter.
The controller $K_c$ is "working" in an cartesian frame. The Jacobian is used to convert forces in the cartesian frame to forces applied by the actuators.
The SVD control architecture is shown in Figure fig:svd_control_gravimeter. The matrices $U$ and $V$ are used to decoupled the plant $G$.
We choose the controller to be a low pass filter: \[ K_c(s) = \frac{G_0}{1 + \frac{s}{\omega_0}} \]
$G_0$ is tuned such that the crossover frequency corresponding to the diagonal terms of the loop gain is equal to $\omega_c$
wc = 2*pi*10; % Crossover Frequency [rad/s]
w0 = 2*pi*0.1; % Controller Pole [rad/s]
K_cen = diag(1./diag(abs(evalfr(Gx, j*wc))))*(1/abs(evalfr(1/(1 + s/w0), j*wc)))/(1 + s/w0);
L_cen = K_cen*Gx;
K_svd = diag(1./diag(abs(evalfr(Gsvd, j*wc))))*(1/abs(evalfr(1/(1 + s/w0), j*wc)))/(1 + s/w0);
L_svd = K_svd*Gsvd;
U_inv = inv(U);
The obtained diagonal elements of the loop gains are shown in Figure fig:gravimeter_comp_loop_gain_diagonal.
Closed-Loop system Performances
<<sec:gravimeter_closed_loop_results>>
Now the system is identified again with additional inputs and outputs:
- $x$, $y$ and $R_z$ ground motion
- $x$, $y$ and $R_z$ acceleration of the payload.
%% Name of the Simulink File
mdl = 'gravimeter';
%% Input/Output definition
clear io; io_i = 1;
io(io_i) = linio([mdl, '/Dx'], 1, 'openinput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Dy'], 1, 'openinput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Rz'], 1, 'openinput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/F1'], 1, 'openinput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/F2'], 1, 'openinput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/F3'], 1, 'openinput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Abs_Motion'], 1, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Abs_Motion'], 2, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Abs_Motion'], 3, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Acc_side'], 1, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Acc_side'], 2, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Acc_top'], 1, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Acc_top'], 2, 'openoutput'); io_i = io_i + 1;
G = linearize(mdl, io);
G.InputName = {'Dx', 'Dy', 'Rz', 'F1', 'F2', 'F3'};
G.OutputName = {'Ax', 'Ay', 'Arz', 'Ax1', 'Ay1', 'Ax2', 'Ay2'};
The loop is closed using the developed controllers.
G_cen = lft(G, -pinv(Jt')*K_cen*pinv(Ja));
G_svd = lft(G, -inv(V')*K_svd*U_inv(1:3, :));
Let's first verify the stability of the closed-loop systems:
isstable(G_cen)
ans = logical 1
isstable(G_svd)
ans = logical 1
The obtained transmissibility in Open-loop, for the centralized control as well as for the SVD control are shown in Figure fig:gravimeter_platform_simscape_cl_transmissibility.
Robustness to a change of actuator position
<<sec:robustness_actuator_position>>
Let say we change the position of the actuators:
la = l/2*0.7; % Position of Act. [m]
ha = h/2*0.7; % Position of Act. [m]
%% Name of the Simulink File
mdl = 'gravimeter';
%% Input/Output definition
clear io; io_i = 1;
io(io_i) = linio([mdl, '/Dx'], 1, 'openinput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Dy'], 1, 'openinput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Rz'], 1, 'openinput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/F1'], 1, 'openinput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/F2'], 1, 'openinput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/F3'], 1, 'openinput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Abs_Motion'], 1, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Abs_Motion'], 2, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Abs_Motion'], 3, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Acc_side'], 1, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Acc_side'], 2, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Acc_top'], 1, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Acc_top'], 2, 'openoutput'); io_i = io_i + 1;
G = linearize(mdl, io);
G.InputName = {'Dx', 'Dy', 'Rz', 'F1', 'F2', 'F3'};
G.OutputName = {'Ax', 'Ay', 'Arz', 'Ax1', 'Ay1', 'Ax2', 'Ay2'};
The loop is closed using the developed controllers.
G_cen_b = lft(G, -pinv(Jt')*K_cen*pinv(Ja));
G_svd_b = lft(G, -inv(V')*K_svd*U_inv(1:3, :));
The new plant is computed, and the centralized and SVD control architectures are applied using the previously computed Jacobian matrices and $U$ and $V$ matrices.
The closed-loop system are still stable in both cases, and the obtained transmissibility are equivalent as shown in Figure fig:gravimeter_transmissibility_offset_act.
Choice of the reference frame for Jacobian decoupling
<<sec:choice_jacobian_reference>>
Introduction ignore
If we want to decouple the system at low frequency (determined by the stiffness matrix), we have to compute the Jacobian at a point where the stiffness matrix is diagonal. A displacement (resp. rotation) of the mass at this particular point should induce a pure force (resp. torque) on the same point due to stiffnesses in the system. This can be verified by geometrical computations.
If we want to decouple the system at high frequency (determined by the mass matrix), we have tot compute the Jacobians at the Center of Mass of the suspended solid. Similarly to the stiffness analysis, when considering only the inertia effects (neglecting the stiffnesses), a force (resp. torque) applied at this point (the center of mass) should induce a pure acceleration (resp. angular acceleration).
Ideally, we would like to have a decoupled mass matrix and stiffness matrix at the same time. To do so, the actuators (springs) should be positioned such that the stiffness matrix is diagonal when evaluated at the CoM of the solid.
Decoupling of the mass matrix
la = l/2; % Position of Act. [m]
ha = h/2; % Position of Act. [m]
%% Name of the Simulink File
mdl = 'gravimeter';
%% Input/Output definition
clear io; io_i = 1;
io(io_i) = linio([mdl, '/F1'], 1, 'openinput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/F2'], 1, 'openinput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/F3'], 1, 'openinput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Acc_side'], 1, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Acc_side'], 2, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Acc_top'], 1, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Acc_top'], 2, 'openoutput'); io_i = io_i + 1;
G = linearize(mdl, io);
G.InputName = {'F1', 'F2', 'F3'};
G.OutputName = {'Ax1', 'Ay1', 'Ax2', 'Ay2'};
Decoupling at the CoM (Mass decoupled)
JMa = [1 0 -h/2
0 1 l/2
1 0 h/2
0 1 0];
JMt = [1 0 -ha
0 1 la
0 1 -la];
GM = pinv(JMa)*G*pinv(JMt');
GM.InputName = {'Fx', 'Fy', 'Mz'};
GM.OutputName = {'Dx', 'Dy', 'Rz'};
Decoupling of the stiffness matrix
Decoupling at the point where K is diagonal (x = 0, y = -h/2 from the schematic {O} frame):
JKa = [1 0 0
0 1 -l/2
1 0 -h
0 1 0];
JKt = [1 0 0
0 1 -la
0 1 la];
And the plant $\bm{G}_x$ is computed:
GK = pinv(JKa)*G*pinv(JKt');
GK.InputName = {'Fx', 'Fy', 'Mz'};
GK.OutputName = {'Dx', 'Dy', 'Rz'};
Combined decoupling of the mass and stiffness matrices
To do so, the actuator position should be modified
la = l/2; % Position of Act. [m]
ha = 0; % Position of Act. [m]
%% Name of the Simulink File
mdl = 'gravimeter';
%% Input/Output definition
clear io; io_i = 1;
io(io_i) = linio([mdl, '/F1'], 1, 'openinput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/F2'], 1, 'openinput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/F3'], 1, 'openinput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Acc_side'], 1, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Acc_side'], 2, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Acc_top'], 1, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Acc_top'], 2, 'openoutput'); io_i = io_i + 1;
G = linearize(mdl, io);
G.InputName = {'F1', 'F2', 'F3'};
G.OutputName = {'Ax1', 'Ay1', 'Ax2', 'Ay2'};
JMa = [1 0 -h/2
0 1 l/2
1 0 h/2
0 1 0];
JMt = [1 0 -ha
0 1 la
0 1 -la];
GKM = pinv(JMa)*G*pinv(JMt');
GKM.InputName = {'Fx', 'Fy', 'Mz'};
GKM.OutputName = {'Dx', 'Dy', 'Rz'};
Conclusion
Ideally, the mechanical system should be designed in order to have a decoupled stiffness matrix at the CoM of the solid.
If not the case, the system can either be decoupled as low frequency if the Jacobian are evaluated at a point where the stiffness matrix is decoupled. Or it can be decoupled at high frequency if the Jacobians are evaluated at the CoM.
SVD decoupling performances
<<sec:decoupling_performances>> As the SVD is applied on a real approximation of the plant dynamics at a frequency $\omega_0$, it is foreseen that the effectiveness of the decoupling depends on the validity of the real approximation.
Let's do the SVD decoupling on a plant that is mostly real (low damping) and one with a large imaginary part (larger damping).
Start with small damping, the obtained diagonal and off-diagonal terms are shown in Figure fig:gravimeter_svd_low_damping.
c = 2e1; % Actuator Damping [N/(m/s)]
Now take a larger damping, the obtained diagonal and off-diagonal terms are shown in Figure fig:gravimeter_svd_high_damping.
c = 5e2; % Actuator Damping [N/(m/s)]
Analytical Model
Model
- collocated actuators and sensors
Stiffness and Mass matrices
Stiffness matrix:
\begin{equation} \mathcal{F}_{\{O\}} = -K_{\{O\}} \mathcal{X}_{\{O\}} \end{equation}with:
- $\mathcal{X}_{\{O\}}$ are displacements/rotations of the mass $x$, $y$, $R_z$ expressed in the frame $\{O\}$
- $\mathcal{F}_{\{O\}}$ are forces/torques $\mathcal{F}_x$, $\mathcal{F}_y$, $\mathcal{M}_z$ applied at the origin of $\{O\}$
Mass matrix:
\begin{equation} \mathcal{F}_{\{O\}} = M_{\{O\}} \ddot{\mathcal{X}}_{\{O\}} \end{equation}Consider the two following frames:
- $\{M\}$: Center of mass => diagonal mass matrix \[ M_{\{M\}} = \begin{bmatrix}m & 0 & 0 \\ 0 & m & 0 \\ 0 & 0 & I\end{bmatrix} \] \[ K_{\{M\}} = \begin{bmatrix}k_1 & 0 & k_1 h_a \\ 0 & k_2 + k_3 & 0 \\ k_1 h_a & 0 & k_1 h_a + (k_2 + k_3)l_a\end{bmatrix} \]
-
$\{K\}$: Diagonal stiffness matrix \[ K_{\{K\}} = \begin{bmatrix}k_1 & 0 & 0 \\ 0 & k_2 + k_3 & 0 \\ 0 & 0 & (k_2 + k_3)l_a\end{bmatrix} \]
- Compute the mass matrix $M_{\{K\}}$ Needs two Jacobians => complicated matrix
Equations
- Ideally write the equation from $\tau$ to $\mathcal{L}$
Jacobians
Usefulness of Jacobians:
- $J_{\{M\}}$ converts $\dot{\mathcal{L}}$ to $\dot{\mathcal{X}}_{\{M\}}$: \[ \dot{\mathcal{X}}_{\{M\}} = J_{\{M\}} \dot{\mathcal{L}} \]
- $J_{\{M\}}^T$ converts $\tau$ to $\mathcal{F}_{\{M\}}$: \[ \mathcal{F}_{\{M\}} = J_{\{M\}}^T \tau \]
- $J_{\{K\}}$ converts $\dot{\mathcal{K}}$to $\dot{\mathcal{X}}_{\{K\}}$: \[ \dot{\mathcal{X}}_{\{K\}} = J_{\{K\}} \dot{\mathcal{K}} \]
- $J_{\{K\}}^T$ converts $\tau$ to $\mathcal{F}_{\{K\}}$: \[ \mathcal{F}_{\{K\}} = J_{\{K\}}^T \tau \]
Let's compute the Jacobians:
\begin{equation} J_{\{M\}} = \begin{bmatrix} 1 & 0 & h_a \\ 0 & 1 & -l_a \\ 0 & 1 & l_a \end{bmatrix} \end{equation} \begin{equation} J_{\{K\}} = \begin{bmatrix} 1 & 0 & 0 \\ 0 & 1 & -l_a \\ 0 & 1 & l_a \end{bmatrix} \end{equation}Parameters
l = 1.0; % Length of the mass [m]
h = 2*1.7; % Height of the mass [m]
la = l/2; % Position of Act. [m]
ha = h/2; % Position of Act. [m]
m = 400; % Mass [kg]
I = 115; % Inertia [kg m^2]
c1 = 2e1; % Actuator Damping [N/(m/s)]
c2 = 2e1; % Actuator Damping [N/(m/s)]
c3 = 2e1; % Actuator Damping [N/(m/s)]
k1 = 15e3; % Actuator Stiffness [N/m]
k2 = 15e3; % Actuator Stiffness [N/m]
k3 = 15e3; % Actuator Stiffness [N/m]
Transfer function from $\tau$ to $\delta \mathcal{L}$
Mass, Damping and Stiffness matrices expressed in $\{M\}$:
Mm = [m 0 0 ;
0 m 0 ;
0 0 I];
Cm = [c1 0 c1*ha ;
0 c2+c3 0 ;
c1*ha 0 c1*ha + (c2+c3)*la];
Km = [k1 0 k1*ha ;
0 k2+k3 0 ;
k1*ha 0 k1*ha + (k2+k3)*la];
Jacobian $J_{\{M\}}$:
Jm = [1 0 ha ;
0 1 -la ;
0 1 la];
Mt = inv(Jm')*Mm*inv(Jm);
Ct = inv(Jm')*Cm*inv(Jm);
Kt = inv(Jm')*Km*inv(Jm);
400.0 | 340.0 | -340.0 |
340.0 | 504.0 | -304.0 |
-340.0 | -304.0 | 504.0 |
15000.0 | 0.0 | 0.0 |
0.0 | 24412.5 | -9412.5 |
0.0 | -9412.5 | 24412.5 |
Gt = s^2*inv(Mt*s^2 + Ct*s + Kt);
% Gt = JM*s^2*inv(MM*s^2 + CM*s + KM)*JM';
Transfer function from $\mathcal{F}_{\{M\}}$ to $\mathcal{X}_{\{M\}}$
Gm = inv(Jm)*Gt*inv(Jm');
400.0 | 0.0 | 0.0 |
0.0 | 400.0 | 0.0 |
0.0 | 0.0 | 115.0 |
15000.0 | 0.0 | 12750.0 |
0.0 | 30000.0 | 0.0 |
12750.0 | 0.0 | 27750.0 |
Transfer function from $\mathcal{F}_{\{K\}}$ to $\mathcal{X}_{\{K\}}$
Jacobian:
Jk = [1 0 0
0 1 -la
0 1 la];
Mass, Damping and Stiffness matrices expressed in $\{K\}$:
Mk = Jk'*Mt*Jk;
Ck = Jk'*Ct*Jk;
Kk = Jk'*Kt*Jk;
400.0 | 0.0 | -340.0 |
0.0 | 400.0 | 0.0 |
-340.0 | 0.0 | 404.0 |
15000.0 | 0.0 | 0.0 |
0.0 | 30000.0 | 0.0 |
0.0 | 0.0 | 16912.5 |
% Gk = s^2*inv(Mk*s^2 + Ck*s + Kk);
Gk = inv(Jk)*Gt*inv(Jk');
Analytical
Parameters
syms la ha m I c k positive
Mm = [m 0 0 ;
0 m 0 ;
0 0 I];
Cm = [c 0 c*ha ;
0 2*c 0 ;
c*ha 0 c*(ha+2*la)];
Km = [k 0 k*ha ;
0 2*k 0 ;
k*ha 0 k*(ha+2*la)];
Jm = [1 0 ha ;
0 1 -la ;
0 1 la];
Mt = inv(Jm')*Mm*inv(Jm);
Ct = inv(Jm')*Cm*inv(Jm);
Kt = inv(Jm')*Km*inv(Jm);
Jk = [1 0 0
0 1 -la
0 1 la];
Mass, Damping and Stiffness matrices expressed in $\{K\}$:
Mk = Jk'*Mt*Jk;
Ck = Jk'*Ct*Jk;
Kk = Jk'*Kt*Jk;
['\begin{equation} M_{\{K\}} = ', latex(simplify(Kk)), '\end{equation}']
\begin{equation} M_{\{K\}} = \left(\begin{array}{ccc} k & 0 & 0\\ 0 & 2\,k & 0\\ 0 & 0 & k\,\left(-{\mathrm{ha}}^2+\mathrm{ha}+2\,\mathrm{la}\right) \end{array}\right)\end{equation}
Diagonal Stiffness Matrix for a planar manipulator
Model and Assumptions
Consider a parallel manipulator with:
- $b_i$: location of the joints on the top platform are called $b_i$
- $\hat{s}_i$: unit vector corresponding to the struts
- $k_i$: stiffness of the struts
- $\tau_i$: actuator forces
- $O_M$: center of mass of the solid body
Consider two frames:
- $\{M\}$ with origin $O_M$
- $\{K\}$ with origin $O_K$
As an example, take the system shown in Figure fig:3dof_model_fully_parallel.
Objective
The objective is to find conditions for the existence of a frame $\{K\}$ in which the Stiffness matrix of the manipulator is diagonal. If the conditions are fulfilled, a second objective is to fine the location of the frame $\{K\}$ analytically.
Conditions for Diagonal Stiffness
The stiffness matrix in the frame $\{K\}$ can be expressed as: \begin{equation} \label{eq:stiffness_formula_planar} K_{\{K\}} = J_{\{K\}}^T \mathcal{K} J_{\{K\}}
\end{equation} where:
- $J_{\{K\}}$ is the Jacobian transformation from the struts to the frame $\{K\}$
- $\mathcal{K}$ is a diagonal matrix with the strut stiffnesses on the diagonal
The Jacobian for a planar manipulator, evaluated in a frame $\{K\}$, can be expressed as follows:
\begin{equation} \label{eq:jacobian_planar}
J_{\{K\}} = \begin{bmatrix}
{}^K\hat{s}_1^T & {}^Kb1,x {}^K\hat{s}1,y - {}^Kb1,x {}^K\hat{s}1,y
{}^K\hat{s}_2^T & {}^Kb2,x {}^K\hat{s}2,y - {}^Kb2,x {}^K\hat{s}2,y
\vdots & \vdots
{}^K\hat{s}_n^T & {}^Kbn,x {}^K\hat{s}n,y - {}^Kbn,x {}^K\hat{s}n,y \\
\end{bmatrix}
\end{equation}
Let's omit the mention of frame, it is assumed that vectors are expressed in frame $\{K\}$. It is specified otherwise.
Injecting eqref:eq:jacobian_planar into eqref:eq:stiffness_formula_planar yields:
\begin{equation} \boxed{ K_{\{K\}} = \left[ \begin{array}{c|c} k_i \hat{s}_i \hat{s}_i^T & k_i \hat{s}_i (b_{i,x}\hat{s}_{i,y} - b_{i,y}\hat{s}_{i,x}) \cr \hline k_i \hat{s}_i (b_{i,x}\hat{s}_{i,y} - b_{i,y}\hat{s}_{i,x}) & k_i (b_{i,x}\hat{s}_{i,y} - b_{i,y}\hat{s}_{i,x})^2 \end{array} \right] } \end{equation}In order to have a decoupled stiffness matrix, we have the following two conditions:
\begin{align} k_i \hat{s}_i \hat{s}_i^T &= \text{diag. matrix} \label{eq:diag_cond_2D_1} \\ k_i \hat{s}_i (b_{i,x}\hat{s}_{i,y} - b_{i,y}\hat{s}_{i,x}) &= 0 \label{eq:diag_cond_2D_2} \end{align}Note that we don't have any condition on the term $k_i (b_{i,x}\hat{s}_{i,y} - b_{i,y}\hat{s}_{i,x})^2$ as it is only a scalar.
Condition eqref:eq:diag_cond_2D_1:
- represents the coupling between translations and forces
- does only depends on the orientation of the struts and the stiffnesses and not on the choice of frame
- it is therefore a intrinsic property of the chosen geometry
Condition eqref:eq:diag_cond_2D_2:
- represents the coupling between forces/rotations and torques/translation
- it does depend on the positions of the joints $b_i$ in the frame $\{K\}$
Let's make a change of frame from the initial frame $\{M\}$ to the frame $\{K\}$:
\begin{align} {}^Kb_i &= {}^Mb_i - {}^MO_K \\ {}^K\hat{s}_i &= {}^M\hat{s}_i \end{align}And the goal is to find ${}^MO_K$ such that eqref:eq:diag_cond_2D_2 is fulfilled:
\begin{equation} k_i ({}^Mb_{i,x}\hat{s}_{i,y} - {}^Mb_{i,y}\hat{s}_{i,x} - {}^MO_{K,x}\hat{s}_{i,y} + {}^MO_{K,y}\hat{s}_{i,x}) \hat{s}_i = 0 \end{equation} \begin{equation} k_i ({}^Mb_{i,x}\hat{s}_{i,y} - {}^Mb_{i,y}\hat{s}_{i,x}) \hat{s}_i = {}^MO_{K,x} k_i \hat{s}_{i,y} \hat{s}_i - {}^MO_{K,y} k_i \hat{s}_{i,x} \hat{s}_i \end{equation}And we have two sets of linear equations of two unknowns.
This can be easily solved by writing the equations in a matrix form:
\begin{equation} \underbrace{k_i ({}^Mb_{i,x}\hat{s}_{i,y} - {}^Mb_{i,y}\hat{s}_{i,x}) \hat{s}_i}_{2 \times 1} = \underbrace{\begin{bmatrix} & \\ k_i \hat{s}_{i,y} \hat{s}_i & - k_i \hat{s}_{i,x} \hat{s}_i \\ & \\ \end{bmatrix}}_{2 \times 2} \underbrace{\begin{bmatrix} {}^MO_{K,x}\\ {}^MO_{K,y} \end{bmatrix}}_{2 \times 1} \end{equation}And finally, if the matrix is invertible:
\begin{equation} \boxed{ {}^MO_K = {\begin{bmatrix} & \\ k_i \hat{s}_{i,y} \hat{s}_i & - k_i \hat{s}_{i,x} \hat{s}_i \\ & \\ \end{bmatrix}}^{-1} k_i ({}^Mb_{i,x}\hat{s}_{i,y} - {}^Mb_{i,y}\hat{s}_{i,x}) \hat{s}_i } \end{equation}Note that a rotation of the frame $\{K\}$ with respect to frame $\{M\}$ would make not change on the "diagonality" of $K_{\{K\}}$.
Example 1 - Planar manipulator with 3 actuators
Consider system of Figure fig:3dof_model_fully_parallel_example.
The stiffnesses $k_i$, the joint positions ${}^Mb_i$ and joint unit vectors ${}^M\hat{s}_i$ are defined below:
ki = [5,1,2]; % Stiffnesses [N/m]
si = [[1;0],[0;1],[0;1]]; si = si./vecnorm(si); % Unit Vectors
bi = [[-1;0.5],[-2;-1],[0;-1]]; % Joint's positions in frame {M}
Let's first verify that condition eqref:diag_cond_2D_1 is true:
ki.*si*si'
5 | 0 |
0 | 2 |
Now, compute ${}^MO_K$:
Ok = inv([sum(ki.*si(2,:).*si, 2), -sum(ki.*si(1,:).*si, 2)])*sum(ki.*(bi(1,:).*si(2,:) - bi(2,:).*si(1,:)).*si, 2);
Let's compute the new coordinates ${}^Kb_i$ after the change of frame:
Kbi = bi - Ok;
In order to verify that the new frame $\{K\}$ indeed yields a diagonal stiffness matrix, we first compute the Jacobian $J_{\{K\}}$:
Jk = [si', (Kbi(1,:).*si(2,:) - Kbi(2,:).*si(1,:))'];
And the stiffness matrix:
K = Jk'*diag(ki)*Jk
Example 2 - Planar manipulator with 4 actuators
Now consider the planar manipulator of Figure fig:model_planar_2.
The stiffnesses $k_i$, the joint positions ${}^Mb_i$ and joint unit vectors ${}^M\hat{s}_i$ are defined below:
ki = [1,2,1,1];
si = [[1;0],[0;1],[-1;0],[0;1]];
si = si./vecnorm(si);
h = 0.2;
L = 2;
bi = [[-L/2;h],[-L/2;-h],[L/2;h],[L/2;h]];
Let's first verify that condition eqref:diag_cond_2D_1 is true:
ki.*si*si'
2 | 0 |
0 | 3 |
Now, compute ${}^MO_K$:
Ok = inv([sum(ki.*si(2,:).*si, 2), -sum(ki.*si(1,:).*si, 2)])*sum(ki.*(bi(1,:).*si(2,:) - bi(2,:).*si(1,:)).*si, 2);
Let's compute the new coordinates ${}^Kb_i$ after the change of frame:
Kbi = bi - Ok;
In order to verify that the new frame $\{K\}$ indeed yields a diagonal stiffness matrix, we first compute the Jacobian $J_{\{K\}}$:
Jk = [si', (Kbi(1,:).*si(2,:) - Kbi(2,:).*si(1,:))'];
And the stiffness matrix:
K = Jk'*diag(ki)*Jk
Diagonal Stiffness Matrix for a general parallel manipulator
Model and Assumptions
Let's consider a 6dof parallel manipulator with:
- $b_i$: location of the joints on the top platform are called $b_i$
- $\hat{s}_i$: unit vector corresponding to the struts
- $k_i$: stiffness of the struts
- $\tau_i$: actuator forces
- $O_M$: center of mass of the solid body
Consider two frames:
- $\{M\}$ with origin $O_M$
- $\{K\}$ with origin $O_K$
An example is shown in Figure fig:stewart_architecture_example.
Objective
The objective is to find conditions for the existence of a frame $\{K\}$ in which the Stiffness matrix of the manipulator is diagonal. If the conditions are fulfilled, a second objective is to fine the location of the frame $\{K\}$ analytically.
Analytical formula of the stiffness matrix
For a fully parallel manipulator, the stiffness matrix $K_{\{K\}}$ expressed in a frame $\{K\}$ is:
\begin{equation} K_{\{K\}} = J_{\{K\}}^T \mathcal{K} J_{\{K\}} \end{equation}where:
- $K_{\{K\}}$ is the Jacobian transformation from the struts to the frame $\{K\}$
- $\mathcal{K}$ is a diagonal matrix with the strut stiffnesses on the diagonal
The analytical expression of $J_{\{K\}}$ is:
\begin{equation} J_{\{K\}} = \begin{bmatrix} {}^K\hat{s}_1^T & ({}^Kb_1 \times {}^K\hat{s}_1)^T \\ {}^K\hat{s}_2^T & ({}^Kb_2 \times {}^K\hat{s}_2)^T \\ \vdots & \vdots \\ {}^K\hat{s}_n^T & ({}^Kb_n \times {}^K\hat{s}_n)^T \end{bmatrix} \end{equation}To simplify, we ignore the superscript $K$ and we assume that all vectors / positions are expressed in this frame $\{K\}$. Otherwise, it is explicitly written.
Let's now write the analytical expressing of the stiffness matrix $K_{\{K\}}$:
\begin{equation} K_{\{K\}} = \begin{bmatrix} \hat{s}_1 & \dots & \hat{s}_n \\ (b_1 \times \hat{s}_1) & \dots & (b_n \times \hat{s}_n) \end{bmatrix} \begin{bmatrix} k_1 & & \\ & \ddots & \\ & & k_n \end{bmatrix} \begin{bmatrix} \hat{s}_1^T & (b_1 \times \hat{s}_1)^T \\ \hat{s}_2^T & (b_2 \times \hat{s}_2)^T \\ \vdots & \dots \\ \hat{s}_n^T & (b_n \times \hat{s}_n)^T \end{bmatrix} \end{equation}And we finally obtain:
\begin{equation} \boxed{ K_{\{K\}} = \left[ \begin{array}{c|c} k_i \hat{s}_i \hat{s}_i^T & k_i \hat{s}_i (b_i \times \hat{s}_i)^T \cr \hline k_i \hat{s}_i (b_i \times \hat{s}_i)^T & k_i (b_i \times \hat{s}_i) (b_i \times \hat{s}_i)^T \end{array} \right] } \end{equation}We want the stiffness matrix to be diagonal, therefore, we have the following conditions:
\begin{align} k_i \hat{s}_i \hat{s}_i^T &= \text{diag. matrix} \label{eq:diag_cond_1} \\ k_i (b_i \times \hat{s}_i) (b_i \times \hat{s}_i)^T &= \text{diag. matrix} \label{eq:diag_cond_2} \\ k_i \hat{s}_i (b_i \times \hat{s}_i)^T &= 0 \label{eq:diag_cond_3} \end{align}Note that:
- condition eqref:eq:diag_cond_1 corresponds to coupling between forces applied on $O_K$ to translations of the payload. It does not depend on the choice of $\{K\}$, it only depends on the orientation of the struts and the stiffnesses. It is therefore an intrinsic property of the manipulator.
- condition eqref:eq:diag_cond_2 corresponds to the coupling between forces applied on $O_K$ and rotation of the payload. Similarly, it does also correspond to the coupling between torques applied on $O_K$ to translations of the payload.
- condition eqref:eq:diag_cond_3 corresponds to the coupling between torques applied on $O_K$ to rotation of the payload.
- conditions eqref:eq:diag_cond_2 and eqref:eq:diag_cond_3 do depend on the positions ${}^Kb_i$ and therefore depend on the choice of $\{K\}$.
Note that if we find a frame $\{K\}$ in which the stiffness matrix $K_{\{K\}}$ is diagonal, it will still be diagonal for any rotation of the frame $\{K\}$. Therefore, we here suppose that the frame $\{K\}$ is aligned with the initial frame $\{M\}$.
Let's make a change of frame from the initial frame $\{M\}$ to the frame $\{K\}$:
\begin{align} {}^Kb_i &= {}^Mb_i - {}^MO_K \\ {}^K\hat{s}_i &= {}^M\hat{s}_i \end{align}The goal is to find ${}^MO_K$ such that conditions eqref:eq:diag_cond_2 and eqref:eq:diag_cond_3 are fulfilled.
Let's first solve equation eqref:eq:diag_cond_3 that corresponds to the coupling between forces and rotations:
\begin{equation} k_i \hat{s}_i (({}^Mb_i - {}^MO_K) \times \hat{s}_i)^T = 0 \end{equation}Taking the transpose and re-arranging:
\begin{equation} k_i ({}^Mb_i \times \hat{s}_i) \hat{s}_i^T = k_i ({}^MO_K \times \hat{s}_i) \hat{s}_i^T \end{equation}As the vector cross product also can be expressed as the product of a skew-symmetric matrix and a vector, we obtain:
\begin{equation} k_i ({}^Mb_i \times \hat{s}_i) \hat{s}_i^T = {}^M\bm{O}_{K} ( k_i \hat{s}_i \hat{s}_i^T ) \end{equation}
with:
\begin{equation} \label{eq:skew_symmetric_cross_product}
{}^M\bm{O}_K = \begin{bmatrix}
0 & -{}^MOK,z & {}^MOK,y
{}^MOK,z & 0 & -{}^MOK,x
-{}^MOK,y & {}^MOK,x & 0
\end{bmatrix}
\end{equation}
We suppose $k_i \hat{s}_i \hat{s}_i^T$ invertible as it is diagonal from eqref:eq:diag_cond_1.
And finally, we find:
\begin{equation} \boxed{ {}^M\bm{O}_{K} = \left( k_i ({}^Mb_i \times \hat{s}_i) \hat{s}_i^T\right) \cdot {\left( k_i \hat{s}_i \hat{s}_i^T \right)}^{-1} } \end{equation}If the obtained ${}^M\bm{O}_{K}$ is a skew-symmetric matrix, we can easily determine the corresponding vector ${}^MO_K$ from eqref:eq:skew_symmetric_cross_product.
In such case, condition eqref:eq:diag_cond_2 is fulfilled and there is no coupling between translations and rotations in the frame $\{K\}$.
Then, we can only verify if condition eqref:eq:diag_cond_3 is verified or not.
If there is no frame $\{K\}$ such that conditions eqref:eq:diag_cond_2 and eqref:eq:diag_cond_3 are valid, it would be interesting to be able to determine the frame $\{K\}$ in which is coupling is minimal.
Example 1 - 6DoF manipulator (3D)
Let's define the geometry of the manipulator (${}^Mb_i$, ${}^Ms_i$ and $k_i$):
ki = [2,2,1,1,3,3,1,1,1,1,2,2];
si = [[-1;0;0],[-1;0;0],[-1;0;0],[-1;0;0],[0;0;1],[0;0;1],[0;0;1],[0;0;1],[0;-1;0],[0;-1;0],[0;-1;0],[0;-1;0]];
bi = [[1;-1;1],[1;1;-1],[1;1;1],[1;-1;-1],[1;-1;-1],[-1;1;-1],[1;1;-1],[-1;-1;-1],[1;1;-1],[-1;1;1],[-1;1;-1],[1;1;1]]-[0;2;-1];
Cond 1:
ki.*si*si'
6 | 0 | 0 |
0 | 6 | 0 |
0 | 0 | 8 |
Find Ok
OkX = (ki.*cross(bi, si)*si')/(ki.*si*si');
if all(diag(OkX) == 0) && all(all((OkX + OkX') == 0))
disp('OkX is skew symmetric')
Ok = [OkX(3,2);OkX(1,3);OkX(2,1)]
else
error('OkX is *not* skew symmetric')
end
0 |
-2 |
1 |
% Verification of second condition
si*cross(bi-Ok, si)'
0 | 0 | 0 |
0 | 0 | 0 |
0 | 0 | 0 |
Verification of third condition
ki.*cross(bi-Ok, si)*cross(bi-Ok, si)'
14 | 4 | -2 |
4 | 14 | 2 |
-2 | 2 | 12 |
Let's compute the Jacobian:
Jk = [si', cross(bi - Ok, si)'];
And the stiffness matrix:
Jk'*diag(ki)*Jk
6 | 0 | 0 | 0 | 0 | 0 |
0 | 6 | 0 | 0 | 0 | 0 |
0 | 0 | 8 | 0 | 0 | 0 |
0 | 0 | 0 | 14 | 4 | -2 |
0 | 0 | 0 | 4 | 14 | 2 |
0 | 0 | 0 | -2 | 2 | 12 |
figure;
hold on;
set(gca,'ColorOrderIndex',1)
plot(b1(1), b1(2), 'o');
set(gca,'ColorOrderIndex',2)
plot(b2(1), b2(2), 'o');
set(gca,'ColorOrderIndex',3)
plot(b3(1), b3(2), 'o');
set(gca,'ColorOrderIndex',1)
quiver(b1(1),b1(2),0.1*s1(1),0.1*s1(2))
set(gca,'ColorOrderIndex',2)
quiver(b2(1),b2(2),0.1*s2(1),0.1*s2(2))
set(gca,'ColorOrderIndex',3)
quiver(b3(1),b3(2),0.1*s3(1),0.1*s3(2))
plot(0, 0, 'ko');
quiver([0,0],[0,0],[0.1,0],[0,0.1], 'k')
plot(Ok(1), Ok(2), 'ro');
quiver([Ok(1),Ok(1)],[Ok(2),Ok(2)],[0.1,0],[0,0.1], 'r')
hold off;
axis equal;
TODO Example 2 - Stewart Platform
Stewart Platform - Simscape Model
<<sec:stewart_platform>>
Introduction ignore
In this analysis, we wish to applied SVD control to the Stewart Platform shown in Figure fig:SP_assembly.
Some notes about the system:
- 6 voice coils actuators are used to control the motion of the top platform.
- the motion of the top platform is measured with a 6-axis inertial unit (3 acceleration + 3 angular accelerations)
- the control objective is to isolate the top platform from vibrations coming from the bottom platform
The analysis of the SVD/Jacobian control applied to the Stewart platform is performed in the following sections:
- Section sec:stewart_simscape: The parameters of the Simscape model of the Stewart platform are defined
- Section sec:stewart_identification: The plant is identified from the Simscape model and the system coupling is shown
- Section sec:stewart_jacobian_decoupling: The plant is first decoupled using the Jacobian
- Section sec:stewart_svd_decoupling: The decoupling is performed thanks to the SVD. To do so a real approximation of the plant is computed.
- Section sec:stewart_gershorin_radii: The effectiveness of the decoupling with the Jacobian and SVD are compared using the Gershorin Radii
- Section sec:stewart_rga:
- Section sec:stewart_decoupled_plant: The dynamics of the decoupled plants are shown
- Section sec:stewart_diagonal_control: A diagonal controller is defined to control the decoupled plant
- Section sec:stewart_closed_loop_results: Finally, the closed loop system properties are studied
Simscape Model - Parameters
<<sec:stewart_simscape>>
open('drone_platform.slx');
Definition of spring parameters:
kx = 0.5*1e3/3; % [N/m]
ky = 0.5*1e3/3;
kz = 1e3/3;
cx = 0.025; % [Nm/rad]
cy = 0.025;
cz = 0.025;
We suppose the sensor is perfectly positioned.
sens_pos_error = zeros(3,1);
Gravity:
g = 0;
We load the Jacobian (previously computed from the geometry):
load('jacobian.mat', 'Aa', 'Ab', 'As', 'l', 'J');
We initialize other parameters:
U = eye(6);
V = eye(6);
Kc = tf(zeros(6));
Identification of the plant
<<sec:stewart_identification>>
The plant shown in Figure fig:stewart_platform_plant is identified from the Simscape model.
The inputs are:
- $D_w$ translation and rotation of the bottom platform (with respect to the center of mass of the top platform)
- $\tau$ the 6 forces applied by the voice coils
The outputs are the 6 accelerations measured by the inertial unit.
%% Name of the Simulink File
mdl = 'drone_platform';
%% Input/Output definition
clear io; io_i = 1;
io(io_i) = linio([mdl, '/Dw'], 1, 'openinput'); io_i = io_i + 1; % Ground Motion
io(io_i) = linio([mdl, '/V-T'], 1, 'openinput'); io_i = io_i + 1; % Actuator Forces
io(io_i) = linio([mdl, '/Inertial Sensor'], 1, 'openoutput'); io_i = io_i + 1; % Top platform acceleration
G = linearize(mdl, io);
G.InputName = {'Dwx', 'Dwy', 'Dwz', 'Rwx', 'Rwy', 'Rwz', ...
'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
G.OutputName = {'Ax', 'Ay', 'Az', 'Arx', 'Ary', 'Arz'};
% Plant
Gu = G(:, {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'});
% Disturbance dynamics
Gd = G(:, {'Dwx', 'Dwy', 'Dwz', 'Rwx', 'Rwy', 'Rwz'});
There are 24 states (6dof for the bottom platform + 6dof for the top platform).
size(G)
State-space model with 6 outputs, 12 inputs, and 24 states.
The elements of the transfer matrix $\bm{G}$ corresponding to the transfer function from actuator forces $\tau$ to the measured acceleration $a$ are shown in Figure fig:stewart_platform_coupled_plant.
One can easily see that the system is strongly coupled.
Decoupling using the Jacobian
<<sec:stewart_jacobian_decoupling>> Consider the control architecture shown in Figure fig:plant_decouple_jacobian. The Jacobian matrix is used to transform forces/torques applied on the top platform to the equivalent forces applied by each actuator.
The Jacobian matrix is computed from the geometry of the platform (position and orientation of the actuators).
0.811 | 0.0 | 0.584 | -0.018 | -0.008 | 0.025 |
-0.406 | -0.703 | 0.584 | -0.016 | -0.012 | -0.025 |
-0.406 | 0.703 | 0.584 | 0.016 | -0.012 | 0.025 |
0.811 | 0.0 | 0.584 | 0.018 | -0.008 | -0.025 |
-0.406 | -0.703 | 0.584 | 0.002 | 0.019 | 0.025 |
-0.406 | 0.703 | 0.584 | -0.002 | 0.019 | -0.025 |
We define a new plant: \[ G_x(s) = G(s) J^{-T} \]
$G_x(s)$ correspond to the transfer function from forces and torques applied to the top platform to the absolute acceleration of the top platform.
Gx = Gu*inv(J');
Gx.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
Decoupling using the SVD
<<sec:stewart_svd_decoupling>>
In order to decouple the plant using the SVD, first a real approximation of the plant transfer function matrix as the crossover frequency is required.
Let's compute a real approximation of the complex matrix $H_1$ which corresponds to the the transfer function $G_u(j\omega_c)$ from forces applied by the actuators to the measured acceleration of the top platform evaluated at the frequency $\omega_c$.
wc = 2*pi*30; % Decoupling frequency [rad/s]
H1 = evalfr(Gu, j*wc);
The real approximation is computed as follows:
D = pinv(real(H1'*H1));
H1 = inv(D*real(H1'*diag(exp(j*angle(diag(H1*D*H1.'))/2))));
4.4 | -2.1 | -2.1 | 4.4 | -2.4 | -2.4 |
-0.2 | -3.9 | 3.9 | 0.2 | -3.8 | 3.8 |
3.4 | 3.4 | 3.4 | 3.4 | 3.4 | 3.4 |
-367.1 | -323.8 | 323.8 | 367.1 | 43.3 | -43.3 |
-162.0 | -237.0 | -237.0 | -162.0 | 398.9 | 398.9 |
220.6 | -220.6 | 220.6 | -220.6 | 220.6 | -220.6 |
Note that the plant $G_u$ at $\omega_c$ is already an almost real matrix. This can be seen on the Bode plots where the phase is close to 1. This can be verified below where only the real value of $G_u(\omega_c)$ is shown
4.4 | -2.1 | -2.1 | 4.4 | -2.4 | -2.4 |
-0.2 | -3.9 | 3.9 | 0.2 | -3.8 | 3.8 |
3.4 | 3.4 | 3.4 | 3.4 | 3.4 | 3.4 |
-367.1 | -323.8 | 323.8 | 367.1 | 43.3 | -43.3 |
-162.0 | -237.0 | -237.0 | -162.0 | 398.9 | 398.9 |
220.6 | -220.6 | 220.6 | -220.6 | 220.6 | -220.6 |
Now, the Singular Value Decomposition of $H_1$ is performed: \[ H_1 = U \Sigma V^H \]
[U,~,V] = svd(H1);
-0.005 | 7e-06 | 6e-11 | -3e-06 | -1 | 0.1 |
-7e-06 | -0.005 | -9e-09 | -5e-09 | -0.1 | -1 |
4e-08 | -2e-10 | -6e-11 | -1 | 3e-06 | -3e-07 |
-0.002 | -1 | -5e-06 | 2e-10 | 0.0006 | 0.005 |
1 | -0.002 | -1e-08 | 2e-08 | -0.005 | 0.0006 |
-4e-09 | 5e-06 | -1 | 6e-11 | -2e-09 | -1e-08 |
-0.2 | 0.5 | -0.4 | -0.4 | -0.6 | -0.2 |
-0.3 | 0.5 | 0.4 | -0.4 | 0.5 | 0.3 |
-0.3 | -0.5 | -0.4 | -0.4 | 0.4 | -0.4 |
-0.2 | -0.5 | 0.4 | -0.4 | -0.5 | 0.3 |
0.6 | -0.06 | -0.4 | -0.4 | 0.1 | 0.6 |
0.6 | 0.06 | 0.4 | -0.4 | -0.006 | -0.6 |
The obtained matrices $U$ and $V$ are used to decouple the system as shown in Figure fig:plant_decouple_svd.
The decoupled plant is then: \[ G_{SVD}(s) = U^{-1} G_u(s) V^{-H} \]
Gsvd = inv(U)*Gu*inv(V');
Verification of the decoupling using the "Gershgorin Radii"
<<sec:stewart_gershorin_radii>>
The "Gershgorin Radii" is computed for the coupled plant $G(s)$, for the "Jacobian plant" $G_x(s)$ and the "SVD Decoupled Plant" $G_{SVD}(s)$:
The "Gershgorin Radii" of a matrix $S$ is defined by: \[ \zeta_i(j\omega) = \frac{\sum\limits_{j\neq i}|S_{ij}(j\omega)|}{|S_{ii}(j\omega)|} \]
This is computed over the following frequencies.
Verification of the decoupling using the "Relative Gain Array"
<<sec:stewart_rga>>
The relative gain array (RGA) is defined as:
\begin{equation} \Lambda\big(G(s)\big) = G(s) \times \big( G(s)^{-1} \big)^T \end{equation}where $\times$ denotes an element by element multiplication and $G(s)$ is an $n \times n$ square transfer matrix.
The obtained RGA elements are shown in Figure fig:simscape_model_rga.
Obtained Decoupled Plants
<<sec:stewart_decoupled_plant>>
The bode plot of the diagonal and off-diagonal elements of $G_{SVD}$ are shown in Figure fig:simscape_model_decoupled_plant_svd.
Similarly, the bode plots of the diagonal elements and off-diagonal elements of the decoupled plant $G_x(s)$ using the Jacobian are shown in Figure fig:simscape_model_decoupled_plant_jacobian.
Diagonal Controller
<<sec:stewart_diagonal_control>> The control diagram for the centralized control is shown in Figure fig:centralized_control.
The controller $K_c$ is "working" in an cartesian frame. The Jacobian is used to convert forces in the cartesian frame to forces applied by the actuators.
The SVD control architecture is shown in Figure fig:svd_control. The matrices $U$ and $V$ are used to decoupled the plant $G$.
We choose the controller to be a low pass filter: \[ K_c(s) = \frac{G_0}{1 + \frac{s}{\omega_0}} \]
$G_0$ is tuned such that the crossover frequency corresponding to the diagonal terms of the loop gain is equal to $\omega_c$
wc = 2*pi*80; % Crossover Frequency [rad/s]
w0 = 2*pi*0.1; % Controller Pole [rad/s]
K_cen = diag(1./diag(abs(evalfr(Gx, j*wc))))*(1/abs(evalfr(1/(1 + s/w0), j*wc)))/(1 + s/w0);
L_cen = K_cen*Gx;
G_cen = feedback(G, pinv(J')*K_cen, [7:12], [1:6]);
K_svd = diag(1./diag(abs(evalfr(Gsvd, j*wc))))*(1/abs(evalfr(1/(1 + s/w0), j*wc)))/(1 + s/w0);
L_svd = K_svd*Gsvd;
G_svd = feedback(G, inv(V')*K_svd*inv(U), [7:12], [1:6]);
The obtained diagonal elements of the loop gains are shown in Figure fig:stewart_comp_loop_gain_diagonal.
Closed-Loop system Performances
<<sec:stewart_closed_loop_results>>
Let's first verify the stability of the closed-loop systems:
isstable(G_cen)
ans = logical 1
isstable(G_svd)
ans = logical 1
The obtained transmissibility in Open-loop, for the centralized control as well as for the SVD control are shown in Figure fig:stewart_platform_simscape_cl_transmissibility.