test-bench-nano-hexapod/test-bench-nano-hexapod.html

1038 lines
45 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>
<!-- 2021-06-14 lun. 18:07 -->
<meta http-equiv="Content-Type" content="text/html;charset=utf-8" />
<title>Nano-Hexapod - Test Bench</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">
<h1 class="title">Nano-Hexapod - Test Bench</h1>
<div id="table-of-contents">
<h2>Table of Contents</h2>
<div id="text-table-of-contents">
<ul>
<li><a href="#org4f28452">1. Encoders fixed to the Struts</a>
<ul>
<li><a href="#orgdb58b6b">1.1. Introduction</a></li>
<li><a href="#orga23f4a3">1.2. Identification of the dynamics</a>
<ul>
<li><a href="#org463f1c5">1.2.1. Load Data</a></li>
<li><a href="#orga89822b">1.2.2. Spectral Analysis - Setup</a></li>
<li><a href="#org2ea8050">1.2.3. DVF Plant</a></li>
<li><a href="#org3af4d82">1.2.4. IFF Plant</a></li>
</ul>
</li>
<li><a href="#org0d5bead">1.3. Comparison with the Simscape Model</a>
<ul>
<li><a href="#org52ed397">1.3.1. Dynamics from Actuator to Force Sensors</a></li>
<li><a href="#org6bb92e5">1.3.2. Dynamics from Actuator to Encoder</a></li>
</ul>
</li>
<li><a href="#org9537bdd">1.4. Integral Force Feedback</a>
<ul>
<li><a href="#org1092513">1.4.1. Root Locus and Decentralized Loop gain</a></li>
<li><a href="#orgb15799f">1.4.2. Multiple Gains - Simulation</a></li>
<li><a href="#orgfc28d74">1.4.3. Experimental Results - Gains</a>
<ul>
<li><a href="#orgc87e132">1.4.3.1. Load Data</a></li>
<li><a href="#org082cedd">1.4.3.2. Spectral Analysis - Setup</a></li>
<li><a href="#orgf617003">1.4.3.3. DVF Plant</a></li>
<li><a href="#orgfaa6821">1.4.3.4. Experimental Results - Comparison of the un-damped and fully damped system</a></li>
</ul>
</li>
<li><a href="#orgc0e0293">1.4.4. Experimental Results - Damped Plant with Optimal gain</a>
<ul>
<li><a href="#org04a0c15">1.4.4.1. Load Data</a></li>
<li><a href="#org288970e">1.4.4.2. Spectral Analysis - Setup</a></li>
<li><a href="#orgbe5d7c4">1.4.4.3. DVF Plant</a></li>
</ul>
</li>
</ul>
</li>
<li><a href="#org4d2a6a9">1.5. Modal Analysis</a>
<ul>
<li><a href="#org76f1cc6">1.5.1. Effectiveness of the IFF Strategy - Compliance</a></li>
<li><a href="#org1c35d39">1.5.2. Comparison with the Simscape Model</a></li>
<li><a href="#org2fb301f">1.5.3. Obtained Mode Shapes</a></li>
</ul>
</li>
</ul>
</li>
<li><a href="#orgfd9b3f1">2. Encoders fixed to the plates</a></li>
</ul>
</div>
</div>
<hr>
<p>This report is also available as a <a href="./test-bench-nano-hexapod.pdf">pdf</a>.</p>
<hr>
<p>
This document is dedicated to the experimental study of the nano-hexapod shown in Figure <a href="#orgf67b6ef">1</a>.
</p>
<div id="orgf67b6ef" class="figure">
<p><img src="figs/IMG_20210608_152917.jpg" alt="IMG_20210608_152917.jpg" />
</p>
<p><span class="figure-number">Figure 1: </span>Nano-Hexapod</p>
</div>
<div class="note" id="org75105c3">
<p>
Here are the documentation of the equipment used for this test bench (lots of them are shwon in Figure <a href="#org800f7b8">2</a>):
</p>
<ul class="org-ul">
<li>Voltage Amplifier: PiezoDrive <a href="doc/PD200-V7-R1.pdf">PD200</a></li>
<li>Amplified Piezoelectric Actuator: Cedrat <a href="doc/APA300ML.pdf">APA300ML</a></li>
<li>DAC/ADC: Speedgoat <a href="doc/IO131-OEM-Datasheet.pdf">IO313</a></li>
<li>Encoder: Renishaw <a href="doc/L-9517-9678-05-A_Data_sheet_VIONiC_series_en.pdf">Vionic</a> and used <a href="doc/L-9517-9862-01-C_Data_sheet_RKLC_EN.pdf">Ruler</a></li>
<li>Interferometers: Attocube</li>
</ul>
</div>
<div id="org800f7b8" class="figure">
<p><img src="figs/IMG_20210608_154722.jpg" alt="IMG_20210608_154722.jpg" />
</p>
<p><span class="figure-number">Figure 2: </span>Nano-Hexapod and the control electronics</p>
</div>
<p>
In Figure <a href="#orgc1fc8a4">3</a> is shown a block diagram of the experimental setup.
When possible, the notations are consistent with this diagram and summarized in Table <a href="#org211ae1e">1</a>.
</p>
<div id="orgc1fc8a4" class="figure">
<p><img src="figs/nano_hexapod_signals.png" alt="nano_hexapod_signals.png" />
</p>
<p><span class="figure-number">Figure 3: </span>Block diagram of the system with named signals</p>
</div>
<table id="org211ae1e" border="2" cellspacing="0" cellpadding="6" rules="groups" frame="hsides">
<caption class="t-above"><span class="table-number">Table 1:</span> List of signals</caption>
<colgroup>
<col class="org-left" />
<col class="org-left" />
<col class="org-left" />
<col class="org-left" />
<col class="org-left" />
</colgroup>
<thead>
<tr>
<th scope="col" class="org-left">&#xa0;</th>
<th scope="col" class="org-left"><b>Unit</b></th>
<th scope="col" class="org-left"><b>Matlab</b></th>
<th scope="col" class="org-left"><b>Vector</b></th>
<th scope="col" class="org-left"><b>Elements</b></th>
</tr>
</thead>
<tbody>
<tr>
<td class="org-left">Control Input (wanted DAC voltage)</td>
<td class="org-left"><code>[V]</code></td>
<td class="org-left"><code>u</code></td>
<td class="org-left">\(\bm{u}\)</td>
<td class="org-left">\(u_i\)</td>
</tr>
<tr>
<td class="org-left">DAC Output Voltage</td>
<td class="org-left"><code>[V]</code></td>
<td class="org-left"><code>u</code></td>
<td class="org-left">\(\tilde{\bm{u}}\)</td>
<td class="org-left">\(\tilde{u}_i\)</td>
</tr>
<tr>
<td class="org-left">PD200 Output Voltage</td>
<td class="org-left"><code>[V]</code></td>
<td class="org-left"><code>ua</code></td>
<td class="org-left">\(\bm{u}_a\)</td>
<td class="org-left">\(u_{a,i}\)</td>
</tr>
<tr>
<td class="org-left">Actuator applied force</td>
<td class="org-left"><code>[N]</code></td>
<td class="org-left"><code>tau</code></td>
<td class="org-left">\(\bm{\tau}\)</td>
<td class="org-left">\(\tau_i\)</td>
</tr>
</tbody>
<tbody>
<tr>
<td class="org-left">Strut motion</td>
<td class="org-left"><code>[m]</code></td>
<td class="org-left"><code>dL</code></td>
<td class="org-left">\(d\bm{\mathcal{L}}\)</td>
<td class="org-left">\(d\mathcal{L}_i\)</td>
</tr>
<tr>
<td class="org-left">Encoder measured displacement</td>
<td class="org-left"><code>[m]</code></td>
<td class="org-left"><code>dLm</code></td>
<td class="org-left">\(d\bm{\mathcal{L}}_m\)</td>
<td class="org-left">\(d\mathcal{L}_{m,i}\)</td>
</tr>
</tbody>
<tbody>
<tr>
<td class="org-left">Force Sensor strain</td>
<td class="org-left"><code>[m]</code></td>
<td class="org-left"><code>epsilon</code></td>
<td class="org-left">\(\bm{\epsilon}\)</td>
<td class="org-left">\(\epsilon_i\)</td>
</tr>
<tr>
<td class="org-left">Force Sensor Generated Voltage</td>
<td class="org-left"><code>[V]</code></td>
<td class="org-left"><code>taum</code></td>
<td class="org-left">\(\tilde{\bm{\tau}}_m\)</td>
<td class="org-left">\(\tilde{\tau}_{m,i}\)</td>
</tr>
<tr>
<td class="org-left">Measured Generated Voltage</td>
<td class="org-left"><code>[V]</code></td>
<td class="org-left"><code>taum</code></td>
<td class="org-left">\(\bm{\tau}_m\)</td>
<td class="org-left">\(\tau_{m,i}\)</td>
</tr>
</tbody>
<tbody>
<tr>
<td class="org-left">Motion of the top platform</td>
<td class="org-left"><code>[m,rad]</code></td>
<td class="org-left"><code>dX</code></td>
<td class="org-left">\(d\bm{\mathcal{X}}\)</td>
<td class="org-left">\(d\mathcal{X}_i\)</td>
</tr>
<tr>
<td class="org-left">Metrology measured displacement</td>
<td class="org-left"><code>[m,rad]</code></td>
<td class="org-left"><code>dXm</code></td>
<td class="org-left">\(d\bm{\mathcal{X}}_m\)</td>
<td class="org-left">\(d\mathcal{X}_{m,i}\)</td>
</tr>
</tbody>
</table>
<p>
This document is divided in the following sections:
</p>
<ul class="org-ul">
<li>Section <a href="#org7e4eeef">1</a>: the encoders are fixed to the struts</li>
<li>Section <a href="#org6f5eb76">2</a>: the encoders are fixed to the plates</li>
</ul>
<div id="outline-container-org4f28452" class="outline-2">
<h2 id="org4f28452"><span class="section-number-2">1</span> Encoders fixed to the Struts</h2>
<div class="outline-text-2" id="text-1">
<p>
<a id="org7e4eeef"></a>
</p>
</div>
<div id="outline-container-orgdb58b6b" class="outline-3">
<h3 id="orgdb58b6b"><span class="section-number-3">1.1</span> Introduction</h3>
<div class="outline-text-3" id="text-1-1">
<p>
In this section, the encoders are fixed to the struts.
</p>
<p>
It is divided in the following sections:
</p>
<ul class="org-ul">
<li>Section <a href="#org9c2cb86">1.2</a>: the transfer function matrix from the actuators to the force sensors and to the encoders is experimentally identified.</li>
<li>Section <a href="#org860409f">1.3</a>: the obtained FRF matrix is compared with the dynamics of the simscape model</li>
<li>Section <a href="#org941b355">1.4</a>: decentralized Integral Force Feedback (IFF) is applied and its performances are evaluated.</li>
<li>Section <a href="#orgb37d2f8">1.5</a>: a modal analysis of the nano-hexapod is performed</li>
</ul>
</div>
</div>
<div id="outline-container-orga23f4a3" class="outline-3">
<h3 id="orga23f4a3"><span class="section-number-3">1.2</span> Identification of the dynamics</h3>
<div class="outline-text-3" id="text-1-2">
<p>
<a id="org9c2cb86"></a>
</p>
</div>
<div id="outline-container-org463f1c5" class="outline-4">
<h4 id="org463f1c5"><span class="section-number-4">1.2.1</span> Load Data</h4>
<div class="outline-text-4" id="text-1-2-1">
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Load Identification Data</span></span>
meas_data_lf = {};
<span class="org-keyword">for</span> <span class="org-variable-name"><span class="org-constant">i</span></span> = <span class="org-constant">1:6</span>
meas_data_lf(<span class="org-constant">i</span>) = {load(sprintf(<span class="org-string">'mat/frf_data_exc_strut_%i_noise_lf.mat'</span>, <span class="org-constant">i</span>), <span class="org-string">'t'</span>, <span class="org-string">'Va'</span>, <span class="org-string">'Vs'</span>, <span class="org-string">'de'</span>)};
meas_data_hf(<span class="org-constant">i</span>) = {load(sprintf(<span class="org-string">'mat/frf_data_exc_strut_%i_noise_hf.mat'</span>, <span class="org-constant">i</span>), <span class="org-string">'t'</span>, <span class="org-string">'Va'</span>, <span class="org-string">'Vs'</span>, <span class="org-string">'de'</span>)};
<span class="org-keyword">end</span>
</pre>
</div>
</div>
</div>
<div id="outline-container-orga89822b" class="outline-4">
<h4 id="orga89822b"><span class="section-number-4">1.2.2</span> Spectral Analysis - Setup</h4>
<div class="outline-text-4" id="text-1-2-2">
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Setup useful variables</span></span>
<span class="org-comment">% Sampling Time [s]</span>
Ts = (meas_data_lf{1}.t(end) <span class="org-type">-</span> (meas_data_lf{1}.t(1)))<span class="org-type">/</span>(length(meas_data_lf{1}.t)<span class="org-type">-</span>1);
<span class="org-comment">% Sampling Frequency [Hz]</span>
Fs = 1<span class="org-type">/</span>Ts;
<span class="org-comment">% Hannning Windows</span>
win = hanning(ceil(1<span class="org-type">*</span>Fs));
<span class="org-comment">% And we get the frequency vector</span>
[<span class="org-type">~</span>, f] = tfestimate(meas_data_lf{1}.Va, meas_data_lf{1}.de, win, [], [], 1<span class="org-type">/</span>Ts);
i_lf = f <span class="org-type">&lt;</span> 250; <span class="org-comment">% Points for low frequency excitation</span>
i_hf = f <span class="org-type">&gt;</span> 250; <span class="org-comment">% Points for high frequency excitation</span>
</pre>
</div>
</div>
</div>
<div id="outline-container-org2ea8050" class="outline-4">
<h4 id="org2ea8050"><span class="section-number-4">1.2.3</span> DVF Plant</h4>
<div class="outline-text-4" id="text-1-2-3">
<p>
First, let&rsquo;s compute the coherence from the excitation voltage and the displacement as measured by the encoders (Figure <a href="#org83cc12f">4</a>).
</p>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Coherence</span></span>
coh_dvf_lf = zeros(length(f), 6, 6);
coh_dvf_hf = zeros(length(f), 6, 6);
<span class="org-keyword">for</span> <span class="org-variable-name"><span class="org-constant">i</span></span> = <span class="org-constant">1:6</span>
coh_dvf_lf(<span class="org-type">:</span>, <span class="org-type">:</span>, <span class="org-constant">i</span>) = mscohere(meas_data_lf{<span class="org-constant">i</span>}.Va, meas_data_lf{<span class="org-constant">i</span>}.de, win, [], [], 1<span class="org-type">/</span>Ts);
coh_dvf_hf(<span class="org-type">:</span>, <span class="org-type">:</span>, <span class="org-constant">i</span>) = mscohere(meas_data_hf{<span class="org-constant">i</span>}.Va, meas_data_hf{<span class="org-constant">i</span>}.de, win, [], [], 1<span class="org-type">/</span>Ts);
<span class="org-keyword">end</span>
</pre>
</div>
<div id="org83cc12f" class="figure">
<p><img src="figs/enc_struts_dvf_coh.png" alt="enc_struts_dvf_coh.png" />
</p>
<p><span class="figure-number">Figure 4: </span>Obtained coherence for the DVF plant</p>
</div>
<p>
Then the 6x6 transfer function matrix is estimated (Figure <a href="#org18fb1d6">5</a>).
</p>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% DVF Plant (transfer function from u to dLm)</span></span>
G_dvf_lf = zeros(length(f), 6, 6);
G_dvf_hf = zeros(length(f), 6, 6);
<span class="org-keyword">for</span> <span class="org-variable-name"><span class="org-constant">i</span></span> = <span class="org-constant">1:6</span>
G_dvf_lf(<span class="org-type">:</span>, <span class="org-type">:</span>, <span class="org-constant">i</span>) = tfestimate(meas_data_lf{<span class="org-constant">i</span>}.Va, meas_data_lf{<span class="org-constant">i</span>}.de, win, [], [], 1<span class="org-type">/</span>Ts);
G_dvf_hf(<span class="org-type">:</span>, <span class="org-type">:</span>, <span class="org-constant">i</span>) = tfestimate(meas_data_hf{<span class="org-constant">i</span>}.Va, meas_data_hf{<span class="org-constant">i</span>}.de, win, [], [], 1<span class="org-type">/</span>Ts);
<span class="org-keyword">end</span>
</pre>
</div>
<div id="org18fb1d6" class="figure">
<p><img src="figs/enc_struts_dvf_frf.png" alt="enc_struts_dvf_frf.png" />
</p>
<p><span class="figure-number">Figure 5: </span>Measured FRF for the DVF plant</p>
</div>
</div>
</div>
<div id="outline-container-org3af4d82" class="outline-4">
<h4 id="org3af4d82"><span class="section-number-4">1.2.4</span> IFF Plant</h4>
<div class="outline-text-4" id="text-1-2-4">
<p>
First, let&rsquo;s compute the coherence from the excitation voltage and the displacement as measured by the encoders (Figure <a href="#org01dd40a">6</a>).
</p>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Coherence for the IFF plant</span></span>
coh_iff_lf = zeros(length(f), 6, 6);
coh_iff_hf = zeros(length(f), 6, 6);
<span class="org-keyword">for</span> <span class="org-variable-name"><span class="org-constant">i</span></span> = <span class="org-constant">1:6</span>
coh_iff_lf(<span class="org-type">:</span>, <span class="org-type">:</span>, <span class="org-constant">i</span>) = mscohere(meas_data_lf{<span class="org-constant">i</span>}.Va, meas_data_lf{<span class="org-constant">i</span>}.Vs, win, [], [], 1<span class="org-type">/</span>Ts);
coh_iff_hf(<span class="org-type">:</span>, <span class="org-type">:</span>, <span class="org-constant">i</span>) = mscohere(meas_data_hf{<span class="org-constant">i</span>}.Va, meas_data_hf{<span class="org-constant">i</span>}.Vs, win, [], [], 1<span class="org-type">/</span>Ts);
<span class="org-keyword">end</span>
</pre>
</div>
<div id="org01dd40a" class="figure">
<p><img src="figs/enc_struts_iff_coh.png" alt="enc_struts_iff_coh.png" />
</p>
<p><span class="figure-number">Figure 6: </span>Obtained coherence for the IFF plant</p>
</div>
<p>
Then the 6x6 transfer function matrix is estimated (Figure <a href="#org671b27d">7</a>).
</p>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% IFF Plant</span></span>
G_iff_lf = zeros(length(f), 6, 6);
G_iff_hf = zeros(length(f), 6, 6);
<span class="org-keyword">for</span> <span class="org-variable-name"><span class="org-constant">i</span></span> = <span class="org-constant">1:6</span>
G_iff_lf(<span class="org-type">:</span>, <span class="org-type">:</span>, <span class="org-constant">i</span>) = tfestimate(meas_data_lf{<span class="org-constant">i</span>}.Va, meas_data_lf{<span class="org-constant">i</span>}.Vs, win, [], [], 1<span class="org-type">/</span>Ts);
G_iff_hf(<span class="org-type">:</span>, <span class="org-type">:</span>, <span class="org-constant">i</span>) = tfestimate(meas_data_hf{<span class="org-constant">i</span>}.Va, meas_data_hf{<span class="org-constant">i</span>}.Vs, win, [], [], 1<span class="org-type">/</span>Ts);
<span class="org-keyword">end</span>
</pre>
</div>
<div id="org671b27d" class="figure">
<p><img src="figs/enc_struts_iff_frf.png" alt="enc_struts_iff_frf.png" />
</p>
<p><span class="figure-number">Figure 7: </span>Measured FRF for the IFF plant</p>
</div>
</div>
</div>
</div>
<div id="outline-container-org0d5bead" class="outline-3">
<h3 id="org0d5bead"><span class="section-number-3">1.3</span> Comparison with the Simscape Model</h3>
<div class="outline-text-3" id="text-1-3">
<p>
<a id="org860409f"></a>
</p>
<p>
In this section, the measured dynamics is compared with the dynamics estimated from the Simscape model.
</p>
</div>
<div id="outline-container-org52ed397" class="outline-4">
<h4 id="org52ed397"><span class="section-number-4">1.3.1</span> Dynamics from Actuator to Force Sensors</h4>
<div class="outline-text-4" id="text-1-3-1">
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Initialize Nano-Hexapod</span></span>
n_hexapod = initializeNanoHexapodFinal(<span class="org-string">'flex_bot_type'</span>, <span class="org-string">'4dof'</span>, ...
<span class="org-string">'flex_top_type'</span>, <span class="org-string">'4dof'</span>, ...
<span class="org-string">'motion_sensor_type'</span>, <span class="org-string">'struts'</span>, ...
<span class="org-string">'actuator_type'</span>, <span class="org-string">'2dof'</span>);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Identify the IFF Plant (transfer function from u to taum)</span></span>
clear io; io_i = 1;
io(io_i) = linio([mdl, <span class="org-string">'/F'</span>], 1, <span class="org-string">'openinput'</span>); io_i = io_i <span class="org-type">+</span> 1; <span class="org-comment">% Actuator Inputs</span>
io(io_i) = linio([mdl, <span class="org-string">'/Fm'</span>], 1, <span class="org-string">'openoutput'</span>); io_i = io_i <span class="org-type">+</span> 1; <span class="org-comment">% Force Sensors</span>
Giff = exp(<span class="org-type">-</span>s<span class="org-type">*</span>Ts)<span class="org-type">*</span>linearize(mdl, io, 0.0, options);
</pre>
</div>
<div id="orgfe01cea" class="figure">
<p><img src="figs/enc_struts_iff_comp_simscape.png" alt="enc_struts_iff_comp_simscape.png" />
</p>
<p><span class="figure-number">Figure 8: </span>Diagonal elements of the IFF Plant</p>
</div>
<div id="org37f6405" class="figure">
<p><img src="figs/enc_struts_iff_comp_offdiag_simscape.png" alt="enc_struts_iff_comp_offdiag_simscape.png" />
</p>
<p><span class="figure-number">Figure 9: </span>Off diagonal elements of the IFF Plant</p>
</div>
</div>
</div>
<div id="outline-container-org6bb92e5" class="outline-4">
<h4 id="org6bb92e5"><span class="section-number-4">1.3.2</span> Dynamics from Actuator to Encoder</h4>
<div class="outline-text-4" id="text-1-3-2">
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Initialization of the Nano-Hexapod</span></span>
n_hexapod = initializeNanoHexapodFinal(<span class="org-string">'flex_bot_type'</span>, <span class="org-string">'4dof'</span>, ...
<span class="org-string">'flex_top_type'</span>, <span class="org-string">'4dof'</span>, ...
<span class="org-string">'motion_sensor_type'</span>, <span class="org-string">'struts'</span>, ...
<span class="org-string">'actuator_type'</span>, <span class="org-string">'2dof'</span>);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Identify the DVF Plant (transfer function from u to dLm)</span></span>
clear io; io_i = 1;
io(io_i) = linio([mdl, <span class="org-string">'/F'</span>], 1, <span class="org-string">'openinput'</span>); io_i = io_i <span class="org-type">+</span> 1; <span class="org-comment">% Actuator Inputs</span>
io(io_i) = linio([mdl, <span class="org-string">'/D'</span>], 1, <span class="org-string">'openoutput'</span>); io_i = io_i <span class="org-type">+</span> 1; <span class="org-comment">% Encoders</span>
Gdvf = exp(<span class="org-type">-</span>s<span class="org-type">*</span>Ts)<span class="org-type">*</span>linearize(mdl, io, 0.0, options);
</pre>
</div>
<div id="org27467a4" class="figure">
<p><img src="figs/enc_struts_dvf_comp_simscape.png" alt="enc_struts_dvf_comp_simscape.png" />
</p>
<p><span class="figure-number">Figure 10: </span>Diagonal elements of the DVF Plant</p>
</div>
<div id="orgf864568" class="figure">
<p><img src="figs/enc_struts_dvf_comp_offdiag_simscape.png" alt="enc_struts_dvf_comp_offdiag_simscape.png" />
</p>
<p><span class="figure-number">Figure 11: </span>Off diagonal elements of the DVF Plant</p>
</div>
</div>
</div>
</div>
<div id="outline-container-org9537bdd" class="outline-3">
<h3 id="org9537bdd"><span class="section-number-3">1.4</span> Integral Force Feedback</h3>
<div class="outline-text-3" id="text-1-4">
<p>
<a id="org941b355"></a>
</p>
</div>
<div id="outline-container-org1092513" class="outline-4">
<h4 id="org1092513"><span class="section-number-4">1.4.1</span> Root Locus and Decentralized Loop gain</h4>
<div class="outline-text-4" id="text-1-4-1">
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% IFF Controller</span></span>
Kiff_g1 = (1<span class="org-type">/</span>(s <span class="org-type">+</span> 2<span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">*</span>40))<span class="org-type">*</span>...<span class="org-comment"> % Low pass filter (provides integral action above 40Hz)</span>
(s<span class="org-type">/</span>(s <span class="org-type">+</span> 2<span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">*</span>30))<span class="org-type">*</span>...<span class="org-comment"> % High pass filter to limit low frequency gain</span>
(1<span class="org-type">/</span>(1 <span class="org-type">+</span> s<span class="org-type">/</span>2<span class="org-type">/</span><span class="org-constant">pi</span><span class="org-type">/</span>500))<span class="org-type">*</span>...<span class="org-comment"> % Low pass filter to be more robust to high frequency resonances</span>
eye(6); <span class="org-comment">% Diagonal 6x6 controller</span>
</pre>
</div>
<div id="orgbecd90a" class="figure">
<p><img src="figs/enc_struts_iff_root_locus.png" alt="enc_struts_iff_root_locus.png" />
</p>
<p><span class="figure-number">Figure 12: </span>Root Locus for the IFF control strategy</p>
</div>
<p>
Then the &ldquo;optimal&rdquo; IFF controller is:
</p>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% IFF controller with Optimal gain</span></span>
Kiff = g<span class="org-type">*</span>Kiff_g1;
</pre>
</div>
<div id="org67421cd" class="figure">
<p><img src="figs/enc_struts_iff_opt_loop_gain.png" alt="enc_struts_iff_opt_loop_gain.png" />
</p>
<p><span class="figure-number">Figure 13: </span>Bode plot of the &ldquo;decentralized loop gain&rdquo; \(G_\text{iff}(i,i) \times K_\text{iff}(i,i)\)</p>
</div>
</div>
</div>
<div id="outline-container-orgb15799f" class="outline-4">
<h4 id="orgb15799f"><span class="section-number-4">1.4.2</span> Multiple Gains - Simulation</h4>
<div class="outline-text-4" id="text-1-4-2">
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Tested IFF gains</span></span>
iff_gains = [4, 10, 20, 40, 100, 200, 400];
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Initialize the Simscape model in closed loop</span></span>
n_hexapod = initializeNanoHexapodFinal(<span class="org-string">'flex_bot_type'</span>, <span class="org-string">'4dof'</span>, ...
<span class="org-string">'flex_top_type'</span>, <span class="org-string">'4dof'</span>, ...
<span class="org-string">'motion_sensor_type'</span>, <span class="org-string">'struts'</span>, ...
<span class="org-string">'actuator_type'</span>, <span class="org-string">'2dof'</span>, ...
<span class="org-string">'controller_type'</span>, <span class="org-string">'iff'</span>);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Identify the (damped) transfer function from u to dLm for different values of the IFF gain</span></span>
Gd_iff = {zeros(1, length(iff_gains))};
clear io; io_i = 1;
io(io_i) = linio([mdl, <span class="org-string">'/F'</span>], 1, <span class="org-string">'openinput'</span>); io_i = io_i <span class="org-type">+</span> 1; <span class="org-comment">% Actuator Inputs</span>
io(io_i) = linio([mdl, <span class="org-string">'/D'</span>], 1, <span class="org-string">'openoutput'</span>); io_i = io_i <span class="org-type">+</span> 1; <span class="org-comment">% Strut Displacement (encoder)</span>
<span class="org-keyword">for</span> <span class="org-variable-name"><span class="org-constant">i</span></span> = <span class="org-constant">1:length(iff_gains)</span>
Kiff = iff_gains(<span class="org-constant">i</span>)<span class="org-type">*</span>Kiff_g1<span class="org-type">*</span>eye(6); <span class="org-comment">% IFF Controller</span>
Gd_iff(<span class="org-constant">i</span>) = {exp(<span class="org-type">-</span>s<span class="org-type">*</span>Ts)<span class="org-type">*</span>linearize(mdl, io, 0.0, options)};
isstable(Gd_iff{<span class="org-constant">i</span>})
<span class="org-keyword">end</span>
</pre>
</div>
<div id="org5e12ba5" class="figure">
<p><img src="figs/enc_struts_iff_gains_effect_dvf_plant.png" alt="enc_struts_iff_gains_effect_dvf_plant.png" />
</p>
<p><span class="figure-number">Figure 14: </span>Effect of the IFF gain \(g\) on the transfer function from \(\bm{\tau}\) to \(d\bm{\mathcal{L}}_m\)</p>
</div>
</div>
</div>
<div id="outline-container-orgfc28d74" class="outline-4">
<h4 id="orgfc28d74"><span class="section-number-4">1.4.3</span> Experimental Results - Gains</h4>
<div class="outline-text-4" id="text-1-4-3">
<p>
Let&rsquo;s look at the damping introduced by IFF as a function of the IFF gain and compare that with the results obtained using the Simscape model.
</p>
</div>
<div id="outline-container-orgc87e132" class="outline-5">
<h5 id="orgc87e132"><span class="section-number-5">1.4.3.1</span> Load Data</h5>
<div class="outline-text-5" id="text-1-4-3-1">
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Load Identification Data</span></span>
meas_iff_gains = {};
<span class="org-keyword">for</span> <span class="org-variable-name"><span class="org-constant">i</span></span> = <span class="org-constant">1:length(iff_gains)</span>
meas_iff_gains(<span class="org-constant">i</span>) = {load(sprintf(<span class="org-string">'mat/iff_strut_1_noise_g_%i.mat'</span>, iff_gains(<span class="org-constant">i</span>)), <span class="org-string">'t'</span>, <span class="org-string">'Vexc'</span>, <span class="org-string">'Vs'</span>, <span class="org-string">'de'</span>, <span class="org-string">'u'</span>)};
<span class="org-keyword">end</span>
</pre>
</div>
</div>
</div>
<div id="outline-container-org082cedd" class="outline-5">
<h5 id="org082cedd"><span class="section-number-5">1.4.3.2</span> Spectral Analysis - Setup</h5>
<div class="outline-text-5" id="text-1-4-3-2">
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Setup useful variables</span></span>
<span class="org-comment">% Sampling Time [s]</span>
Ts = (meas_iff_gains{1}.t(end) <span class="org-type">-</span> (meas_iff_gains{1}.t(1)))<span class="org-type">/</span>(length(meas_iff_gains{1}.t)<span class="org-type">-</span>1);
<span class="org-comment">% Sampling Frequency [Hz]</span>
Fs = 1<span class="org-type">/</span>Ts;
<span class="org-comment">% Hannning Windows</span>
win = hanning(ceil(1<span class="org-type">*</span>Fs));
<span class="org-comment">% And we get the frequency vector</span>
[<span class="org-type">~</span>, f] = tfestimate(meas_iff_gains{1}.Vexc, meas_iff_gains{1}.de, win, [], [], 1<span class="org-type">/</span>Ts);
</pre>
</div>
</div>
</div>
<div id="outline-container-orgf617003" class="outline-5">
<h5 id="orgf617003"><span class="section-number-5">1.4.3.3</span> DVF Plant</h5>
<div class="outline-text-5" id="text-1-4-3-3">
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% DVF Plant (transfer function from u to dLm)</span></span>
G_iff_gains = {};
<span class="org-keyword">for</span> <span class="org-variable-name"><span class="org-constant">i</span></span> = <span class="org-constant">1:length(iff_gains)</span>
G_iff_gains{<span class="org-constant">i</span>} = tfestimate(meas_iff_gains{<span class="org-constant">i</span>}.Vexc, meas_iff_gains{<span class="org-constant">i</span>}.de(<span class="org-type">:</span>,1), win, [], [], 1<span class="org-type">/</span>Ts);
<span class="org-keyword">end</span>
</pre>
</div>
<div id="org16336f2" class="figure">
<p><img src="figs/comp_iff_gains_dvf_plant.png" alt="comp_iff_gains_dvf_plant.png" />
</p>
<p><span class="figure-number">Figure 15: </span>Transfer function from \(u\) to \(d\mathcal{L}_m\) for multiple values of the IFF gain</p>
</div>
<div id="orgcef8028" class="figure">
<p><img src="figs/comp_iff_gains_dvf_plant_zoom.png" alt="comp_iff_gains_dvf_plant_zoom.png" />
</p>
<p><span class="figure-number">Figure 16: </span>Transfer function from \(u\) to \(d\mathcal{L}_m\) for multiple values of the IFF gain (Zoom)</p>
</div>
<div class="important" id="orgf90d42d">
<p>
The IFF control strategy is very effective for the damping of the suspension modes.
It however does not damp the modes at 200Hz, 300Hz and 400Hz (flexible modes of the APA).
This is very logical.
</p>
<p>
Also, the experimental results and the models obtained from the Simscape model are in agreement.
</p>
</div>
</div>
</div>
<div id="outline-container-orgfaa6821" class="outline-5">
<h5 id="orgfaa6821"><span class="section-number-5">1.4.3.4</span> Experimental Results - Comparison of the un-damped and fully damped system</h5>
<div class="outline-text-5" id="text-1-4-3-4">
<div id="org16f8986" class="figure">
<p><img src="figs/comp_undamped_opt_iff_gain_diagonal.png" alt="comp_undamped_opt_iff_gain_diagonal.png" />
</p>
<p><span class="figure-number">Figure 17: </span>Comparison of the diagonal elements of the tranfer function from \(\bm{u}\) to \(d\bm{\mathcal{L}}_m\) without active damping and with optimal IFF gain</p>
</div>
<div class="question" id="orgb8cc006">
<p>
A series of modes at around 205Hz are also damped.
</p>
<p>
Are these damped modes at 205Hz additional &ldquo;suspension&rdquo; modes or flexible modes of the struts?
</p>
</div>
</div>
</div>
</div>
<div id="outline-container-orgc0e0293" class="outline-4">
<h4 id="orgc0e0293"><span class="section-number-4">1.4.4</span> Experimental Results - Damped Plant with Optimal gain</h4>
<div class="outline-text-4" id="text-1-4-4">
<p>
Let&rsquo;s now look at the \(6 \times 6\) damped plant with the optimal gain \(g = 400\).
</p>
</div>
<div id="outline-container-org04a0c15" class="outline-5">
<h5 id="org04a0c15"><span class="section-number-5">1.4.4.1</span> Load Data</h5>
<div class="outline-text-5" id="text-1-4-4-1">
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Load Identification Data</span></span>
meas_iff_struts = {};
<span class="org-keyword">for</span> <span class="org-variable-name"><span class="org-constant">i</span></span> = <span class="org-constant">1:6</span>
meas_iff_struts(<span class="org-constant">i</span>) = {load(sprintf(<span class="org-string">'mat/iff_strut_%i_noise_g_400.mat'</span>, <span class="org-constant">i</span>), <span class="org-string">'t'</span>, <span class="org-string">'Vexc'</span>, <span class="org-string">'Vs'</span>, <span class="org-string">'de'</span>, <span class="org-string">'u'</span>)};
<span class="org-keyword">end</span>
</pre>
</div>
</div>
</div>
<div id="outline-container-org288970e" class="outline-5">
<h5 id="org288970e"><span class="section-number-5">1.4.4.2</span> Spectral Analysis - Setup</h5>
<div class="outline-text-5" id="text-1-4-4-2">
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Setup useful variables</span></span>
<span class="org-comment">% Sampling Time [s]</span>
Ts = (meas_iff_struts{1}.t(end) <span class="org-type">-</span> (meas_iff_struts{1}.t(1)))<span class="org-type">/</span>(length(meas_iff_struts{1}.t)<span class="org-type">-</span>1);
<span class="org-comment">% Sampling Frequency [Hz]</span>
Fs = 1<span class="org-type">/</span>Ts;
<span class="org-comment">% Hannning Windows</span>
win = hanning(ceil(1<span class="org-type">*</span>Fs));
<span class="org-comment">% And we get the frequency vector</span>
[<span class="org-type">~</span>, f] = tfestimate(meas_iff_struts{1}.Vexc, meas_iff_struts{1}.de, win, [], [], 1<span class="org-type">/</span>Ts);
</pre>
</div>
</div>
</div>
<div id="outline-container-orgbe5d7c4" class="outline-5">
<h5 id="orgbe5d7c4"><span class="section-number-5">1.4.4.3</span> DVF Plant</h5>
<div class="outline-text-5" id="text-1-4-4-3">
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% DVF Plant (transfer function from u to dLm)</span></span>
G_iff_opt = {};
<span class="org-keyword">for</span> <span class="org-variable-name"><span class="org-constant">i</span></span> = <span class="org-constant">1:6</span>
G_iff_opt{<span class="org-constant">i</span>} = tfestimate(meas_iff_struts{<span class="org-constant">i</span>}.Vexc, meas_iff_struts{<span class="org-constant">i</span>}.de, win, [], [], 1<span class="org-type">/</span>Ts);
<span class="org-keyword">end</span>
</pre>
</div>
<div id="org02df88f" class="figure">
<p><img src="figs/damped_iff_plant_comp_diagonal.png" alt="damped_iff_plant_comp_diagonal.png" />
</p>
<p><span class="figure-number">Figure 18: </span>Comparison of the diagonal elements of the transfer functions from \(\bm{u}\) to \(d\bm{\mathcal{L}}_m\) with active damping (IFF) applied with an optimal gain \(g = 400\)</p>
</div>
<div id="orgc6361cd" class="figure">
<p><img src="figs/damped_iff_plant_comp_off_diagonal.png" alt="damped_iff_plant_comp_off_diagonal.png" />
</p>
<p><span class="figure-number">Figure 19: </span>Comparison of the off-diagonal elements of the transfer functions from \(\bm{u}\) to \(d\bm{\mathcal{L}}_m\) with active damping (IFF) applied with an optimal gain \(g = 400\)</p>
</div>
<div class="important" id="org1353115">
<p>
With the IFF control strategy applied and the optimal gain used, the suspension modes are very well damped.
Remains the undamped flexible modes of the APA (200Hz, 300Hz, 400Hz), and the modes of the plates (700Hz).
</p>
<p>
The Simscape model and the experimental results are in very good agreement.
</p>
</div>
</div>
</div>
</div>
</div>
<div id="outline-container-org4d2a6a9" class="outline-3">
<h3 id="org4d2a6a9"><span class="section-number-3">1.5</span> Modal Analysis</h3>
<div class="outline-text-3" id="text-1-5">
<p>
<a id="orgb37d2f8"></a>
</p>
<p>
Several 3-axis accelerometers are fixed on the top platform of the nano-hexapod as shown in Figure <a href="#orgcc43dbe">22</a>.
</p>
<div id="org6f43329" class="figure">
<p><img src="figs/accelerometers_nano_hexapod.jpg" alt="accelerometers_nano_hexapod.jpg" />
</p>
<p><span class="figure-number">Figure 20: </span>Location of the accelerometers on top of the nano-hexapod</p>
</div>
<p>
The top platform is then excited using an instrumented hammer as shown in Figure <a href="#org5333181">21</a>.
</p>
<div id="org5333181" class="figure">
<p><img src="figs/hammer_excitation_compliance_meas.jpg" alt="hammer_excitation_compliance_meas.jpg" />
</p>
<p><span class="figure-number">Figure 21: </span>Example of an excitation using an instrumented hammer</p>
</div>
</div>
<div id="outline-container-org76f1cc6" class="outline-4">
<h4 id="org76f1cc6"><span class="section-number-4">1.5.1</span> Effectiveness of the IFF Strategy - Compliance</h4>
<div class="outline-text-4" id="text-1-5-1">
<p>
In this section, we wish to estimated the effectiveness of the IFF strategy concerning the compliance.
</p>
<p>
The top plate is excited vertically using the instrumented hammer two times:
</p>
<ol class="org-ol">
<li>no control loop is used</li>
<li>decentralized IFF is used</li>
</ol>
<p>
The data is loaded.
</p>
<div class="org-src-container">
<pre class="src src-matlab">frf_ol = load(<span class="org-string">'Measurement_Z_axis.mat'</span>); <span class="org-comment">% Open-Loop</span>
frf_iff = load(<span class="org-string">'Measurement_Z_axis_damped.mat'</span>); <span class="org-comment">% IFF</span>
</pre>
</div>
<p>
The mean vertical motion of the top platform is computed by averaging all 5 accelerometers.
</p>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Multiply by 10 (gain in m/s^2/V) and divide by 5 (number of accelerometers)</span></span>
d_frf_ol = 10<span class="org-type">/</span>5<span class="org-type">*</span>(frf_ol.FFT1_H1_4_1_RMS_Y_Mod <span class="org-type">+</span> frf_ol.FFT1_H1_7_1_RMS_Y_Mod <span class="org-type">+</span> frf_ol.FFT1_H1_10_1_RMS_Y_Mod <span class="org-type">+</span> frf_ol.FFT1_H1_13_1_RMS_Y_Mod <span class="org-type">+</span> frf_ol.FFT1_H1_16_1_RMS_Y_Mod)<span class="org-type">./</span>(2<span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">*</span>frf_ol.FFT1_H1_16_1_RMS_X_Val)<span class="org-type">.^</span>2;
d_frf_iff = 10<span class="org-type">/</span>5<span class="org-type">*</span>(frf_iff.FFT1_H1_4_1_RMS_Y_Mod <span class="org-type">+</span> frf_iff.FFT1_H1_7_1_RMS_Y_Mod <span class="org-type">+</span> frf_iff.FFT1_H1_10_1_RMS_Y_Mod <span class="org-type">+</span> frf_iff.FFT1_H1_13_1_RMS_Y_Mod <span class="org-type">+</span> frf_iff.FFT1_H1_16_1_RMS_Y_Mod)<span class="org-type">./</span>(2<span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">*</span>frf_iff.FFT1_H1_16_1_RMS_X_Val)<span class="org-type">.^</span>2;
</pre>
</div>
<p>
The vertical compliance (magnitude of the transfer function from a vertical force applied on the top plate to the vertical motion of the top plate) is shown in Figure <a href="#orgcc43dbe">22</a>.
</p>
<div id="orgcc43dbe" class="figure">
<p><img src="figs/compliance_vertical_comp_iff.png" alt="compliance_vertical_comp_iff.png" />
</p>
<p><span class="figure-number">Figure 22: </span>Measured vertical compliance with and without IFF</p>
</div>
<div class="important" id="org38045ac">
<p>
From Figure <a href="#orgcc43dbe">22</a>, it is clear that the IFF control strategy is very effective in damping the suspensions modes of the nano-hexapode.
It also has the effect of degrading (slightly) the vertical compliance at low frequency.
</p>
<p>
It also seems some damping can be added to the modes at around 205Hz which are flexible modes of the struts.
</p>
</div>
</div>
</div>
<div id="outline-container-org1c35d39" class="outline-4">
<h4 id="org1c35d39"><span class="section-number-4">1.5.2</span> Comparison with the Simscape Model</h4>
<div class="outline-text-4" id="text-1-5-2">
<p>
Let&rsquo;s now compare the measured vertical compliance with the vertical compliance as estimated from the Simscape model.
</p>
<p>
The transfer function from a vertical external force to the absolute motion of the top platform is identified (with and without IFF) using the Simscape model.
The comparison is done in Figure <a href="#org8a08cb4">23</a>.
Again, the model is quite accurate!
</p>
<div id="org8a08cb4" class="figure">
<p><img src="figs/compliance_vertical_comp_model_iff.png" alt="compliance_vertical_comp_model_iff.png" />
</p>
<p><span class="figure-number">Figure 23: </span>Measured vertical compliance with and without IFF</p>
</div>
</div>
</div>
<div id="outline-container-org2fb301f" class="outline-4">
<h4 id="org2fb301f"><span class="section-number-4">1.5.3</span> Obtained Mode Shapes</h4>
<div class="outline-text-4" id="text-1-5-3">
<p>
Then, several excitation are performed using the instrumented Hammer and the mode shapes are extracted.
</p>
<p>
We can observe the mode shapes of the first 6 modes that are the suspension modes (the plate is behaving as a solid body) in Figure <a href="#org5b33924">24</a>.
</p>
<div id="org5b33924" class="figure">
<p><img src="figs/mode_shapes_annotated.gif" alt="mode_shapes_annotated.gif" />
</p>
<p><span class="figure-number">Figure 24: </span>Measured mode shapes for the first six modes</p>
</div>
<p>
Then, there is a mode at 692Hz which corresponds to a flexible mode of the top plate (Figure <a href="#org5b33924">24</a>).
</p>
<div id="orgb4a4a07" class="figure">
<p><img src="figs/ModeShapeFlex1_crop.gif" alt="ModeShapeFlex1_crop.gif" />
</p>
<p><span class="figure-number">Figure 25: </span>First flexible mode at 692Hz</p>
</div>
<p>
The obtained modes are summarized in Table <a href="#org0c9e4da">2</a>.
</p>
<table id="org0c9e4da" border="2" cellspacing="0" cellpadding="6" rules="groups" frame="hsides">
<caption class="t-above"><span class="table-number">Table 2:</span> Description of the identified modes</caption>
<colgroup>
<col class="org-right" />
<col class="org-right" />
<col class="org-left" />
</colgroup>
<thead>
<tr>
<th scope="col" class="org-right">Mode</th>
<th scope="col" class="org-right">Freq. [Hz]</th>
<th scope="col" class="org-left">Description</th>
</tr>
</thead>
<tbody>
<tr>
<td class="org-right">1</td>
<td class="org-right">105</td>
<td class="org-left">Suspension Mode: Y-translation</td>
</tr>
<tr>
<td class="org-right">2</td>
<td class="org-right">107</td>
<td class="org-left">Suspension Mode: X-translation</td>
</tr>
<tr>
<td class="org-right">3</td>
<td class="org-right">131</td>
<td class="org-left">Suspension Mode: Z-translation</td>
</tr>
<tr>
<td class="org-right">4</td>
<td class="org-right">161</td>
<td class="org-left">Suspension Mode: Y-tilt</td>
</tr>
<tr>
<td class="org-right">5</td>
<td class="org-right">162</td>
<td class="org-left">Suspension Mode: X-tilt</td>
</tr>
<tr>
<td class="org-right">6</td>
<td class="org-right">180</td>
<td class="org-left">Suspension Mode: Z-rotation</td>
</tr>
<tr>
<td class="org-right">7</td>
<td class="org-right">692</td>
<td class="org-left">(flexible) Membrane mode of the top platform</td>
</tr>
</tbody>
</table>
</div>
</div>
</div>
</div>
<div id="outline-container-orgfd9b3f1" class="outline-2">
<h2 id="orgfd9b3f1"><span class="section-number-2">2</span> Encoders fixed to the plates</h2>
<div class="outline-text-2" id="text-2">
<p>
<a id="org6f5eb76"></a>
</p>
</div>
</div>
</div>
<div id="postamble" class="status">
<p class="author">Author: Dehaeze Thomas</p>
<p class="date">Created: 2021-06-14 lun. 18:07</p>
</div>
</body>
</html>