dcm-simscape-model/dcm-simscape.html

915 lines
29 KiB
HTML
Raw Normal View History

2021-11-30 11:28:07 +01:00
<?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>
<!-- 2021-11-30 mar. 11:26 -->
<meta http-equiv="Content-Type" content="text/html;charset=utf-8" />
<title>DCM - Dynamical Multi-Body Model</title>
<meta name="author" content="Dehaeze Thomas" />
<meta name="generator" content="Org Mode" />
<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 = {
svg: {
scale: 1,
fontCache: "global"
},
tex: {
tags: "ams",
multlineWidth: "%MULTLINEWIDTH",
tagSide: "right",
macros: {bm: ["\\boldsymbol{#1}",1],},
tagIndent: ".8em"
}
};
</script>
<script id="MathJax-script" async
src="https://cdn.jsdelivr.net/npm/mathjax@3/es5/tex-svg.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" class="content">
<h1 class="title">DCM - Dynamical Multi-Body Model</h1>
<div id="table-of-contents" role="doc-toc">
<h2>Table of Contents</h2>
<div id="text-table-of-contents" role="doc-toc">
<ul>
<li><a href="#orgeeaccd1">1. System Kinematics</a>
<ul>
<li><a href="#org82f10d2">1.1. Bragg Angle</a></li>
<li><a href="#orgea96012">1.2. Kinematics (111 Crystal)</a>
<ul>
<li><a href="#org1ea22c7">1.2.1. Interferometers - 111 Crystal</a></li>
<li><a href="#orgdcb38e9">1.2.2. Piezo - 111 Crystal</a></li>
</ul>
</li>
<li><a href="#org7beb5f6">1.3. Save Kinematics</a></li>
</ul>
</li>
<li><a href="#orgc562e49">2. Open Loop System Identification</a>
<ul>
<li><a href="#org461a35a">2.1. Identification</a></li>
<li><a href="#org32530ab">2.2. Plant in the frame of the fastjacks</a></li>
<li><a href="#org831ac4a">2.3. Plant in the frame of the crystal</a></li>
</ul>
</li>
<li><a href="#org6a67c7c">3. Active Damping Plant (Strain gauges)</a>
<ul>
<li><a href="#org59bf8d2">3.1. Identification</a></li>
</ul>
</li>
<li><a href="#org98018d6">4. Active Damping Plant (Force Sensors)</a>
<ul>
<li><a href="#orgf3d05f6">4.1. Identification</a></li>
<li><a href="#org2c7747a">4.2. Controller - Root Locus</a></li>
<li><a href="#org44eaa41">4.3. Damped Plant</a></li>
<li><a href="#orgd9ea17f">4.4. Save</a></li>
</ul>
</li>
<li><a href="#org93a00ff">5. HAC-LAC (IFF) architecture</a></li>
</ul>
</div>
</div>
<hr>
<p>This report is also available as a <a href="./dcm-simscape.pdf">pdf</a>.</p>
<hr>
<p>
In this document, a Simscape (.e.g. multi-body) model of the ESRF Double Crystal Monochromator (DCM) is presented and used to develop and optimize the control strategy.
</p>
<p>
It is structured as follow:
</p>
<ul class="org-ul">
<li>Section <a href="#org2e89cff">1</a>: the kinematics of the DCM is presented, and Jacobian matrices which are used to solve the inverse and forward kinematics are computed.</li>
<li>Section <a href="#orgdd4a98d">2</a>: the system dynamics is identified in the absence of control.</li>
<li>Section <a href="#orgdeb64e7">3</a>: it is studied whether if the strain gauges fixed to the piezoelectric actuators can be used to actively damp the plant.</li>
<li>Section <a href="#org624796e">4</a>: piezoelectric force sensors are added in series with the piezoelectric actuators and are used to actively damp the plant using the Integral Force Feedback (IFF) control strategy.</li>
<li>Section <a href="#orga8f0b23">5</a>: the High Authority Control - Low Authority Control (HAC-LAC) strategy is tested on the Simscape model.</li>
</ul>
<div id="outline-container-orgeeaccd1" class="outline-2">
<h2 id="orgeeaccd1"><span class="section-number-2">1.</span> System Kinematics</h2>
<div class="outline-text-2" id="text-1">
<p>
<a id="org2e89cff"></a>
</p>
</div>
<div id="outline-container-org82f10d2" class="outline-3">
<h3 id="org82f10d2"><span class="section-number-3">1.1.</span> Bragg Angle</h3>
<div class="outline-text-3" id="text-1-1">
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak">%% Tested bragg angles</span>
bragg = linspace(5, 80, 1000); <span class="org-comment-delimiter">% </span><span class="org-comment">Bragg angle [deg]</span>
d_off = 10.5e<span class="org-builtin">-</span>3; <span class="org-comment-delimiter">% </span><span class="org-comment">Wanted offset between x-rays [m]</span>
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak">%% Vertical Jack motion as a function of Bragg angle</span>
dz = d_off<span class="org-builtin">./</span>(2<span class="org-builtin">*</span>cos(bragg<span class="org-builtin">*</span><span class="org-matlab-math">pi</span><span class="org-builtin">/</span>180));
</pre>
</div>
<div id="org41541e2" class="figure">
<p><img src="figs/jack_motion_bragg_angle.png" alt="jack_motion_bragg_angle.png" />
</p>
<p><span class="figure-number">Figure 1: </span>Jack motion as a function of Bragg angle</p>
</div>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak">%% Required Jack stroke</span>
<span class="org-matlab-math">ans</span> = 1e3<span class="org-builtin">*</span>(dz(end) <span class="org-builtin">-</span> dz(1))
</pre>
</div>
<pre class="example">
24.963
</pre>
</div>
</div>
<div id="outline-container-orgea96012" class="outline-3">
<h3 id="orgea96012"><span class="section-number-3">1.2.</span> Kinematics (111 Crystal)</h3>
<div class="outline-text-3" id="text-1-2">
<p>
The reference frame is taken at the center of the 111 second crystal.
</p>
</div>
<div id="outline-container-org1ea22c7" class="outline-4">
<h4 id="org1ea22c7"><span class="section-number-4">1.2.1.</span> Interferometers - 111 Crystal</h4>
<div class="outline-text-4" id="text-1-2-1">
<p>
Three interferometers are pointed to the bottom surface of the 111 crystal.
</p>
<p>
The position of the measurement points are shown in Figure <a href="#org2ba7ed7">2</a> as well as the origin where the motion of the crystal is computed.
</p>
<div id="org2ba7ed7" class="figure">
<p><img src="figs/sensor_111_crystal_points.png" alt="sensor_111_crystal_points.png" />
</p>
<p><span class="figure-number">Figure 2: </span>Bottom view of the second crystal 111. Position of the measurement points.</p>
</div>
<p>
The inverse kinematics consisting of deriving the interferometer measurements from the motion of the crystal (see Figure <a href="#orga898030">3</a>):
</p>
\begin{equation}
\begin{bmatrix}
x_1 \\ x_2 \\ x_3
\end{bmatrix}
=
\bm{J}_{s,111}
\begin{bmatrix}
d_z \\ r_y \\ r_x
\end{bmatrix}
\end{equation}
<div id="orga898030" class="figure">
<p><img src="figs/schematic_sensor_jacobian_inverse_kinematics.png" alt="schematic_sensor_jacobian_inverse_kinematics.png" />
</p>
<p><span class="figure-number">Figure 3: </span>Inverse Kinematics - Interferometers</p>
</div>
<p>
From the Figure <a href="#org2ba7ed7">2</a>, the inverse kinematics can be solved as follow (for small motion):
</p>
\begin{equation}
\bm{J}_{s,111}
=
\begin{bmatrix}
1 & 0.07 & -0.015 \\
1 & 0 & 0.015 \\
1 & -0.07 & -0.015
\end{bmatrix}
\end{equation}
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak">%% Sensor Jacobian matrix for 111 crystal</span>
J_s_111 = [1, 0.07, <span class="org-builtin">-</span>0.015
1, 0, 0.015
1, <span class="org-builtin">-</span>0.07, <span class="org-builtin">-</span>0.015];
</pre>
</div>
<table id="org798edde" border="2" cellspacing="0" cellpadding="6" rules="groups" frame="hsides">
<caption class="t-above"><span class="table-number">Table 1:</span> Sensor Jacobian \(\bm{J}_{s,111}\)</caption>
<colgroup>
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
</colgroup>
<tbody>
<tr>
<td class="org-right">1.0</td>
<td class="org-right">0.07</td>
<td class="org-right">-0.015</td>
</tr>
<tr>
<td class="org-right">1.0</td>
<td class="org-right">0.0</td>
<td class="org-right">0.015</td>
</tr>
<tr>
<td class="org-right">1.0</td>
<td class="org-right">-0.07</td>
<td class="org-right">-0.015</td>
</tr>
</tbody>
</table>
<p>
The forward kinematics is solved by inverting the Jacobian matrix (see Figure <a href="#org1633a04">4</a>).
</p>
\begin{equation}
\begin{bmatrix}
d_z \\ r_y \\ r_x
\end{bmatrix}
=
\bm{J}_{s,111}^{-1}
\begin{bmatrix}
x_1 \\ x_2 \\ x_3
\end{bmatrix}
\end{equation}
<div id="org1633a04" class="figure">
<p><img src="figs/schematic_sensor_jacobian_forward_kinematics.png" alt="schematic_sensor_jacobian_forward_kinematics.png" />
</p>
<p><span class="figure-number">Figure 4: </span>Forward Kinematics - Interferometers</p>
</div>
<table id="org1bb9156" border="2" cellspacing="0" cellpadding="6" rules="groups" frame="hsides">
<caption class="t-above"><span class="table-number">Table 2:</span> Inverse of the sensor Jacobian \(\bm{J}_{s,111}^{-1}\)</caption>
<colgroup>
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
</colgroup>
<tbody>
<tr>
<td class="org-right">0.25</td>
<td class="org-right">0.5</td>
<td class="org-right">0.25</td>
</tr>
<tr>
<td class="org-right">7.14</td>
<td class="org-right">0.0</td>
<td class="org-right">-7.14</td>
</tr>
<tr>
<td class="org-right">-16.67</td>
<td class="org-right">33.33</td>
<td class="org-right">-16.67</td>
</tr>
</tbody>
</table>
</div>
</div>
<div id="outline-container-orgdcb38e9" class="outline-4">
<h4 id="orgdcb38e9"><span class="section-number-4">1.2.2.</span> Piezo - 111 Crystal</h4>
<div class="outline-text-4" id="text-1-2-2">
<p>
The location of the actuators with respect with the center of the 111 second crystal are shown in Figure <a href="#org67c7fa3">5</a>.
</p>
<div id="org67c7fa3" class="figure">
<p><img src="figs/actuator_jacobian_111_points.png" alt="actuator_jacobian_111_points.png" />
</p>
<p><span class="figure-number">Figure 5: </span>Location of actuators with respect to the center of the 111 second crystal (bottom view)</p>
</div>
<p>
Inverse Kinematics consist of deriving the axial (z) motion of the 3 actuators from the motion of the crystal&rsquo;s center.
</p>
\begin{equation}
\begin{bmatrix}
d_{u_r} \\ d_{u_h} \\ d_{d}
\end{bmatrix}
=
\bm{J}_{a,111}
\begin{bmatrix}
d_z \\ r_y \\ r_x
\end{bmatrix}
\end{equation}
<div id="org6dc1eec" class="figure">
<p><img src="figs/schematic_actuator_jacobian_inverse_kinematics.png" alt="schematic_actuator_jacobian_inverse_kinematics.png" />
</p>
<p><span class="figure-number">Figure 6: </span>Inverse Kinematics - Actuators</p>
</div>
<p>
Based on the geometry in Figure <a href="#org67c7fa3">5</a>, we obtain:
</p>
\begin{equation}
\bm{J}_{a,111}
=
\begin{bmatrix}
1 & 0.14 & -0.1525 \\
1 & 0.14 & 0.0675 \\
1 & -0.14 & -0.0425
\end{bmatrix}
\end{equation}
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak">%% Actuator Jacobian - 111 crystal</span>
J_a_111 = [1, 0.14, <span class="org-builtin">-</span>0.1525
1, 0.14, 0.0675
1, <span class="org-builtin">-</span>0.14, <span class="org-builtin">-</span>0.0425];
</pre>
</div>
<table id="org987e530" border="2" cellspacing="0" cellpadding="6" rules="groups" frame="hsides">
<caption class="t-above"><span class="table-number">Table 3:</span> Actuator Jacobian \(\bm{J}_{a,111}\)</caption>
<colgroup>
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
</colgroup>
<tbody>
<tr>
<td class="org-right">1.0</td>
<td class="org-right">0.14</td>
<td class="org-right">-0.1525</td>
</tr>
<tr>
<td class="org-right">1.0</td>
<td class="org-right">0.14</td>
<td class="org-right">0.0675</td>
</tr>
<tr>
<td class="org-right">1.0</td>
<td class="org-right">-0.14</td>
<td class="org-right">-0.0425</td>
</tr>
</tbody>
</table>
<p>
The forward Kinematics is solved by inverting the Jacobian matrix:
</p>
\begin{equation}
\begin{bmatrix}
d_z \\ r_y \\ r_x
\end{bmatrix}
=
\bm{J}_{a,111}^{-1}
\begin{bmatrix}
d_{u_r} \\ d_{u_h} \\ d_{d}
\end{bmatrix}
\end{equation}
<div id="orga69da79" class="figure">
<p><img src="figs/schematic_actuator_jacobian_forward_kinematics.png" alt="schematic_actuator_jacobian_forward_kinematics.png" />
</p>
<p><span class="figure-number">Figure 7: </span>Forward Kinematics - Actuators for 111 crystal</p>
</div>
<table id="orgb6769cb" border="2" cellspacing="0" cellpadding="6" rules="groups" frame="hsides">
<caption class="t-above"><span class="table-number">Table 4:</span> Inverse of the actuator Jacobian \(\bm{J}_{a,111}^{-1}\)</caption>
<colgroup>
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
</colgroup>
<tbody>
<tr>
<td class="org-right">0.0568</td>
<td class="org-right">0.4432</td>
<td class="org-right">0.5</td>
</tr>
<tr>
<td class="org-right">1.7857</td>
<td class="org-right">1.7857</td>
<td class="org-right">-3.5714</td>
</tr>
<tr>
<td class="org-right">-4.5455</td>
<td class="org-right">4.5455</td>
<td class="org-right">0.0</td>
</tr>
</tbody>
</table>
</div>
</div>
</div>
<div id="outline-container-org7beb5f6" class="outline-3">
<h3 id="org7beb5f6"><span class="section-number-3">1.3.</span> Save Kinematics</h3>
<div class="outline-text-3" id="text-1-3">
<div class="org-src-container">
<pre class="src src-matlab">save(<span class="org-string">'mat/dcm_kinematics.mat'</span>, <span class="org-string">'J_a_111'</span>, <span class="org-string">'J_s_111'</span>)
</pre>
</div>
</div>
</div>
</div>
<div id="outline-container-orgc562e49" class="outline-2">
<h2 id="orgc562e49"><span class="section-number-2">2.</span> Open Loop System Identification</h2>
<div class="outline-text-2" id="text-2">
<p>
<a id="orgdd4a98d"></a>
</p>
</div>
<div id="outline-container-org461a35a" class="outline-3">
<h3 id="org461a35a"><span class="section-number-3">2.1.</span> Identification</h3>
<div class="outline-text-3" id="text-2-1">
<p>
Let&rsquo;s considered the system \(\bm{G}(s)\) with:
</p>
<ul class="org-ul">
<li>3 inputs: force applied to the 3 fast jacks</li>
<li>3 outputs: measured displacement by the 3 interferometers pointing at the 111 second crystal</li>
</ul>
<p>
It is schematically shown in Figure <a href="#org7c50fa9">8</a>.
</p>
<div id="org7c50fa9" class="figure">
<p><img src="figs/schematic_system_inputs_outputs.png" alt="schematic_system_inputs_outputs.png" />
</p>
<p><span class="figure-number">Figure 8: </span>Dynamical system with inputs and outputs</p>
</div>
<p>
The system is identified from the Simscape model.
</p>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak">%% Input/Output definition</span>
clear io; io_i = 1;
<span class="org-matlab-cellbreak">%% Inputs</span>
<span class="org-comment-delimiter">% </span><span class="org-comment">Control Input {3x1} [N]</span>
io(io_i) = linio([mdl, <span class="org-string">'/control_system'</span>], 1, <span class="org-string">'openinput'</span>); io_i = io_i <span class="org-builtin">+</span> 1;
<span class="org-matlab-cellbreak">%% Outputs</span>
<span class="org-comment-delimiter">% </span><span class="org-comment">Interferometers {3x1} [m]</span>
io(io_i) = linio([mdl, <span class="org-string">'/DCM'</span>], 1, <span class="org-string">'openoutput'</span>); io_i = io_i <span class="org-builtin">+</span> 1;
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak">%% Extraction of the dynamics</span>
G = linearize(mdl, io);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">size(G)
</pre>
</div>
<pre class="example">
size(G)
State-space model with 3 outputs, 3 inputs, and 24 states.
</pre>
</div>
</div>
<div id="outline-container-org32530ab" class="outline-3">
<h3 id="org32530ab"><span class="section-number-3">2.2.</span> Plant in the frame of the fastjacks</h3>
<div class="outline-text-3" id="text-2-2">
<div class="org-src-container">
<pre class="src src-matlab">load(<span class="org-string">'mat/dcm_kinematics.mat'</span>);
</pre>
</div>
<p>
Using the forward and inverse kinematics, we can computed the dynamics from piezo forces to axial motion of the 3 fastjacks (see Figure <a href="#orga3837b0">9</a>).
</p>
<div id="orga3837b0" class="figure">
<p><img src="figs/schematic_jacobian_frame_fastjack.png" alt="schematic_jacobian_frame_fastjack.png" />
</p>
<p><span class="figure-number">Figure 9: </span>Use of Jacobian matrices to obtain the system in the frame of the fastjacks</p>
</div>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak">%% Compute the system in the frame of the fastjacks</span>
G_pz = J_a_111<span class="org-builtin">*</span>inv(J_s_111)<span class="org-builtin">*</span>G;
</pre>
</div>
<p>
The DC gain of the new system shows that the system is well decoupled at low frequency.
</p>
<div class="org-src-container">
<pre class="src src-matlab">dcgain(G_pz)
</pre>
</div>
<table id="org06bdfa0" border="2" cellspacing="0" cellpadding="6" rules="groups" frame="hsides">
<caption class="t-above"><span class="table-number">Table 5:</span> DC gain of the plant in the frame of the fast jacks \(\bm{G}_{\text{fj}}\)</caption>
<colgroup>
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
</colgroup>
<tbody>
<tr>
<td class="org-right">4.4407e-09</td>
<td class="org-right">2.7656e-12</td>
<td class="org-right">1.0132e-12</td>
</tr>
<tr>
<td class="org-right">2.7656e-12</td>
<td class="org-right">4.4407e-09</td>
<td class="org-right">1.0132e-12</td>
</tr>
<tr>
<td class="org-right">1.0109e-12</td>
<td class="org-right">1.0109e-12</td>
<td class="org-right">4.4424e-09</td>
</tr>
</tbody>
</table>
<p>
The bode plot of \(\bm{G}_{\text{fj}}(s)\) is shown in Figure <a href="#org4e62924">10</a>.
</p>
<div id="org4e62924" class="figure">
<p><img src="figs/bode_plot_plant_fj.png" alt="bode_plot_plant_fj.png" />
</p>
<p><span class="figure-number">Figure 10: </span>Bode plot of the diagonal and off-diagonal elements of the plant in the frame of the fast jacks</p>
</div>
<div class="important" id="org3ded063">
<p>
Computing the system in the frame of the fastjack gives good decoupling at low frequency (until the first resonance of the system).
</p>
</div>
</div>
</div>
<div id="outline-container-org831ac4a" class="outline-3">
<h3 id="org831ac4a"><span class="section-number-3">2.3.</span> Plant in the frame of the crystal</h3>
<div class="outline-text-3" id="text-2-3">
<div id="org3adfc9a" class="figure">
<p><img src="figs/schematic_jacobian_frame_crystal.png" alt="schematic_jacobian_frame_crystal.png" />
</p>
<p><span class="figure-number">Figure 11: </span>Use of Jacobian matrices to obtain the system in the frame of the crystal</p>
</div>
<div class="org-src-container">
<pre class="src src-matlab">G_mr = inv(J_s_111)<span class="org-builtin">*</span>G<span class="org-builtin">*</span>inv(J_a_111<span class="org-builtin">'</span>);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">dcgain(G_mr)
</pre>
</div>
<table border="2" cellspacing="0" cellpadding="6" rules="groups" frame="hsides">
<colgroup>
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
</colgroup>
<tbody>
<tr>
<td class="org-right">1.9978e-09</td>
<td class="org-right">3.9657e-09</td>
<td class="org-right">7.7944e-09</td>
</tr>
<tr>
<td class="org-right">3.9656e-09</td>
<td class="org-right">8.4979e-08</td>
<td class="org-right">-1.5135e-17</td>
</tr>
<tr>
<td class="org-right">7.7944e-09</td>
<td class="org-right">-3.9252e-17</td>
<td class="org-right">1.834e-07</td>
</tr>
</tbody>
</table>
<p>
This results in a coupled system.
The main reason is that, as we map forces to the center of the 111 crystal and not at the center of mass/stiffness of the moving part, vertical forces will induce rotation and torques will induce vertical motion.
</p>
</div>
</div>
</div>
<div id="outline-container-org6a67c7c" class="outline-2">
<h2 id="org6a67c7c"><span class="section-number-2">3.</span> Active Damping Plant (Strain gauges)</h2>
<div class="outline-text-2" id="text-3">
<p>
<a id="orgdeb64e7"></a>
</p>
<p>
In this section, we wish to see whether if strain gauges fixed to the piezoelectric actuator can be used for active damping.
</p>
</div>
<div id="outline-container-org59bf8d2" class="outline-3">
<h3 id="org59bf8d2"><span class="section-number-3">3.1.</span> Identification</h3>
<div class="outline-text-3" id="text-3-1">
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak">%% Input/Output definition</span>
clear io; io_i = 1;
<span class="org-matlab-cellbreak">%% Inputs</span>
<span class="org-comment-delimiter">% </span><span class="org-comment">Control Input {3x1} [N]</span>
io(io_i) = linio([mdl, <span class="org-string">'/u'</span>], 1, <span class="org-string">'openinput'</span>); io_i = io_i <span class="org-builtin">+</span> 1;
<span class="org-comment-delimiter">% </span><span class="org-comment">% Stepper Displacement {3x1} [m]</span>
<span class="org-comment-delimiter">% </span><span class="org-comment">io(io_i) = linio([mdl, '/d'], 1, 'openinput'); io_i = io_i + 1;</span>
<span class="org-matlab-cellbreak">%% Outputs</span>
<span class="org-comment-delimiter">% </span><span class="org-comment">Strain Gauges {3x1} [m]</span>
io(io_i) = linio([mdl, <span class="org-string">'/sg'</span>], 1, <span class="org-string">'openoutput'</span>); io_i = io_i <span class="org-builtin">+</span> 1;
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak">%% Extraction of the dynamics</span>
G_sg = linearize(mdl, io);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">dcgain(G_sg)
</pre>
</div>
<table border="2" cellspacing="0" cellpadding="6" rules="groups" frame="hsides">
<colgroup>
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
</colgroup>
<tbody>
<tr>
<td class="org-right">-1.4113e-13</td>
<td class="org-right">1.0339e-13</td>
<td class="org-right">3.774e-14</td>
</tr>
<tr>
<td class="org-right">1.0339e-13</td>
<td class="org-right">-1.4113e-13</td>
<td class="org-right">3.774e-14</td>
</tr>
<tr>
<td class="org-right">3.7792e-14</td>
<td class="org-right">3.7792e-14</td>
<td class="org-right">-7.5585e-14</td>
</tr>
</tbody>
</table>
</div>
</div>
</div>
<div id="outline-container-org98018d6" class="outline-2">
<h2 id="org98018d6"><span class="section-number-2">4.</span> Active Damping Plant (Force Sensors)</h2>
<div class="outline-text-2" id="text-4">
<p>
<a id="org624796e"></a>
</p>
<p>
Force sensors are added above the piezoelectric actuators.
They can consists of a simple piezoelectric ceramic stack.
See for instance <a href="fleming10_integ_strain_force_feedb_high">fleming10_integ_strain_force_feedb_high</a>.
</p>
</div>
<div id="outline-container-orgf3d05f6" class="outline-3">
<h3 id="orgf3d05f6"><span class="section-number-3">4.1.</span> Identification</h3>
<div class="outline-text-3" id="text-4-1">
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak">%% Input/Output definition</span>
clear io; io_i = 1;
<span class="org-matlab-cellbreak">%% Inputs</span>
<span class="org-comment-delimiter">% </span><span class="org-comment">Control Input {3x1} [N]</span>
io(io_i) = linio([mdl, <span class="org-string">'/control_system'</span>], 1, <span class="org-string">'openinput'</span>); io_i = io_i <span class="org-builtin">+</span> 1;
<span class="org-matlab-cellbreak">%% Outputs</span>
<span class="org-comment-delimiter">% </span><span class="org-comment">Force Sensor {3x1} [m]</span>
io(io_i) = linio([mdl, <span class="org-string">'/DCM'</span>], 3, <span class="org-string">'openoutput'</span>); io_i = io_i <span class="org-builtin">+</span> 1;
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak">%% Extraction of the dynamics</span>
G_fs = linearize(mdl, io);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">dcgain(G_fs)
</pre>
</div>
<table border="2" cellspacing="0" cellpadding="6" rules="groups" frame="hsides">
<colgroup>
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
</colgroup>
<tbody>
<tr>
<td class="org-right">-1.4113e-13</td>
<td class="org-right">1.0339e-13</td>
<td class="org-right">3.774e-14</td>
</tr>
<tr>
<td class="org-right">1.0339e-13</td>
<td class="org-right">-1.4113e-13</td>
<td class="org-right">3.774e-14</td>
</tr>
<tr>
<td class="org-right">3.7792e-14</td>
<td class="org-right">3.7792e-14</td>
<td class="org-right">-7.5585e-14</td>
</tr>
</tbody>
</table>
<div id="org2468af2" class="figure">
<p><img src="figs/iff_plant_bode_plot.png" alt="iff_plant_bode_plot.png" />
</p>
<p><span class="figure-number">Figure 12: </span>Bode plot of IFF Plant</p>
</div>
</div>
</div>
<div id="outline-container-org2c7747a" class="outline-3">
<h3 id="org2c7747a"><span class="section-number-3">4.2.</span> Controller - Root Locus</h3>
<div class="outline-text-3" id="text-4-2">
<div class="org-src-container">
<pre class="src src-matlab">Kiff_g1 = eye(3)<span class="org-builtin">*</span>1<span class="org-builtin">/</span>(1 <span class="org-builtin">+</span> s<span class="org-builtin">/</span>2<span class="org-builtin">/</span><span class="org-matlab-math">pi</span><span class="org-builtin">/</span>20);
</pre>
</div>
<div id="orgac1f06c" class="figure">
<p><img src="figs/iff_root_locus.png" alt="iff_root_locus.png" />
</p>
<p><span class="figure-number">Figure 13: </span>Root Locus plot for the IFF Control strategy</p>
</div>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak">%% Integral Force Feedback Controller</span>
Kiff = g<span class="org-builtin">*</span>Kiff_g1;
</pre>
</div>
</div>
</div>
<div id="outline-container-org44eaa41" class="outline-3">
<h3 id="org44eaa41"><span class="section-number-3">4.3.</span> Damped Plant</h3>
<div class="outline-text-3" id="text-4-3">
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak">%% Input/Output definition</span>
clear io; io_i = 1;
<span class="org-matlab-cellbreak">%% Inputs</span>
<span class="org-comment-delimiter">% </span><span class="org-comment">Control Input {3x1} [N]</span>
io(io_i) = linio([mdl, <span class="org-string">'/control_system'</span>], 1, <span class="org-string">'input'</span>); io_i = io_i <span class="org-builtin">+</span> 1;
<span class="org-matlab-cellbreak">%% Outputs</span>
<span class="org-comment-delimiter">% </span><span class="org-comment">Force Sensor {3x1} [m]</span>
io(io_i) = linio([mdl, <span class="org-string">'/DCM'</span>], 1, <span class="org-string">'openoutput'</span>); io_i = io_i <span class="org-builtin">+</span> 1;
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak">%% DCM Kinematics</span>
load(<span class="org-string">'mat/dcm_kinematics.mat'</span>);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak">%% Identification of the Open Loop plant</span>
controller.type = 0; <span class="org-comment-delimiter">% </span><span class="org-comment">Open Loop</span>
G_ol = J_a_111<span class="org-builtin">*</span>inv(J_s_111)<span class="org-builtin">*</span>linearize(mdl, io);
G_ol.InputName = {<span class="org-string">'u_ur'</span>, <span class="org-string">'u_uh'</span>, <span class="org-string">'u_d'</span>};
G_ol.OutputName = {<span class="org-string">'d_ur'</span>, <span class="org-string">'d_uh'</span>, <span class="org-string">'d_d'</span>};
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak">%% Identification of the damped plant with IFF</span>
controller.type = 1; <span class="org-comment-delimiter">% </span><span class="org-comment">IFF</span>
G_dp = J_a_111<span class="org-builtin">*</span>inv(J_s_111)<span class="org-builtin">*</span>linearize(mdl, io);
G_dp.InputName = {<span class="org-string">'u_ur'</span>, <span class="org-string">'u_uh'</span>, <span class="org-string">'u_d'</span>};
G_dp.OutputName = {<span class="org-string">'d_ur'</span>, <span class="org-string">'d_uh'</span>, <span class="org-string">'d_d'</span>};
</pre>
</div>
<div id="orge31be94" class="figure">
<p><img src="figs/comp_damped_undamped_plant_iff_bode_plot.png" alt="comp_damped_undamped_plant_iff_bode_plot.png" />
</p>
<p><span class="figure-number">Figure 14: </span>Bode plot of both the open-loop plant and the damped plant using IFF</p>
</div>
<div class="important" id="org4a8fc3e">
<p>
The Integral Force Feedback control strategy is very effective in damping the suspension modes of the DCM.
</p>
</div>
</div>
</div>
<div id="outline-container-orgd9ea17f" class="outline-3">
<h3 id="orgd9ea17f"><span class="section-number-3">4.4.</span> Save</h3>
<div class="outline-text-3" id="text-4-4">
<div class="org-src-container">
<pre class="src src-matlab">save(<span class="org-string">'mat/Kiff.mat'</span>, <span class="org-string">'Kiff'</span>);
</pre>
</div>
</div>
</div>
</div>
<div id="outline-container-org93a00ff" class="outline-2">
<h2 id="org93a00ff"><span class="section-number-2">5.</span> HAC-LAC (IFF) architecture</h2>
<div class="outline-text-2" id="text-5">
<p>
<a id="orga8f0b23"></a>
</p>
</div>
</div>
</div>
<div id="postamble" class="status">
<p class="author">Author: Dehaeze Thomas</p>
<p class="date">Created: 2021-11-30 mar. 11:26</p>
</div>
</body>
</html>