<?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-09 mer. 18:13 --> <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="#orgd5a3ff2">1. Encoders fixed to the Struts</a> <ul> <li><a href="#orgaaf36d1">1.1. Introduction</a></li> <li><a href="#org4eac0e4">1.2. Identification of the dynamics</a> <ul> <li><a href="#orge7631cb">1.2.1. Load Data</a></li> <li><a href="#org3d8f0db">1.2.2. Spectral Analysis - Setup</a></li> <li><a href="#orgfe475e0">1.2.3. DVF Plant</a></li> <li><a href="#org9c55cb0">1.2.4. IFF Plant</a></li> </ul> </li> <li><a href="#orgb32a800">1.3. Comparison with the Simscape Model</a> <ul> <li><a href="#org49d6b51">1.3.1. Dynamics from Actuator to Force Sensors</a></li> <li><a href="#org68f8e6c">1.3.2. Dynamics from Actuator to Encoder</a></li> </ul> </li> <li><a href="#orge6221eb">1.4. Integral Force Feedback</a> <ul> <li><a href="#org1ccd985">1.4.1. Root Locus and Decentralized Loop gain</a></li> <li><a href="#orgd6bc33c">1.4.2. Multiple Gains - Simulation</a></li> <li><a href="#orgcbdb9eb">1.4.3. Experimental Results</a></li> </ul> </li> </ul> </li> <li><a href="#org16300e1">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> In this document, the dynamics of the nano-hexapod shown in Figure <a href="#orgcaac3cd">1</a> is identified. </p> <div class="note" id="org64d5e50"> <p> Here are the documentation of the equipment used for this test bench: </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="orgcaac3cd" 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 id="org6004b44" 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> <div id="orgc32dab5" 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="orgcb52f65" 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"> </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> <div id="outline-container-orgd5a3ff2" class="outline-2"> <h2 id="orgd5a3ff2"><span class="section-number-2">1</span> Encoders fixed to the Struts</h2> <div class="outline-text-2" id="text-1"> </div> <div id="outline-container-orgaaf36d1" class="outline-3"> <h3 id="orgaaf36d1"><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> </div> </div> <div id="outline-container-org4eac0e4" class="outline-3"> <h3 id="org4eac0e4"><span class="section-number-3">1.2</span> Identification of the dynamics</h3> <div class="outline-text-3" id="text-1-2"> </div> <div id="outline-container-orge7631cb" class="outline-4"> <h4 id="orge7631cb"><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-org3d8f0db" class="outline-4"> <h4 id="org3d8f0db"><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"><</span> 250; <span class="org-comment">% Points for low frequency excitation</span> i_hf = f <span class="org-type">></span> 250; <span class="org-comment">% Points for high frequency excitation</span> </pre> </div> </div> </div> <div id="outline-container-orgfe475e0" class="outline-4"> <h4 id="orgfe475e0"><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’s compute the coherence from the excitation voltage and the displacement as measured by the encoders (Figure <a href="#org7027095">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="org7027095" 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="#orgeda62ff">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="orgeda62ff" 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-org9c55cb0" class="outline-4"> <h4 id="org9c55cb0"><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’s compute the coherence from the excitation voltage and the displacement as measured by the encoders (Figure <a href="#orga958a00">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="orga958a00" 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="#orgaa3ad1c">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="orgaa3ad1c" 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-orgb32a800" class="outline-3"> <h3 id="orgb32a800"><span class="section-number-3">1.3</span> Comparison with the Simscape Model</h3> <div class="outline-text-3" id="text-1-3"> <p> In this section, the measured dynamics is compared with the dynamics estimated from the Simscape model. </p> </div> <div id="outline-container-org49d6b51" class="outline-4"> <h4 id="org49d6b51"><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="orgb002d1f" 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="orgef9afdd" 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-org68f8e6c" class="outline-4"> <h4 id="org68f8e6c"><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="org8001ef8" 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="org8a8dc6a" 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-orge6221eb" class="outline-3"> <h3 id="orge6221eb"><span class="section-number-3">1.4</span> Integral Force Feedback</h3> <div class="outline-text-3" id="text-1-4"> </div> <div id="outline-container-org1ccd985" class="outline-4"> <h4 id="org1ccd985"><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="org9d7fb85" 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 “optimal” 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="org879ceab" 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 “decentralized loop gain” \(G_\text{iff}(i,i) \times K_\text{iff}(i,i)\)</p> </div> </div> </div> <div id="outline-container-orgd6bc33c" class="outline-4"> <h4 id="orgd6bc33c"><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, 1000]; </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="orgb5b5f55" 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-orgcbdb9eb" class="outline-4"> <h4 id="orgcbdb9eb"><span class="section-number-4">1.4.3</span> Experimental Results</h4> </div> </div> </div> <div id="outline-container-org16300e1" class="outline-2"> <h2 id="org16300e1"><span class="section-number-2">2</span> Encoders fixed to the plates</h2> </div> </div> <div id="postamble" class="status"> <p class="author">Author: Dehaeze Thomas</p> <p class="date">Created: 2021-06-09 mer. 18:13</p> </div> </body> </html>