svd-control/index.html

1191 lines
43 KiB
HTML

<?xml version="1.0" encoding="utf-8"?>
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Strict//EN"
"http://www.w3.org/TR/xhtml1/DTD/xhtml1-strict.dtd">
<html xmlns="http://www.w3.org/1999/xhtml" lang="en" xml:lang="en">
<head>
<!-- 2020-11-16 lun. 14:57 -->
<meta http-equiv="Content-Type" content="text/html;charset=utf-8" />
<title>SVD Control</title>
<meta name="generator" content="Org mode" />
<meta name="author" content="Dehaeze Thomas" />
<link rel="stylesheet" type="text/css" href="https://research.tdehaeze.xyz/css/style.css"/>
<script type="text/javascript" src="https://research.tdehaeze.xyz/js/script.js"></script>
<script>MathJax = {
tex: {
tags: 'ams',
macros: {bm: ["\\boldsymbol{#1}",1],}
}
};
</script>
<script type="text/javascript" src="https://cdn.jsdelivr.net/npm/mathjax@3/es5/tex-mml-chtml.js"></script>
</head>
<body>
<div id="org-div-home-and-up">
<a accesskey="h" href="../index.html"> UP </a>
|
<a accesskey="H" href="../index.html"> HOME </a>
</div><div id="content">
<h1 class="title">SVD Control</h1>
<div id="table-of-contents">
<h2>Table of Contents</h2>
<div id="text-table-of-contents">
<ul>
<li><a href="#orgf63e94c">1. Gravimeter - Simscape Model</a>
<ul>
<li><a href="#orgc2c89e6">1.1. Introduction</a></li>
<li><a href="#orgda90b3d">1.2. Simscape Model - Parameters</a></li>
<li><a href="#org85c3f24">1.3. System Identification - Without Gravity</a></li>
<li><a href="#org8e5ae36">1.4. Physical Decoupling using the Jacobian</a></li>
<li><a href="#orgddfc400">1.5. Real Approximation of \(G\) at the decoupling frequency</a></li>
<li><a href="#org28831e0">1.6. SVD Decoupling</a></li>
<li><a href="#org1259605">1.7. Verification of the decoupling using the &ldquo;Gershgorin Radii&rdquo;</a></li>
<li><a href="#orgf7fb4bc">1.8. Obtained Decoupled Plants</a></li>
<li><a href="#org0f337cd">1.9. Diagonal Controller</a></li>
<li><a href="#org5626a2a">1.10. Closed-Loop system Performances</a></li>
</ul>
</li>
<li><a href="#org9de6455">2. Stewart Platform - Simscape Model</a>
<ul>
<li><a href="#org9fac4ff">2.1. Simscape Model - Parameters</a></li>
<li><a href="#org64c3675">2.2. Identification of the plant</a></li>
<li><a href="#org5553e88">2.3. Physical Decoupling using the Jacobian</a></li>
<li><a href="#orgb2fd90a">2.4. Real Approximation of \(G\) at the decoupling frequency</a></li>
<li><a href="#org2170f1f">2.5. SVD Decoupling</a></li>
<li><a href="#org3ab4ab3">2.6. Verification of the decoupling using the &ldquo;Gershgorin Radii&rdquo;</a></li>
<li><a href="#org4dc3b97">2.7. Obtained Decoupled Plants</a></li>
<li><a href="#org45ebb9e">2.8. Diagonal Controller</a></li>
<li><a href="#org24cfde2">2.9. Closed-Loop system Performances</a></li>
</ul>
</li>
</ul>
</div>
</div>
<div id="outline-container-orgf63e94c" class="outline-2">
<h2 id="orgf63e94c"><span class="section-number-2">1</span> Gravimeter - Simscape Model</h2>
<div class="outline-text-2" id="text-1">
</div>
<div id="outline-container-orgc2c89e6" class="outline-3">
<h3 id="orgc2c89e6"><span class="section-number-3">1.1</span> Introduction</h3>
<div class="outline-text-3" id="text-1-1">
<div id="orgc02238b" class="figure">
<p><img src="figs/gravimeter_model.png" alt="gravimeter_model.png" />
</p>
<p><span class="figure-number">Figure 1: </span>Model of the gravimeter</p>
</div>
</div>
</div>
<div id="outline-container-orgda90b3d" class="outline-3">
<h3 id="orgda90b3d"><span class="section-number-3">1.2</span> Simscape Model - Parameters</h3>
<div class="outline-text-3" id="text-1-2">
<div class="org-src-container">
<pre class="src src-matlab">open(<span class="org-string">'gravimeter.slx'</span>)
</pre>
</div>
<p>
Parameters
</p>
<div class="org-src-container">
<pre class="src src-matlab">l = 1.0; <span class="org-comment">% Length of the mass [m]</span>
h = 1.7; <span class="org-comment">% Height of the mass [m]</span>
la = l<span class="org-type">/</span>2; <span class="org-comment">% Position of Act. [m]</span>
ha = h<span class="org-type">/</span>2; <span class="org-comment">% Position of Act. [m]</span>
m = 400; <span class="org-comment">% Mass [kg]</span>
I = 115; <span class="org-comment">% Inertia [kg m^2]</span>
k = 15e3; <span class="org-comment">% Actuator Stiffness [N/m]</span>
c = 0.03; <span class="org-comment">% Actuator Damping [N/(m/s)]</span>
deq = 0.2; <span class="org-comment">% Length of the actuators [m]</span>
g = 0; <span class="org-comment">% Gravity [m/s2]</span>
</pre>
</div>
</div>
</div>
<div id="outline-container-org85c3f24" class="outline-3">
<h3 id="org85c3f24"><span class="section-number-3">1.3</span> System Identification - Without Gravity</h3>
<div class="outline-text-3" id="text-1-3">
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Name of the Simulink File</span></span>
mdl = <span class="org-string">'gravimeter'</span>;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Input/Output definition</span></span>
clear io; io_i = 1;
io(io_i) = linio([mdl, <span class="org-string">'/F1'</span>], 1, <span class="org-string">'openinput'</span>); io_i = io_i <span class="org-type">+</span> 1;
io(io_i) = linio([mdl, <span class="org-string">'/F2'</span>], 1, <span class="org-string">'openinput'</span>); io_i = io_i <span class="org-type">+</span> 1;
io(io_i) = linio([mdl, <span class="org-string">'/F3'</span>], 1, <span class="org-string">'openinput'</span>); io_i = io_i <span class="org-type">+</span> 1;
io(io_i) = linio([mdl, <span class="org-string">'/Acc_side'</span>], 1, <span class="org-string">'openoutput'</span>); io_i = io_i <span class="org-type">+</span> 1;
io(io_i) = linio([mdl, <span class="org-string">'/Acc_side'</span>], 2, <span class="org-string">'openoutput'</span>); io_i = io_i <span class="org-type">+</span> 1;
io(io_i) = linio([mdl, <span class="org-string">'/Acc_top'</span>], 1, <span class="org-string">'openoutput'</span>); io_i = io_i <span class="org-type">+</span> 1;
io(io_i) = linio([mdl, <span class="org-string">'/Acc_top'</span>], 2, <span class="org-string">'openoutput'</span>); io_i = io_i <span class="org-type">+</span> 1;
G = linearize(mdl, io);
G.InputName = {<span class="org-string">'F1'</span>, <span class="org-string">'F2'</span>, <span class="org-string">'F3'</span>};
G.OutputName = {<span class="org-string">'Ax1'</span>, <span class="org-string">'Az1'</span>, <span class="org-string">'Ax2'</span>, <span class="org-string">'Az2'</span>};
</pre>
</div>
<p>
The inputs and outputs of the plant are shown in Figure <a href="#org1e9a005">2</a>.
</p>
<div id="org1e9a005" class="figure">
<p><img src="figs/gravimeter_plant_schematic.png" alt="gravimeter_plant_schematic.png" />
</p>
<p><span class="figure-number">Figure 2: </span>Schematic of the gravimeter plant</p>
</div>
\begin{equation}
\bm{a} = \begin{bmatrix} a_{1x} \\ a_{1z} \\ a_{2x} \\ a_{2z} \end{bmatrix}
\end{equation}
\begin{equation}
\bm{\tau} = \begin{bmatrix}\tau_1 \\ \tau_2 \\ \tau_2 \end{bmatrix}
\end{equation}
<p>
We can check the poles of the plant:
</p>
<pre class="example" id="orgf282ac9">
-0.000183495485977108 + 13.546056874877i
-0.000183495485977108 - 13.546056874877i
-7.49842878906757e-05 + 8.65934902322567i
-7.49842878906757e-05 - 8.65934902322567i
-1.33171230256362e-05 + 3.64924169037897i
-1.33171230256362e-05 - 3.64924169037897i
</pre>
<p>
The plant as 6 states as expected (2 translations + 1 rotation)
</p>
<div class="org-src-container">
<pre class="src src-matlab">size(G)
</pre>
</div>
<pre class="example">
State-space model with 4 outputs, 3 inputs, and 6 states.
</pre>
<p>
The bode plot of all elements of the plant are shown in Figure <a href="#org46dddc8">3</a>.
</p>
<div id="org46dddc8" class="figure">
<p><img src="figs/open_loop_tf.png" alt="open_loop_tf.png" />
</p>
<p><span class="figure-number">Figure 3: </span>Open Loop Transfer Function from 3 Actuators to 4 Accelerometers</p>
</div>
</div>
</div>
<div id="outline-container-org8e5ae36" class="outline-3">
<h3 id="org8e5ae36"><span class="section-number-3">1.4</span> Physical Decoupling using the Jacobian</h3>
<div class="outline-text-3" id="text-1-4">
<p>
<a id="org205deff"></a>
</p>
<p>
Consider the control architecture shown in Figure <a href="#org37ed539">4</a>.
</p>
<p>
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.
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.
</p>
<p>
We thus define a new plant as defined in Figure <a href="#org37ed539">4</a>.
\[ G_x(s) = J_a G(s) J_{\tau}^{-T} \]
</p>
<p>
\(G_x(s)\) correspond to the transfer function from forces and torques applied to the gravimeter at its center of mass to the absolute acceleration of the gravimeter&rsquo;s center of mass.
</p>
<div id="org37ed539" class="figure">
<p><img src="figs/gravimeter_decouple_jacobian.png" alt="gravimeter_decouple_jacobian.png" />
</p>
<p><span class="figure-number">Figure 4: </span>Decoupled plant \(\bm{G}_x\) using the Jacobian matrix \(J\)</p>
</div>
<p>
The jacobian corresponding to the sensors and actuators are defined below.
</p>
<div class="org-src-container">
<pre class="src src-matlab">Ja = [1 0 h<span class="org-type">/</span>2
0 1 <span class="org-type">-</span>l<span class="org-type">/</span>2
1 0 <span class="org-type">-</span>h<span class="org-type">/</span>2
0 1 0];
Jt = [1 0 ha
0 1 <span class="org-type">-</span>la
0 1 la];
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">Gx = pinv(Ja)<span class="org-type">*</span>G<span class="org-type">*</span>pinv(Jt<span class="org-type">'</span>);
Gx.InputName = {<span class="org-string">'Fx'</span>, <span class="org-string">'Fz'</span>, <span class="org-string">'My'</span>};
Gx.OutputName = {<span class="org-string">'Dx'</span>, <span class="org-string">'Dz'</span>, <span class="org-string">'Ry'</span>};
</pre>
</div>
<p>
The diagonal and off-diagonal elements of \(G_x\) are shown in Figure <a href="#org8a23ee9">5</a>.
</p>
<div id="org8a23ee9" class="figure">
<p><img src="figs/gravimeter_jacobian_plant.png" alt="gravimeter_jacobian_plant.png" />
</p>
<p><span class="figure-number">Figure 5: </span>Diagonal and off-diagonal elements of \(G_x\)</p>
</div>
</div>
</div>
<div id="outline-container-orgddfc400" class="outline-3">
<h3 id="orgddfc400"><span class="section-number-3">1.5</span> Real Approximation of \(G\) at the decoupling frequency</h3>
<div class="outline-text-3" id="text-1-5">
<p>
<a id="orgba3d650"></a>
</p>
<p>
Let&rsquo;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\).
</p>
<div class="org-src-container">
<pre class="src src-matlab">wc = 2<span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">*</span>10; <span class="org-comment">% Decoupling frequency [rad/s]</span>
H1 = evalfr(G, <span class="org-constant">j</span><span class="org-type">*</span>wc);
</pre>
</div>
<p>
The real approximation is computed as follows:
</p>
<div class="org-src-container">
<pre class="src src-matlab">D = pinv(real(H1<span class="org-type">'*</span>H1));
H1 = inv(D<span class="org-type">*</span>real(H1<span class="org-type">'*</span>diag(exp(<span class="org-constant">j</span><span class="org-type">*</span>angle(diag(H1<span class="org-type">*</span>D<span class="org-type">*</span>H1<span class="org-type">.'</span>))<span class="org-type">/</span>2))));
</pre>
</div>
<table border="2" cellspacing="0" cellpadding="6" rules="groups" frame="hsides">
<caption class="t-above"><span class="table-number">Table 1:</span> Real approximate of \(G\) at the decoupling frequency \(\omega_c\)</caption>
<colgroup>
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
</colgroup>
<tbody>
<tr>
<td class="org-right">0.0026</td>
<td class="org-right">-3.7e-05</td>
<td class="org-right">3.7e-05</td>
</tr>
<tr>
<td class="org-right">1.9e-10</td>
<td class="org-right">0.0025</td>
<td class="org-right">0.0025</td>
</tr>
<tr>
<td class="org-right">-0.0078</td>
<td class="org-right">0.0045</td>
<td class="org-right">-0.0045</td>
</tr>
</tbody>
</table>
</div>
</div>
<div id="outline-container-org28831e0" class="outline-3">
<h3 id="org28831e0"><span class="section-number-3">1.6</span> SVD Decoupling</h3>
<div class="outline-text-3" id="text-1-6">
<p>
<a id="org3b895d5"></a>
</p>
<p>
First, the Singular Value Decomposition of \(H_1\) is performed:
\[ H_1 = U \Sigma V^H \]
</p>
<div class="org-src-container">
<pre class="src src-matlab">[U,<span class="org-type">~</span>,V] = svd(H1);
</pre>
</div>
<p>
The obtained matrices \(U\) and \(V\) are used to decouple the system as shown in Figure <a href="#orgf89ac65">6</a>.
</p>
<div id="orgf89ac65" class="figure">
<p><img src="figs/gravimeter_decouple_svd.png" alt="gravimeter_decouple_svd.png" />
</p>
<p><span class="figure-number">Figure 6: </span>Decoupled plant \(\bm{G}_{SVD}\) using the Singular Value Decomposition</p>
</div>
<p>
The decoupled plant is then:
\[ G_{SVD}(s) = U^{-1} G_u(s) V^{-H} \]
</p>
<div class="org-src-container">
<pre class="src src-matlab">Gsvd = inv(U)<span class="org-type">*</span>G<span class="org-type">*</span>inv(V<span class="org-type">'</span>);
</pre>
</div>
<p>
The diagonal and off-diagonal elements of the &ldquo;SVD&rdquo; plant are shown in Figure <a href="#org0156ba0">7</a>.
</p>
<div id="org0156ba0" class="figure">
<p><img src="figs/gravimeter_svd_plant.png" alt="gravimeter_svd_plant.png" />
</p>
<p><span class="figure-number">Figure 7: </span>Diagonal and off-diagonal elements of \(G_{svd}\)</p>
</div>
</div>
</div>
<div id="outline-container-org1259605" class="outline-3">
<h3 id="org1259605"><span class="section-number-3">1.7</span> Verification of the decoupling using the &ldquo;Gershgorin Radii&rdquo;</h3>
<div class="outline-text-3" id="text-1-7">
<p>
<a id="org481fdbf"></a>
</p>
<p>
The &ldquo;Gershgorin Radii&rdquo; is computed for the coupled plant \(G(s)\), for the &ldquo;Jacobian plant&rdquo; \(G_x(s)\) and the &ldquo;SVD Decoupled Plant&rdquo; \(G_{SVD}(s)\):
</p>
<p>
The &ldquo;Gershgorin Radii&rdquo; 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)|} \]
</p>
<p>
This is computed over the following frequencies.
</p>
<div class="org-src-container">
<pre class="src src-matlab">freqs = logspace(<span class="org-type">-</span>2, 2, 1000); <span class="org-comment">% [Hz]</span>
</pre>
</div>
<div id="orgf3eb235" class="figure">
<p><img src="figs/simscape_model_gershgorin_radii.png" alt="simscape_model_gershgorin_radii.png" />
</p>
<p><span class="figure-number">Figure 8: </span>Gershgorin Radii of the Coupled and Decoupled plants</p>
</div>
</div>
</div>
<div id="outline-container-orgf7fb4bc" class="outline-3">
<h3 id="orgf7fb4bc"><span class="section-number-3">1.8</span> Obtained Decoupled Plants</h3>
<div class="outline-text-3" id="text-1-8">
<p>
<a id="orgb69f29a"></a>
</p>
<p>
The bode plot of the diagonal and off-diagonal elements of \(G_{SVD}\) are shown in Figure <a href="#orgb60380e">9</a>.
</p>
<div id="orgb60380e" class="figure">
<p><img src="figs/simscape_model_decoupled_plant_svd.png" alt="simscape_model_decoupled_plant_svd.png" />
</p>
<p><span class="figure-number">Figure 9: </span>Decoupled Plant using SVD</p>
</div>
<p>
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 <a href="#orgbeb4333">10</a>.
</p>
<div id="orgbeb4333" class="figure">
<p><img src="figs/simscape_model_decoupled_plant_jacobian.png" alt="simscape_model_decoupled_plant_jacobian.png" />
</p>
<p><span class="figure-number">Figure 10: </span>Gravimeter Platform Plant from forces (resp. torques) applied by the legs to the acceleration (resp. angular acceleration) of the platform as well as all the coupling terms between the two (non-diagonal terms of the transfer function matrix)</p>
</div>
</div>
</div>
<div id="outline-container-org0f337cd" class="outline-3">
<h3 id="org0f337cd"><span class="section-number-3">1.9</span> Diagonal Controller</h3>
<div class="outline-text-3" id="text-1-9">
<p>
<a id="orgbb5b7ec"></a>
The control diagram for the centralized control is shown in Figure <a href="#org3c126ef">11</a>.
</p>
<p>
The controller \(K_c\) is &ldquo;working&rdquo; in an cartesian frame.
The Jacobian is used to convert forces in the cartesian frame to forces applied by the actuators.
</p>
<div id="org3c126ef" class="figure">
<p><img src="figs/centralized_control.png" alt="centralized_control.png" />
</p>
<p><span class="figure-number">Figure 11: </span>Control Diagram for the Centralized control</p>
</div>
<p>
The SVD control architecture is shown in Figure <a href="#org684edc8">12</a>.
The matrices \(U\) and \(V\) are used to decoupled the plant \(G\).
</p>
<div id="org684edc8" class="figure">
<p><img src="figs/svd_control.png" alt="svd_control.png" />
</p>
<p><span class="figure-number">Figure 12: </span>Control Diagram for the SVD control</p>
</div>
<p>
We choose the controller to be a low pass filter:
\[ K_c(s) = \frac{G_0}{1 + \frac{s}{\omega_0}} \]
</p>
<p>
\(G_0\) is tuned such that the crossover frequency corresponding to the diagonal terms of the loop gain is equal to \(\omega_c\)
</p>
<div class="org-src-container">
<pre class="src src-matlab">wc = 2<span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">*</span>80; <span class="org-comment">% Crossover Frequency [rad/s]</span>
w0 = 2<span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">*</span>0.1; <span class="org-comment">% Controller Pole [rad/s]</span>
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">K_cen = diag(1<span class="org-type">./</span>diag(abs(evalfr(Gx, <span class="org-constant">j</span><span class="org-type">*</span>wc))))<span class="org-type">*</span>(1<span class="org-type">/</span>abs(evalfr(1<span class="org-type">/</span>(1 <span class="org-type">+</span> s<span class="org-type">/</span>w0), <span class="org-constant">j</span><span class="org-type">*</span>wc)))<span class="org-type">/</span>(1 <span class="org-type">+</span> s<span class="org-type">/</span>w0);
L_cen = K_cen<span class="org-type">*</span>Gx;
G_cen = feedback(G, pinv(J<span class="org-type">'</span>)<span class="org-type">*</span>K_cen, [7<span class="org-type">:</span>12], [1<span class="org-type">:</span>6]);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">K_svd = diag(1<span class="org-type">./</span>diag(abs(evalfr(Gsvd, <span class="org-constant">j</span><span class="org-type">*</span>wc))))<span class="org-type">*</span>(1<span class="org-type">/</span>abs(evalfr(1<span class="org-type">/</span>(1 <span class="org-type">+</span> s<span class="org-type">/</span>w0), <span class="org-constant">j</span><span class="org-type">*</span>wc)))<span class="org-type">/</span>(1 <span class="org-type">+</span> s<span class="org-type">/</span>w0);
L_svd = K_svd<span class="org-type">*</span>Gsvd;
G_svd = feedback(G, inv(V<span class="org-type">'</span>)<span class="org-type">*</span>K_svd<span class="org-type">*</span>inv(U), [7<span class="org-type">:</span>12], [1<span class="org-type">:</span>6]);
</pre>
</div>
<p>
The obtained diagonal elements of the loop gains are shown in Figure <a href="#orgc17e119">13</a>.
</p>
<div id="orgc17e119" class="figure">
<p><img src="figs/gravimeter_comp_loop_gain_diagonal.png" alt="gravimeter_comp_loop_gain_diagonal.png" />
</p>
<p><span class="figure-number">Figure 13: </span>Comparison of the diagonal elements of the loop gains for the SVD control architecture and the Jacobian one</p>
</div>
</div>
</div>
<div id="outline-container-org5626a2a" class="outline-3">
<h3 id="org5626a2a"><span class="section-number-3">1.10</span> Closed-Loop system Performances</h3>
<div class="outline-text-3" id="text-1-10">
<p>
<a id="org1ea1fa6"></a>
</p>
<p>
Let&rsquo;s first verify the stability of the closed-loop systems:
</p>
<div class="org-src-container">
<pre class="src src-matlab">isstable(G_cen)
</pre>
</div>
<pre class="example">
ans =
logical
1
</pre>
<div class="org-src-container">
<pre class="src src-matlab">isstable(G_svd)
</pre>
</div>
<pre class="example">
ans =
logical
1
</pre>
<p>
The obtained transmissibility in Open-loop, for the centralized control as well as for the SVD control are shown in Figure <a href="#org48b61b4">14</a>.
</p>
<div id="org48b61b4" class="figure">
<p><img src="figs/gravimeter_platform_simscape_cl_transmissibility.png" alt="gravimeter_platform_simscape_cl_transmissibility.png" />
</p>
<p><span class="figure-number">Figure 14: </span>Obtained Transmissibility</p>
</div>
</div>
</div>
</div>
<div id="outline-container-org9de6455" class="outline-2">
<h2 id="org9de6455"><span class="section-number-2">2</span> Stewart Platform - Simscape Model</h2>
<div class="outline-text-2" id="text-2">
<p>
In this analysis, we wish to applied SVD control to the Stewart Platform shown in Figure <a href="#orgc0e86b2">15</a>.
</p>
<p>
Some notes about the system:
</p>
<ul class="org-ul">
<li>6 voice coils actuators are used to control the motion of the top platform.</li>
<li>the motion of the top platform is measured with a 6-axis inertial unit (3 acceleration + 3 angular accelerations)</li>
<li>the control objective is to isolate the top platform from vibrations coming from the bottom platform</li>
</ul>
<div id="orgc0e86b2" class="figure">
<p><img src="figs/SP_assembly.png" alt="SP_assembly.png" />
</p>
<p><span class="figure-number">Figure 15: </span>Stewart Platform CAD View</p>
</div>
<p>
The analysis of the SVD control applied to the Stewart platform is performed in the following sections:
</p>
<ul class="org-ul">
<li>Section <a href="#orgd7fb151">2.1</a>: The parameters of the Simscape model of the Stewart platform are defined</li>
<li>Section <a href="#org02e37d2">2.2</a>: The plant is identified from the Simscape model and the system coupling is shown</li>
<li>Section <a href="#orge673cb7">2.3</a>: The plant is first decoupled using the Jacobian</li>
<li>Section <a href="#org1ed6102">2.4</a>: A real approximation of the plant is computed for further decoupling using the Singular Value Decomposition (SVD)</li>
<li>Section <a href="#org4e65e2f">2.5</a>: The decoupling is performed thanks to the SVD</li>
<li>Section <a href="#org481fdbf">1.7</a>: The effectiveness of the decoupling with the Jacobian and SVD are compared using the Gershorin Radii</li>
<li>Section <a href="#org8e2bf48">2.7</a>: The dynamics of the decoupled plants are shown</li>
<li>Section <a href="#orgb15c6a0">2.8</a>: A diagonal controller is defined to control the decoupled plant</li>
<li>Section <a href="#org16d9e9e">2.9</a>: Finally, the closed loop system properties are studied</li>
</ul>
</div>
<div id="outline-container-org9fac4ff" class="outline-3">
<h3 id="org9fac4ff"><span class="section-number-3">2.1</span> Simscape Model - Parameters</h3>
<div class="outline-text-3" id="text-2-1">
<p>
<a id="orgd7fb151"></a>
</p>
<div class="org-src-container">
<pre class="src src-matlab">open(<span class="org-string">'drone_platform.slx'</span>);
</pre>
</div>
<p>
Definition of spring parameters:
</p>
<div class="org-src-container">
<pre class="src src-matlab">kx = 0.5<span class="org-type">*</span>1e3<span class="org-type">/</span>3; <span class="org-comment">% [N/m]</span>
ky = 0.5<span class="org-type">*</span>1e3<span class="org-type">/</span>3;
kz = 1e3<span class="org-type">/</span>3;
cx = 0.025; <span class="org-comment">% [Nm/rad]</span>
cy = 0.025;
cz = 0.025;
</pre>
</div>
<p>
Gravity:
</p>
<div class="org-src-container">
<pre class="src src-matlab">g = 0;
</pre>
</div>
<p>
We load the Jacobian (previously computed from the geometry):
</p>
<div class="org-src-container">
<pre class="src src-matlab">load(<span class="org-string">'./jacobian.mat'</span>, <span class="org-string">'Aa'</span>, <span class="org-string">'Ab'</span>, <span class="org-string">'As'</span>, <span class="org-string">'l'</span>, <span class="org-string">'J'</span>);
</pre>
</div>
<p>
We initialize other parameters:
</p>
<div class="org-src-container">
<pre class="src src-matlab">U = eye(6);
V = eye(6);
Kc = tf(zeros(6));
</pre>
</div>
<div id="org106c9cc" class="figure">
<p><img src="figs/stewart_simscape.png" alt="stewart_simscape.png" />
</p>
<p><span class="figure-number">Figure 16: </span>General view of the Simscape Model</p>
</div>
<div id="orgfc04931" class="figure">
<p><img src="figs/stewart_platform_details.png" alt="stewart_platform_details.png" />
</p>
<p><span class="figure-number">Figure 17: </span>Simscape model of the Stewart platform</p>
</div>
</div>
</div>
<div id="outline-container-org64c3675" class="outline-3">
<h3 id="org64c3675"><span class="section-number-3">2.2</span> Identification of the plant</h3>
<div class="outline-text-3" id="text-2-2">
<p>
<a id="org02e37d2"></a>
</p>
<p>
The plant shown in Figure <a href="#org33c829a">18</a> is identified from the Simscape model.
</p>
<p>
The inputs are:
</p>
<ul class="org-ul">
<li>\(D_w\) translation and rotation of the bottom platform (with respect to the center of mass of the top platform)</li>
<li>\(\tau\) the 6 forces applied by the voice coils</li>
</ul>
<p>
The outputs are the 6 accelerations measured by the inertial unit.
</p>
<div id="org33c829a" class="figure">
<p><img src="figs/stewart_platform_plant.png" alt="stewart_platform_plant.png" />
</p>
<p><span class="figure-number">Figure 18: </span>Considered plant \(\bm{G} = \begin{bmatrix}G_d\\G_u\end{bmatrix}\). \(D_w\) is the translation/rotation of the support, \(\tau\) the actuator forces, \(a\) the acceleration/angular acceleration of the top platform</p>
</div>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Name of the Simulink File</span></span>
mdl = <span class="org-string">'drone_platform'</span>;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Input/Output definition</span></span>
clear io; io_i = 1;
io(io_i) = linio([mdl, <span class="org-string">'/Dw'</span>], 1, <span class="org-string">'openinput'</span>); io_i = io_i <span class="org-type">+</span> 1; <span class="org-comment">% Ground Motion</span>
io(io_i) = linio([mdl, <span class="org-string">'/V-T'</span>], 1, <span class="org-string">'openinput'</span>); io_i = io_i <span class="org-type">+</span> 1; <span class="org-comment">% Actuator Forces</span>
io(io_i) = linio([mdl, <span class="org-string">'/Inertial Sensor'</span>], 1, <span class="org-string">'openoutput'</span>); io_i = io_i <span class="org-type">+</span> 1; <span class="org-comment">% Top platform acceleration</span>
G = linearize(mdl, io);
G.InputName = {<span class="org-string">'Dwx'</span>, <span class="org-string">'Dwy'</span>, <span class="org-string">'Dwz'</span>, <span class="org-string">'Rwx'</span>, <span class="org-string">'Rwy'</span>, <span class="org-string">'Rwz'</span>, ...
<span class="org-string">'F1'</span>, <span class="org-string">'F2'</span>, <span class="org-string">'F3'</span>, <span class="org-string">'F4'</span>, <span class="org-string">'F5'</span>, <span class="org-string">'F6'</span>};
G.OutputName = {<span class="org-string">'Ax'</span>, <span class="org-string">'Ay'</span>, <span class="org-string">'Az'</span>, <span class="org-string">'Arx'</span>, <span class="org-string">'Ary'</span>, <span class="org-string">'Arz'</span>};
<span class="org-comment">% Plant</span>
Gu = G(<span class="org-type">:</span>, {<span class="org-string">'F1'</span>, <span class="org-string">'F2'</span>, <span class="org-string">'F3'</span>, <span class="org-string">'F4'</span>, <span class="org-string">'F5'</span>, <span class="org-string">'F6'</span>});
<span class="org-comment">% Disturbance dynamics</span>
Gd = G(<span class="org-type">:</span>, {<span class="org-string">'Dwx'</span>, <span class="org-string">'Dwy'</span>, <span class="org-string">'Dwz'</span>, <span class="org-string">'Rwx'</span>, <span class="org-string">'Rwy'</span>, <span class="org-string">'Rwz'</span>});
</pre>
</div>
<p>
There are 24 states (6dof for the bottom platform + 6dof for the top platform).
</p>
<div class="org-src-container">
<pre class="src src-matlab">size(G)
</pre>
</div>
<pre class="example">
State-space model with 6 outputs, 12 inputs, and 24 states.
</pre>
<p>
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 <a href="#orgc011df4">19</a>.
</p>
<p>
One can easily see that the system is strongly coupled.
</p>
<div id="orgc011df4" class="figure">
<p><img src="figs/stewart_platform_coupled_plant.png" alt="stewart_platform_coupled_plant.png" />
</p>
<p><span class="figure-number">Figure 19: </span>Magnitude of all 36 elements of the transfer function matrix \(G_u\)</p>
</div>
</div>
</div>
<div id="outline-container-org5553e88" class="outline-3">
<h3 id="org5553e88"><span class="section-number-3">2.3</span> Physical Decoupling using the Jacobian</h3>
<div class="outline-text-3" id="text-2-3">
<p>
<a id="orge673cb7"></a>
Consider the control architecture shown in Figure <a href="#orgd600249">20</a>.
The Jacobian matrix is used to transform forces/torques applied on the top platform to the equivalent forces applied by each actuator.
</p>
<div id="orgd600249" class="figure">
<p><img src="figs/plant_decouple_jacobian.png" alt="plant_decouple_jacobian.png" />
</p>
<p><span class="figure-number">Figure 20: </span>Decoupled plant \(\bm{G}_x\) using the Jacobian matrix \(J\)</p>
</div>
<p>
We define a new plant:
\[ G_x(s) = G(s) J^{-T} \]
</p>
<p>
\(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.
</p>
<div class="org-src-container">
<pre class="src src-matlab">Gx = Gu<span class="org-type">*</span>inv(J<span class="org-type">'</span>);
Gx.InputName = {<span class="org-string">'Fx'</span>, <span class="org-string">'Fy'</span>, <span class="org-string">'Fz'</span>, <span class="org-string">'Mx'</span>, <span class="org-string">'My'</span>, <span class="org-string">'Mz'</span>};
</pre>
</div>
</div>
</div>
<div id="outline-container-orgb2fd90a" class="outline-3">
<h3 id="orgb2fd90a"><span class="section-number-3">2.4</span> Real Approximation of \(G\) at the decoupling frequency</h3>
<div class="outline-text-3" id="text-2-4">
<p>
<a id="org1ed6102"></a>
</p>
<p>
Let&rsquo;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\).
</p>
<div class="org-src-container">
<pre class="src src-matlab">wc = 2<span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">*</span>30; <span class="org-comment">% Decoupling frequency [rad/s]</span>
H1 = evalfr(Gu, <span class="org-constant">j</span><span class="org-type">*</span>wc);
</pre>
</div>
<p>
The real approximation is computed as follows:
</p>
<div class="org-src-container">
<pre class="src src-matlab">D = pinv(real(H1<span class="org-type">'*</span>H1));
H1 = inv(D<span class="org-type">*</span>real(H1<span class="org-type">'*</span>diag(exp(<span class="org-constant">j</span><span class="org-type">*</span>angle(diag(H1<span class="org-type">*</span>D<span class="org-type">*</span>H1<span class="org-type">.'</span>))<span class="org-type">/</span>2))));
</pre>
</div>
<table border="2" cellspacing="0" cellpadding="6" rules="groups" frame="hsides">
<caption class="t-above"><span class="table-number">Table 2:</span> Real approximate of \(G\) at the decoupling frequency \(\omega_c\)</caption>
<colgroup>
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
</colgroup>
<tbody>
<tr>
<td class="org-right">4.4</td>
<td class="org-right">-2.1</td>
<td class="org-right">-2.1</td>
<td class="org-right">4.4</td>
<td class="org-right">-2.4</td>
<td class="org-right">-2.4</td>
</tr>
<tr>
<td class="org-right">-0.2</td>
<td class="org-right">-3.9</td>
<td class="org-right">3.9</td>
<td class="org-right">0.2</td>
<td class="org-right">-3.8</td>
<td class="org-right">3.8</td>
</tr>
<tr>
<td class="org-right">3.4</td>
<td class="org-right">3.4</td>
<td class="org-right">3.4</td>
<td class="org-right">3.4</td>
<td class="org-right">3.4</td>
<td class="org-right">3.4</td>
</tr>
<tr>
<td class="org-right">-367.1</td>
<td class="org-right">-323.8</td>
<td class="org-right">323.8</td>
<td class="org-right">367.1</td>
<td class="org-right">43.3</td>
<td class="org-right">-43.3</td>
</tr>
<tr>
<td class="org-right">-162.0</td>
<td class="org-right">-237.0</td>
<td class="org-right">-237.0</td>
<td class="org-right">-162.0</td>
<td class="org-right">398.9</td>
<td class="org-right">398.9</td>
</tr>
<tr>
<td class="org-right">220.6</td>
<td class="org-right">-220.6</td>
<td class="org-right">220.6</td>
<td class="org-right">-220.6</td>
<td class="org-right">220.6</td>
<td class="org-right">-220.6</td>
</tr>
</tbody>
</table>
<p>
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
</p>
<table border="2" cellspacing="0" cellpadding="6" rules="groups" frame="hsides">
<colgroup>
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
</colgroup>
<tbody>
<tr>
<td class="org-right">4.4</td>
<td class="org-right">-2.1</td>
<td class="org-right">-2.1</td>
<td class="org-right">4.4</td>
<td class="org-right">-2.4</td>
<td class="org-right">-2.4</td>
</tr>
<tr>
<td class="org-right">-0.2</td>
<td class="org-right">-3.9</td>
<td class="org-right">3.9</td>
<td class="org-right">0.2</td>
<td class="org-right">-3.8</td>
<td class="org-right">3.8</td>
</tr>
<tr>
<td class="org-right">3.4</td>
<td class="org-right">3.4</td>
<td class="org-right">3.4</td>
<td class="org-right">3.4</td>
<td class="org-right">3.4</td>
<td class="org-right">3.4</td>
</tr>
<tr>
<td class="org-right">-367.1</td>
<td class="org-right">-323.8</td>
<td class="org-right">323.8</td>
<td class="org-right">367.1</td>
<td class="org-right">43.3</td>
<td class="org-right">-43.3</td>
</tr>
<tr>
<td class="org-right">-162.0</td>
<td class="org-right">-237.0</td>
<td class="org-right">-237.0</td>
<td class="org-right">-162.0</td>
<td class="org-right">398.9</td>
<td class="org-right">398.9</td>
</tr>
<tr>
<td class="org-right">220.6</td>
<td class="org-right">-220.6</td>
<td class="org-right">220.6</td>
<td class="org-right">-220.6</td>
<td class="org-right">220.6</td>
<td class="org-right">-220.6</td>
</tr>
</tbody>
</table>
</div>
</div>
<div id="outline-container-org2170f1f" class="outline-3">
<h3 id="org2170f1f"><span class="section-number-3">2.5</span> SVD Decoupling</h3>
<div class="outline-text-3" id="text-2-5">
<p>
<a id="org4e65e2f"></a>
</p>
<p>
First, the Singular Value Decomposition of \(H_1\) is performed:
\[ H_1 = U \Sigma V^H \]
</p>
<div class="org-src-container">
<pre class="src src-matlab">[U,<span class="org-type">~</span>,V] = svd(H1);
</pre>
</div>
<p>
The obtained matrices \(U\) and \(V\) are used to decouple the system as shown in Figure <a href="#org6359e10">21</a>.
</p>
<div id="org6359e10" class="figure">
<p><img src="figs/plant_decouple_svd.png" alt="plant_decouple_svd.png" />
</p>
<p><span class="figure-number">Figure 21: </span>Decoupled plant \(\bm{G}_{SVD}\) using the Singular Value Decomposition</p>
</div>
<p>
The decoupled plant is then:
\[ G_{SVD}(s) = U^{-1} G_u(s) V^{-H} \]
</p>
<div class="org-src-container">
<pre class="src src-matlab">Gsvd = inv(U)<span class="org-type">*</span>Gu<span class="org-type">*</span>inv(V<span class="org-type">'</span>);
</pre>
</div>
</div>
</div>
<div id="outline-container-org3ab4ab3" class="outline-3">
<h3 id="org3ab4ab3"><span class="section-number-3">2.6</span> Verification of the decoupling using the &ldquo;Gershgorin Radii&rdquo;</h3>
<div class="outline-text-3" id="text-2-6">
<p>
<a id="orgdcdf134"></a>
</p>
<p>
The &ldquo;Gershgorin Radii&rdquo; is computed for the coupled plant \(G(s)\), for the &ldquo;Jacobian plant&rdquo; \(G_x(s)\) and the &ldquo;SVD Decoupled Plant&rdquo; \(G_{SVD}(s)\):
</p>
<p>
The &ldquo;Gershgorin Radii&rdquo; 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)|} \]
</p>
<p>
This is computed over the following frequencies.
</p>
<div class="org-src-container">
<pre class="src src-matlab">freqs = logspace(<span class="org-type">-</span>2, 2, 1000); <span class="org-comment">% [Hz]</span>
</pre>
</div>
<div id="orgd2ce493" class="figure">
<p><img src="figs/simscape_model_gershgorin_radii.png" alt="simscape_model_gershgorin_radii.png" />
</p>
<p><span class="figure-number">Figure 22: </span>Gershgorin Radii of the Coupled and Decoupled plants</p>
</div>
</div>
</div>
<div id="outline-container-org4dc3b97" class="outline-3">
<h3 id="org4dc3b97"><span class="section-number-3">2.7</span> Obtained Decoupled Plants</h3>
<div class="outline-text-3" id="text-2-7">
<p>
<a id="org8e2bf48"></a>
</p>
<p>
The bode plot of the diagonal and off-diagonal elements of \(G_{SVD}\) are shown in Figure <a href="#orgb60380e">9</a>.
</p>
<div id="orgfd8a34b" class="figure">
<p><img src="figs/simscape_model_decoupled_plant_svd.png" alt="simscape_model_decoupled_plant_svd.png" />
</p>
<p><span class="figure-number">Figure 23: </span>Decoupled Plant using SVD</p>
</div>
<p>
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 <a href="#orgbeb4333">10</a>.
</p>
<div id="org1804588" class="figure">
<p><img src="figs/simscape_model_decoupled_plant_jacobian.png" alt="simscape_model_decoupled_plant_jacobian.png" />
</p>
<p><span class="figure-number">Figure 24: </span>Stewart Platform Plant from forces (resp. torques) applied by the legs to the acceleration (resp. angular acceleration) of the platform as well as all the coupling terms between the two (non-diagonal terms of the transfer function matrix)</p>
</div>
</div>
</div>
<div id="outline-container-org45ebb9e" class="outline-3">
<h3 id="org45ebb9e"><span class="section-number-3">2.8</span> Diagonal Controller</h3>
<div class="outline-text-3" id="text-2-8">
<p>
<a id="orgb15c6a0"></a>
The control diagram for the centralized control is shown in Figure <a href="#org3c126ef">11</a>.
</p>
<p>
The controller \(K_c\) is &ldquo;working&rdquo; in an cartesian frame.
The Jacobian is used to convert forces in the cartesian frame to forces applied by the actuators.
</p>
<div id="org77500bd" class="figure">
<p><img src="figs/centralized_control.png" alt="centralized_control.png" />
</p>
<p><span class="figure-number">Figure 25: </span>Control Diagram for the Centralized control</p>
</div>
<p>
The SVD control architecture is shown in Figure <a href="#org684edc8">12</a>.
The matrices \(U\) and \(V\) are used to decoupled the plant \(G\).
</p>
<div id="orgae6c81f" class="figure">
<p><img src="figs/svd_control.png" alt="svd_control.png" />
</p>
<p><span class="figure-number">Figure 26: </span>Control Diagram for the SVD control</p>
</div>
<p>
We choose the controller to be a low pass filter:
\[ K_c(s) = \frac{G_0}{1 + \frac{s}{\omega_0}} \]
</p>
<p>
\(G_0\) is tuned such that the crossover frequency corresponding to the diagonal terms of the loop gain is equal to \(\omega_c\)
</p>
<div class="org-src-container">
<pre class="src src-matlab">wc = 2<span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">*</span>80; <span class="org-comment">% Crossover Frequency [rad/s]</span>
w0 = 2<span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">*</span>0.1; <span class="org-comment">% Controller Pole [rad/s]</span>
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">K_cen = diag(1<span class="org-type">./</span>diag(abs(evalfr(Gx, <span class="org-constant">j</span><span class="org-type">*</span>wc))))<span class="org-type">*</span>(1<span class="org-type">/</span>abs(evalfr(1<span class="org-type">/</span>(1 <span class="org-type">+</span> s<span class="org-type">/</span>w0), <span class="org-constant">j</span><span class="org-type">*</span>wc)))<span class="org-type">/</span>(1 <span class="org-type">+</span> s<span class="org-type">/</span>w0);
L_cen = K_cen<span class="org-type">*</span>Gx;
G_cen = feedback(G, pinv(J<span class="org-type">'</span>)<span class="org-type">*</span>K_cen, [7<span class="org-type">:</span>12], [1<span class="org-type">:</span>6]);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">K_svd = diag(1<span class="org-type">./</span>diag(abs(evalfr(Gsvd, <span class="org-constant">j</span><span class="org-type">*</span>wc))))<span class="org-type">*</span>(1<span class="org-type">/</span>abs(evalfr(1<span class="org-type">/</span>(1 <span class="org-type">+</span> s<span class="org-type">/</span>w0), <span class="org-constant">j</span><span class="org-type">*</span>wc)))<span class="org-type">/</span>(1 <span class="org-type">+</span> s<span class="org-type">/</span>w0);
L_svd = K_svd<span class="org-type">*</span>Gsvd;
G_svd = feedback(G, inv(V<span class="org-type">'</span>)<span class="org-type">*</span>K_svd<span class="org-type">*</span>inv(U), [7<span class="org-type">:</span>12], [1<span class="org-type">:</span>6]);
</pre>
</div>
<p>
The obtained diagonal elements of the loop gains are shown in Figure <a href="#orgda3965b">27</a>.
</p>
<div id="orgda3965b" class="figure">
<p><img src="figs/stewart_comp_loop_gain_diagonal.png" alt="stewart_comp_loop_gain_diagonal.png" />
</p>
<p><span class="figure-number">Figure 27: </span>Comparison of the diagonal elements of the loop gains for the SVD control architecture and the Jacobian one</p>
</div>
</div>
</div>
<div id="outline-container-org24cfde2" class="outline-3">
<h3 id="org24cfde2"><span class="section-number-3">2.9</span> Closed-Loop system Performances</h3>
<div class="outline-text-3" id="text-2-9">
<p>
<a id="org16d9e9e"></a>
</p>
<p>
Let&rsquo;s first verify the stability of the closed-loop systems:
</p>
<div class="org-src-container">
<pre class="src src-matlab">isstable(G_cen)
</pre>
</div>
<pre class="example">
ans =
logical
1
</pre>
<div class="org-src-container">
<pre class="src src-matlab">isstable(G_svd)
</pre>
</div>
<pre class="example">
ans =
logical
1
</pre>
<p>
The obtained transmissibility in Open-loop, for the centralized control as well as for the SVD control are shown in Figure <a href="#orgd4c5aa5">28</a>.
</p>
<div id="orgd4c5aa5" class="figure">
<p><img src="figs/stewart_platform_simscape_cl_transmissibility.png" alt="stewart_platform_simscape_cl_transmissibility.png" />
</p>
<p><span class="figure-number">Figure 28: </span>Obtained Transmissibility</p>
</div>
</div>
</div>
</div>
</div>
<div id="postamble" class="status">
<p class="author">Author: Dehaeze Thomas</p>
<p class="date">Created: 2020-11-16 lun. 14:57</p>
</div>
</body>
</html>