stewart-simscape/docs/flexible-stewart-platform.html

1223 lines
58 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-01-08 ven. 15:52 -->
<meta http-equiv="Content-Type" content="text/html;charset=utf-8" />
<title>Stewart Platform with Flexible Elements</title>
<meta name="generator" content="Org mode" />
<meta name="author" content="Dehaeze Thomas" />
<link rel="stylesheet" type="text/css" href="https://research.tdehaeze.xyz/css/style.css"/>
<script type="text/javascript" src="https://research.tdehaeze.xyz/js/script.js"></script>
</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">Stewart Platform with Flexible Elements</h1>
<div id="table-of-contents">
<h2>Table of Contents</h2>
<div id="text-table-of-contents">
<ul>
<li><a href="#orgc309c7b">1. Simscape Model</a>
<ul>
<li><a href="#org0e00e94">1.1. Flexible APA</a></li>
<li><a href="#orgf337fe9">1.2. Flexible Joint</a></li>
<li><a href="#orgc239ed1">1.3. Identification</a></li>
<li><a href="#org59e4972">1.4. No Flexible Elements</a></li>
<li><a href="#orgb06052a">1.5. Flexible joints</a></li>
<li><a href="#org4cccff6">1.6. Flexible APA</a></li>
<li><a href="#org4f41f14">1.7. Flexible Joints and APA</a></li>
<li><a href="#orga39e477">1.8. Save</a></li>
<li><a href="#org1e66228">1.9. Direct Velocity Feedback</a></li>
<li><a href="#orgef60bbc">1.10. Integral Force Feedback</a></li>
<li><a href="#org50fdd32">1.11. Procedure to include flexible elements into Simscape</a></li>
<li><a href="#org55fe34f">1.12. Conclusion</a></li>
</ul>
</li>
<li><a href="#org2d65f84">2. Control with flexible elements</a>
<ul>
<li><a href="#org7f0d75c">2.1. Flexible APA and Flexible Joint</a></li>
<li><a href="#org5f84aea">2.2. Identification</a></li>
<li><a href="#org5ae25be">2.3. Decentralized Direct Velocity Feedback</a></li>
<li><a href="#org3d014d0">2.4. HAC</a></li>
</ul>
</li>
<li><a href="#org2b937bc">3. Flexible Joint Specifications</a>
<ul>
<li><a href="#org775a387">3.1. Stewart Platform Initialization</a></li>
<li><a href="#orgc430963">3.2. Effect of the Bending Stiffness</a></li>
<li><a href="#orgb29824b">3.3. Effect of the Torsion Stiffness</a></li>
<li><a href="#org6d029b0">3.4. Effect of the Axial Stiffness</a></li>
<li><a href="#org5177329">3.5. Effect of the Radial (Shear) Stiffness</a></li>
<li><a href="#orge0f8240">3.6. Comparison of perfect joint and worst specified joint</a></li>
<li><a href="#org79b6e2d">3.7. Conclusion</a></li>
</ul>
</li>
<li><a href="#org8798d60">4. Flexible Joint Specifications with the APA300ML</a>
<ul>
<li><a href="#org6d56b33">4.1. Stewart Platform Initialization</a></li>
<li><a href="#orgdc3d576">4.2. Comparison of perfect joint and worst specified joint</a></li>
</ul>
</li>
<li><a href="#orgbae1ad3">5. Relative Motion Sensors</a>
<ul>
<li><a href="#org74f7ec9">5.1. Stewart Platform Initialization</a></li>
</ul>
</li>
<li><a href="#orgb454975">6. Struts with Encoders</a>
<ul>
<li><a href="#org6bde940">6.1. Flexible Strut</a></li>
<li><a href="#org4b369e6">6.2. Stewart Platform</a></li>
</ul>
</li>
</ul>
</div>
</div>
<div id="outline-container-orgc309c7b" class="outline-2">
<h2 id="orgc309c7b"><span class="section-number-2">1</span> Simscape Model</h2>
<div class="outline-text-2" id="text-1">
</div>
<div id="outline-container-org0e00e94" class="outline-3">
<h3 id="org0e00e94"><span class="section-number-3">1.1</span> Flexible APA</h3>
<div class="outline-text-3" id="text-1-1">
<div class="org-src-container">
<pre class="src src-matlab">apa = load(<span class="org-string">'./mat/APA300ML.mat'</span>, <span class="org-string">'int_xyz'</span>, <span class="org-string">'int_i'</span>, <span class="org-string">'n_xyz'</span>, <span class="org-string">'n_i'</span>, <span class="org-string">'nodes'</span>, <span class="org-string">'M'</span>, <span class="org-string">'K'</span>);
</pre>
</div>
<table border="2" cellspacing="0" cellpadding="6" rules="groups" frame="hsides">
<colgroup>
<col class="org-left" />
<col class="org-right" />
</colgroup>
<tbody>
<tr>
<td class="org-left">Total number of Nodes</td>
<td class="org-right">7</td>
</tr>
<tr>
<td class="org-left">Number of interface Nodes</td>
<td class="org-right">7</td>
</tr>
<tr>
<td class="org-left">Number of Modes</td>
<td class="org-right">120</td>
</tr>
<tr>
<td class="org-left">Size of M and K matrices</td>
<td class="org-right">162</td>
</tr>
</tbody>
</table>
<table border="2" cellspacing="0" cellpadding="6" rules="groups" frame="hsides">
<caption class="t-above"><span class="table-number">Table 1:</span> Coordinates of the interface nodes</caption>
<colgroup>
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
</colgroup>
<thead>
<tr>
<th scope="col" class="org-right">Node i</th>
<th scope="col" class="org-right">Node Number</th>
<th scope="col" class="org-right">x [m]</th>
<th scope="col" class="org-right">y [m]</th>
<th scope="col" class="org-right">z [m]</th>
</tr>
</thead>
<tbody>
<tr>
<td class="org-right">1.0</td>
<td class="org-right">697783.0</td>
<td class="org-right">0.0</td>
<td class="org-right">0.0</td>
<td class="org-right">-0.015</td>
</tr>
<tr>
<td class="org-right">2.0</td>
<td class="org-right">697784.0</td>
<td class="org-right">0.0</td>
<td class="org-right">0.0</td>
<td class="org-right">0.015</td>
</tr>
<tr>
<td class="org-right">3.0</td>
<td class="org-right">697785.0</td>
<td class="org-right">-0.0325</td>
<td class="org-right">0.0</td>
<td class="org-right">0.0</td>
</tr>
<tr>
<td class="org-right">4.0</td>
<td class="org-right">697786.0</td>
<td class="org-right">-0.0125</td>
<td class="org-right">0.0</td>
<td class="org-right">0.0</td>
</tr>
<tr>
<td class="org-right">5.0</td>
<td class="org-right">697787.0</td>
<td class="org-right">-0.0075</td>
<td class="org-right">0.0</td>
<td class="org-right">0.0</td>
</tr>
<tr>
<td class="org-right">6.0</td>
<td class="org-right">697788.0</td>
<td class="org-right">0.0125</td>
<td class="org-right">0.0</td>
<td class="org-right">0.0</td>
</tr>
<tr>
<td class="org-right">7.0</td>
<td class="org-right">697789.0</td>
<td class="org-right">0.0325</td>
<td class="org-right">0.0</td>
<td class="org-right">0.0</td>
</tr>
</tbody>
</table>
</div>
</div>
<div id="outline-container-orgf337fe9" class="outline-3">
<h3 id="orgf337fe9"><span class="section-number-3">1.2</span> Flexible Joint</h3>
<div class="outline-text-3" id="text-1-2">
<div class="org-src-container">
<pre class="src src-matlab">flex_joint = load(<span class="org-string">'./mat/flexor_025.mat'</span>, <span class="org-string">'int_xyz'</span>, <span class="org-string">'int_i'</span>, <span class="org-string">'n_xyz'</span>, <span class="org-string">'n_i'</span>, <span class="org-string">'nodes'</span>, <span class="org-string">'M'</span>, <span class="org-string">'K'</span>);
</pre>
</div>
<table border="2" cellspacing="0" cellpadding="6" rules="groups" frame="hsides">
<colgroup>
<col class="org-left" />
<col class="org-right" />
</colgroup>
<tbody>
<tr>
<td class="org-left">Total number of Nodes</td>
<td class="org-right">2</td>
</tr>
<tr>
<td class="org-left">Number of interface Nodes</td>
<td class="org-right">2</td>
</tr>
<tr>
<td class="org-left">Number of Modes</td>
<td class="org-right">6</td>
</tr>
<tr>
<td class="org-left">Size of M and K matrices</td>
<td class="org-right">18</td>
</tr>
</tbody>
</table>
<table border="2" cellspacing="0" cellpadding="6" rules="groups" frame="hsides">
<caption class="t-above"><span class="table-number">Table 2:</span> Coordinates of the interface nodes</caption>
<colgroup>
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
</colgroup>
<thead>
<tr>
<th scope="col" class="org-right">Node i</th>
<th scope="col" class="org-right">Node Number</th>
<th scope="col" class="org-right">x [m]</th>
<th scope="col" class="org-right">y [m]</th>
<th scope="col" class="org-right">z [m]</th>
</tr>
</thead>
<tbody>
<tr>
<td class="org-right">1.0</td>
<td class="org-right">528875.0</td>
<td class="org-right">0.0</td>
<td class="org-right">0.0</td>
<td class="org-right">0.0</td>
</tr>
<tr>
<td class="org-right">2.0</td>
<td class="org-right">528876.0</td>
<td class="org-right">0.0</td>
<td class="org-right">0.0</td>
<td class="org-right">-0.0</td>
</tr>
</tbody>
</table>
<table border="2" cellspacing="0" cellpadding="6" rules="groups" frame="hsides">
<colgroup>
<col class="org-left" />
<col class="org-right" />
</colgroup>
<thead>
<tr>
<th scope="col" class="org-left"><b>Caracteristic</b></th>
<th scope="col" class="org-right"><b>Value</b></th>
</tr>
</thead>
<tbody>
<tr>
<td class="org-left">Axial Stiffness [N/um]</td>
<td class="org-right">94</td>
</tr>
<tr>
<td class="org-left">Bending Stiffness [Nm/rad]</td>
<td class="org-right">5</td>
</tr>
<tr>
<td class="org-left">Bending Stiffness [Nm/rad]</td>
<td class="org-right">5</td>
</tr>
<tr>
<td class="org-left">Torsion Stiffness [Nm/rad]</td>
<td class="org-right">260</td>
</tr>
</tbody>
</table>
</div>
</div>
<div id="outline-container-orgc239ed1" class="outline-3">
<h3 id="orgc239ed1"><span class="section-number-3">1.3</span> Identification</h3>
<div class="outline-text-3" id="text-1-3">
<p>
And we identify the dynamics from force actuators to force sensors.
</p>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Options for Linearized</span></span>
options = linearizeOptions;
options.SampleTime = 0;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Name of the Simulink File</span></span>
mdl = <span class="org-string">'stewart_platform_model'</span>;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Input/Output definition</span></span>
clear io; io_i = 1;
io(io_i) = linio([mdl, <span class="org-string">'/Controller'</span>], 1, <span class="org-string">'openinput'</span>); io_i = io_i <span class="org-type">+</span> 1; <span class="org-comment">% Actuator Force Inputs [N]</span>
io(io_i) = linio([mdl, <span class="org-string">'/Stewart Platform'</span>], 1, <span class="org-string">'openoutput'</span>, [], <span class="org-string">'dLm'</span>); io_i = io_i <span class="org-type">+</span> 1; <span class="org-comment">% Relative Displacement Outputs [m]</span>
io(io_i) = linio([mdl, <span class="org-string">'/Stewart Platform'</span>], 1, <span class="org-string">'openoutput'</span>, [], <span class="org-string">'Taum'</span>); io_i = io_i <span class="org-type">+</span> 1; <span class="org-comment">% Force Sensors [N]</span>
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">ground = initializeGround(<span class="org-string">'type'</span>, <span class="org-string">'none'</span>);
payload = initializePayload(<span class="org-string">'type'</span>, <span class="org-string">'rigid'</span>, <span class="org-string">'m'</span>, 50);
controller = initializeController(<span class="org-string">'type'</span>, <span class="org-string">'open-loop'</span>);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">disturbances = initializeDisturbances();
</pre>
</div>
</div>
</div>
<div id="outline-container-org59e4972" class="outline-3">
<h3 id="org59e4972"><span class="section-number-3">1.4</span> No Flexible Elements</h3>
<div class="outline-text-3" id="text-1-4">
<div class="org-src-container">
<pre class="src src-matlab">stewart = initializeStewartPlatform();
stewart = initializeFramesPositions(stewart);
stewart = generateGeneralConfiguration(stewart);
stewart = computeJointsPose(stewart);
stewart = initializeAmplifiedStrutDynamics(stewart, <span class="org-string">'Ke'</span>, 1.5e6<span class="org-type">*</span>ones(6,1), <span class="org-string">'Ka'</span>, 40.5e6<span class="org-type">*</span>ones(6,1), <span class="org-string">'K1'</span>, 0.4e6<span class="org-type">*</span>ones(6,1));
stewart = initializeJointDynamics(stewart, <span class="org-string">'type_M'</span>, <span class="org-string">'spherical_3dof'</span>, ...
<span class="org-string">'Kr_M'</span>, flex_joint.K(1,1)<span class="org-type">*</span>ones(6,1), ...
<span class="org-string">'Ka_M'</span>, flex_joint.K(3,3)<span class="org-type">*</span>ones(6,1), ...
<span class="org-string">'Kf_M'</span>, flex_joint.K(4,4)<span class="org-type">*</span>ones(6,1), ...
<span class="org-string">'Kt_M'</span>, flex_joint.K(6,6)<span class="org-type">*</span>ones(6,1), ...
<span class="org-string">'type_F'</span>, <span class="org-string">'universal_3dof'</span>, ...
<span class="org-string">'Kr_F'</span>, flex_joint.K(1,1)<span class="org-type">*</span>ones(6,1), ...
<span class="org-string">'Ka_F'</span>, flex_joint.K(3,3)<span class="org-type">*</span>ones(6,1), ...
<span class="org-string">'Kf_F'</span>, flex_joint.K(4,4)<span class="org-type">*</span>ones(6,1), ...
<span class="org-string">'Kt_F'</span>, flex_joint.K(6,6)<span class="org-type">*</span>ones(6,1));
stewart = initializeCylindricalPlatforms(stewart);
stewart = initializeCylindricalStruts(stewart);
stewart = computeJacobian(stewart);
stewart = initializeStewartPose(stewart);
stewart = initializeInertialSensor(stewart);
references = initializeReferences(stewart);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Run the linearization</span></span>
G = linearize(mdl, io, options);
G.InputName = {<span class="org-string">'F1'</span>, <span class="org-string">'F2'</span>, <span class="org-string">'F3'</span>, <span class="org-string">'F4'</span>, <span class="org-string">'F5'</span>, <span class="org-string">'F6'</span>};
G.OutputName = {<span class="org-string">'Dm1'</span>, <span class="org-string">'Dm2'</span>, <span class="org-string">'Dm3'</span>, <span class="org-string">'Dm4'</span>, <span class="org-string">'Dm5'</span>, <span class="org-string">'Dm6'</span>, <span class="org-string">'Fm1'</span>, <span class="org-string">'Fm2'</span>, <span class="org-string">'Fm3'</span>, <span class="org-string">'Fm4'</span>, <span class="org-string">'Fm5'</span>, <span class="org-string">'Fm6'</span>};
</pre>
</div>
</div>
</div>
<div id="outline-container-orgb06052a" class="outline-3">
<h3 id="orgb06052a"><span class="section-number-3">1.5</span> Flexible joints</h3>
<div class="outline-text-3" id="text-1-5">
<div id="org62ba26b" class="figure">
<p><img src="figs/simscape_flex_joints.png" alt="simscape_flex_joints.png" />
</p>
<p><span class="figure-number">Figure 1: </span>Figure caption</p>
</div>
<div class="org-src-container">
<pre class="src src-matlab">stewart = initializeStewartPlatform();
stewart = initializeFramesPositions(stewart);
stewart = generateGeneralConfiguration(stewart);
stewart = computeJointsPose(stewart);
stewart = initializeAmplifiedStrutDynamics(stewart, <span class="org-string">'Ke'</span>, 1.5e6<span class="org-type">*</span>ones(6,1), <span class="org-string">'Ka'</span>, 40.5e6<span class="org-type">*</span>ones(6,1), <span class="org-string">'K1'</span>, 0.4e6<span class="org-type">*</span>ones(6,1));
stewart = initializeJointDynamics(stewart, <span class="org-string">'type_F'</span>, <span class="org-string">'flexible'</span>, <span class="org-string">'K_F'</span>, flex_joint.K, <span class="org-string">'M_F'</span>, flex_joint.M, <span class="org-string">'n_xyz_F'</span>, flex_joint.n_xyz, <span class="org-string">'xi_F'</span>, 0.1, <span class="org-string">'step_file_F'</span>, <span class="org-string">'mat/flexor_ID16.STEP'</span>, <span class="org-string">'type_M'</span>, <span class="org-string">'flexible'</span>, <span class="org-string">'K_M'</span>, flex_joint.K, <span class="org-string">'M_M'</span>, flex_joint.M, <span class="org-string">'n_xyz_M'</span>, flex_joint.n_xyz, <span class="org-string">'xi_M'</span>, 0.1, <span class="org-string">'step_file_M'</span>, <span class="org-string">'mat/flexor_ID16.STEP'</span>);
stewart = initializeCylindricalPlatforms(stewart);
stewart = initializeCylindricalStruts(stewart);
stewart = computeJacobian(stewart);
stewart = initializeStewartPose(stewart);
stewart = initializeInertialSensor(stewart);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Run the linearization</span></span>
Gj = linearize(mdl, io, options);
Gj.InputName = {<span class="org-string">'F1'</span>, <span class="org-string">'F2'</span>, <span class="org-string">'F3'</span>, <span class="org-string">'F4'</span>, <span class="org-string">'F5'</span>, <span class="org-string">'F6'</span>};
Gj.OutputName = {<span class="org-string">'Dm1'</span>, <span class="org-string">'Dm2'</span>, <span class="org-string">'Dm3'</span>, <span class="org-string">'Dm4'</span>, <span class="org-string">'Dm5'</span>, <span class="org-string">'Dm6'</span>, <span class="org-string">'Fm1'</span>, <span class="org-string">'Fm2'</span>, <span class="org-string">'Fm3'</span>, <span class="org-string">'Fm4'</span>, <span class="org-string">'Fm5'</span>, <span class="org-string">'Fm6'</span>};
</pre>
</div>
</div>
</div>
<div id="outline-container-org4cccff6" class="outline-3">
<h3 id="org4cccff6"><span class="section-number-3">1.6</span> Flexible APA</h3>
<div class="outline-text-3" id="text-1-6">
<div id="org6abb282" class="figure">
<p><img src="figs/simscape_flex_apa.png" alt="simscape_flex_apa.png" />
</p>
<p><span class="figure-number">Figure 2: </span>Figure caption</p>
</div>
<div class="org-src-container">
<pre class="src src-matlab">stewart = initializeStewartPlatform();
stewart = initializeFramesPositions(stewart);
stewart = generateGeneralConfiguration(stewart);
stewart = computeJointsPose(stewart);
stewart = initializeFlexibleStrutDynamics(stewart, <span class="org-string">'H'</span>, 0.03, <span class="org-string">'K'</span>, apa.K, <span class="org-string">'M'</span>, apa.M, <span class="org-string">'n_xyz'</span>, apa.n_xyz, <span class="org-string">'xi'</span>, 0.1, <span class="org-string">'Gf'</span>, <span class="org-type">-</span>2.65e7, <span class="org-string">'step_file'</span>, <span class="org-string">'mat/APA300ML.STEP'</span>);
stewart = initializeJointDynamics(stewart, <span class="org-string">'type_M'</span>, <span class="org-string">'spherical_3dof'</span>, ...
<span class="org-string">'Kr_M'</span>, flex_joint.K(1,1)<span class="org-type">*</span>ones(6,1), ...
<span class="org-string">'Ka_M'</span>, flex_joint.K(3,3)<span class="org-type">*</span>ones(6,1), ...
<span class="org-string">'Kf_M'</span>, flex_joint.K(4,4)<span class="org-type">*</span>ones(6,1), ...
<span class="org-string">'Kt_M'</span>, flex_joint.K(6,6)<span class="org-type">*</span>ones(6,1), ...
<span class="org-string">'type_F'</span>, <span class="org-string">'universal_3dof'</span>, ...
<span class="org-string">'Kr_F'</span>, flex_joint.K(1,1)<span class="org-type">*</span>ones(6,1), ...
<span class="org-string">'Ka_F'</span>, flex_joint.K(3,3)<span class="org-type">*</span>ones(6,1), ...
<span class="org-string">'Kf_F'</span>, flex_joint.K(4,4)<span class="org-type">*</span>ones(6,1), ...
<span class="org-string">'Kt_F'</span>, flex_joint.K(6,6)<span class="org-type">*</span>ones(6,1));
stewart = initializeCylindricalPlatforms(stewart);
stewart = initializeCylindricalStruts(stewart, <span class="org-string">'type_F'</span>, <span class="org-string">'none'</span>, <span class="org-string">'type_M'</span>, <span class="org-string">'none'</span>);
stewart = computeJacobian(stewart);
stewart = initializeStewartPose(stewart);
stewart = initializeInertialSensor(stewart);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Run the linearization</span></span>
Ga = <span class="org-type">-</span>linearize(mdl, io, options);
Ga.InputName = {<span class="org-string">'F1'</span>, <span class="org-string">'F2'</span>, <span class="org-string">'F3'</span>, <span class="org-string">'F4'</span>, <span class="org-string">'F5'</span>, <span class="org-string">'F6'</span>};
Ga.OutputName = {<span class="org-string">'Dm1'</span>, <span class="org-string">'Dm2'</span>, <span class="org-string">'Dm3'</span>, <span class="org-string">'Dm4'</span>, <span class="org-string">'Dm5'</span>, <span class="org-string">'Dm6'</span>, <span class="org-string">'Fm1'</span>, <span class="org-string">'Fm2'</span>, <span class="org-string">'Fm3'</span>, <span class="org-string">'Fm4'</span>, <span class="org-string">'Fm5'</span>, <span class="org-string">'Fm6'</span>};
</pre>
</div>
</div>
</div>
<div id="outline-container-org4f41f14" class="outline-3">
<h3 id="org4f41f14"><span class="section-number-3">1.7</span> Flexible Joints and APA</h3>
<div class="outline-text-3" id="text-1-7">
<div id="org2716c94" class="figure">
<p><img src="figs/simscape_flexible.png" alt="simscape_flexible.png" />
</p>
<p><span class="figure-number">Figure 3: </span>Figure caption</p>
</div>
<div class="org-src-container">
<pre class="src src-matlab">stewart = initializeStewartPlatform();
stewart = initializeFramesPositions(stewart);
stewart = generateGeneralConfiguration(stewart);
stewart = computeJointsPose(stewart);
stewart = initializeFlexibleStrutDynamics(stewart, <span class="org-string">'H'</span>, 0.03, <span class="org-string">'K'</span>, apa.K, <span class="org-string">'M'</span>, apa.M, <span class="org-string">'n_xyz'</span>, apa.n_xyz, <span class="org-string">'xi'</span>, 0.1, <span class="org-string">'Gf'</span>, <span class="org-type">-</span>2.65e7, <span class="org-string">'step_file'</span>, <span class="org-string">'mat/APA300ML.STEP'</span>);
stewart = initializeJointDynamics(stewart, <span class="org-string">'type_F'</span>, <span class="org-string">'flexible'</span>, <span class="org-string">'K_F'</span>, flex_joint.K, <span class="org-string">'M_F'</span>, flex_joint.M, <span class="org-string">'n_xyz_F'</span>, flex_joint.n_xyz, <span class="org-string">'xi_F'</span>, 0.1, <span class="org-string">'step_file_F'</span>, <span class="org-string">'mat/flexor_ID16.STEP'</span>, <span class="org-string">'type_M'</span>, <span class="org-string">'flexible'</span>, <span class="org-string">'K_M'</span>, flex_joint.K, <span class="org-string">'M_M'</span>, flex_joint.M, <span class="org-string">'n_xyz_M'</span>, flex_joint.n_xyz, <span class="org-string">'xi_M'</span>, 0.1, <span class="org-string">'step_file_M'</span>, <span class="org-string">'mat/flexor_ID16.STEP'</span>);
stewart = initializeCylindricalPlatforms(stewart);
stewart = initializeCylindricalStruts(stewart, <span class="org-string">'type_F'</span>, <span class="org-string">'none'</span>, <span class="org-string">'type_M'</span>, <span class="org-string">'none'</span>);
stewart = computeJacobian(stewart);
stewart = initializeStewartPose(stewart);
stewart = initializeInertialSensor(stewart);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">Gf = <span class="org-type">-</span>linearize(mdl, io, options);
Gf.InputName = {<span class="org-string">'F1'</span>, <span class="org-string">'F2'</span>, <span class="org-string">'F3'</span>, <span class="org-string">'F4'</span>, <span class="org-string">'F5'</span>, <span class="org-string">'F6'</span>};
Gf.OutputName = {<span class="org-string">'Dm1'</span>, <span class="org-string">'Dm2'</span>, <span class="org-string">'Dm3'</span>, <span class="org-string">'Dm4'</span>, <span class="org-string">'Dm5'</span>, <span class="org-string">'Dm6'</span>, <span class="org-string">'Fm1'</span>, <span class="org-string">'Fm2'</span>, <span class="org-string">'Fm3'</span>, <span class="org-string">'Fm4'</span>, <span class="org-string">'Fm5'</span>, <span class="org-string">'Fm6'</span>};
</pre>
</div>
</div>
</div>
<div id="outline-container-orga39e477" class="outline-3">
<h3 id="orga39e477"><span class="section-number-3">1.8</span> Save</h3>
<div class="outline-text-3" id="text-1-8">
<div class="org-src-container">
<pre class="src src-matlab">save(<span class="org-string">'./mat/flexible_stewart_platform.mat'</span>, <span class="org-string">'G'</span>, <span class="org-string">'Gj'</span>, <span class="org-string">'Ga'</span>, <span class="org-string">'Gf'</span>);
</pre>
</div>
</div>
</div>
<div id="outline-container-org1e66228" class="outline-3">
<h3 id="org1e66228"><span class="section-number-3">1.9</span> Direct Velocity Feedback</h3>
<div class="outline-text-3" id="text-1-9">
<div id="orgb31eeec" class="figure">
<p><img src="figs/flexible_elements_effect_dvf.png" alt="flexible_elements_effect_dvf.png" />
</p>
<p><span class="figure-number">Figure 4: </span>Change of the DVF plant dynamics with the added flexible elements</p>
</div>
</div>
</div>
<div id="outline-container-orgef60bbc" class="outline-3">
<h3 id="orgef60bbc"><span class="section-number-3">1.10</span> Integral Force Feedback</h3>
<div class="outline-text-3" id="text-1-10">
<div id="orgbe59bc0" class="figure">
<p><img src="figs/flexible_elements_effect_iff.png" alt="flexible_elements_effect_iff.png" />
</p>
<p><span class="figure-number">Figure 5: </span>Change of the IFF plant dynamics with the added flexible elements</p>
</div>
</div>
</div>
<div id="outline-container-org50fdd32" class="outline-3">
<h3 id="org50fdd32"><span class="section-number-3">1.11</span> Procedure to include flexible elements into Simscape</h3>
<div class="outline-text-3" id="text-1-11">
<p>
In order to model a flexible element with only few mass-spring-damper elements:
</p>
<ul class="org-ul">
<li>FEM of the flexible element</li>
<li>Super-Element extraction</li>
<li>Parameters to extract
<ul class="org-ul">
<li>For the flexible joint: axial, shear, bending and torsion stiffnesses</li>
<li>For the APA: k1, ka, ke, c1</li>
</ul></li>
<li>This can be done directly from the Stiffness matrix or using identification from a simple Simscape model</li>
</ul>
</div>
</div>
<div id="outline-container-org55fe34f" class="outline-3">
<h3 id="org55fe34f"><span class="section-number-3">1.12</span> Conclusion</h3>
<div class="outline-text-3" id="text-1-12">
<div class="important" id="orgba069e0">
<p>
The results seems to indicate that the model is well represented with only few degrees of freedom.
This permit to have a relatively sane number of states for the model.
</p>
</div>
</div>
</div>
</div>
<div id="outline-container-org2d65f84" class="outline-2">
<h2 id="org2d65f84"><span class="section-number-2">2</span> Control with flexible elements</h2>
<div class="outline-text-2" id="text-2">
</div>
<div id="outline-container-org7f0d75c" class="outline-3">
<h3 id="org7f0d75c"><span class="section-number-3">2.1</span> Flexible APA and Flexible Joint</h3>
<div class="outline-text-3" id="text-2-1">
<div class="org-src-container">
<pre class="src src-matlab">apa = load(<span class="org-string">'./mat/APA300ML.mat'</span>, <span class="org-string">'int_xyz'</span>, <span class="org-string">'int_i'</span>, <span class="org-string">'n_xyz'</span>, <span class="org-string">'n_i'</span>, <span class="org-string">'nodes'</span>, <span class="org-string">'M'</span>, <span class="org-string">'K'</span>);
flex_joint = load(<span class="org-string">'./mat/flexor_ID16.mat'</span>, <span class="org-string">'int_xyz'</span>, <span class="org-string">'int_i'</span>, <span class="org-string">'n_xyz'</span>, <span class="org-string">'n_i'</span>, <span class="org-string">'nodes'</span>, <span class="org-string">'M'</span>, <span class="org-string">'K'</span>);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">stewart = initializeStewartPlatform();
stewart = initializeFramesPositions(stewart);
stewart = generateGeneralConfiguration(stewart);
stewart = computeJointsPose(stewart);
stewart = initializeFlexibleStrutDynamics(stewart, <span class="org-string">'H'</span>, 0.03, <span class="org-string">'K'</span>, apa.K, <span class="org-string">'M'</span>, apa.M, <span class="org-string">'n_xyz'</span>, apa.n_xyz, <span class="org-string">'xi'</span>, 0.1, <span class="org-string">'step_file'</span>, <span class="org-string">'mat/APA300ML.STEP'</span>);
stewart = initializeJointDynamics(stewart, <span class="org-string">'type_F'</span>, <span class="org-string">'flexible'</span>, <span class="org-string">'K_F'</span>, flex_joint.K, <span class="org-string">'M_F'</span>, flex_joint.M, <span class="org-string">'n_xyz_F'</span>, flex_joint.n_xyz, <span class="org-string">'xi_F'</span>, 0.1, <span class="org-string">'step_file_F'</span>, <span class="org-string">'mat/flexor_ID16.STEP'</span>, <span class="org-string">'type_M'</span>, <span class="org-string">'flexible'</span>, <span class="org-string">'K_M'</span>, flex_joint.K, <span class="org-string">'M_M'</span>, flex_joint.M, <span class="org-string">'n_xyz_M'</span>, flex_joint.n_xyz, <span class="org-string">'xi_M'</span>, 0.1, <span class="org-string">'step_file_M'</span>, <span class="org-string">'mat/flexor_ID16.STEP'</span>);
stewart = initializeCylindricalPlatforms(stewart);
stewart = initializeCylindricalStruts(stewart, <span class="org-string">'type_F'</span>, <span class="org-string">'none'</span>, <span class="org-string">'type_M'</span>, <span class="org-string">'none'</span>);
stewart = computeJacobian(stewart);
stewart = initializeStewartPose(stewart);
stewart = initializeInertialSensor(stewart);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">ground = initializeGround(<span class="org-string">'type'</span>, <span class="org-string">'none'</span>);
payload = initializePayload(<span class="org-string">'type'</span>, <span class="org-string">'rigid'</span>, <span class="org-string">'m'</span>, 50);
controller = initializeController(<span class="org-string">'type'</span>, <span class="org-string">'open-loop'</span>);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">disturbances = initializeDisturbances();
references = initializeReferences(stewart);
</pre>
</div>
</div>
</div>
<div id="outline-container-org5f84aea" class="outline-3">
<h3 id="org5f84aea"><span class="section-number-3">2.2</span> Identification</h3>
<div class="outline-text-3" id="text-2-2">
<p>
And we identify the dynamics from force actuators to force sensors.
</p>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Options for Linearized</span></span>
options = linearizeOptions;
options.SampleTime = 0;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Name of the Simulink File</span></span>
mdl = <span class="org-string">'stewart_platform_model'</span>;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Input/Output definition</span></span>
clear io; io_i = 1;
io(io_i) = linio([mdl, <span class="org-string">'/Controller'</span>], 1, <span class="org-string">'openinput'</span>); io_i = io_i <span class="org-type">+</span> 1; <span class="org-comment">% Actuator Force Inputs [N]</span>
io(io_i) = linio([mdl, <span class="org-string">'/Stewart Platform'</span>], 1, <span class="org-string">'openoutput'</span>, [], <span class="org-string">'dLm'</span>); io_i = io_i <span class="org-type">+</span> 1; <span class="org-comment">% Relative Displacement Outputs [m]</span>
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">G = <span class="org-type">-</span>linearize(mdl, io, options);
G.InputName = {<span class="org-string">'F1'</span>, <span class="org-string">'F2'</span>, <span class="org-string">'F3'</span>, <span class="org-string">'F4'</span>, <span class="org-string">'F5'</span>, <span class="org-string">'F6'</span>};
G.OutputName = {<span class="org-string">'Dm1'</span>, <span class="org-string">'Dm2'</span>, <span class="org-string">'Dm3'</span>, <span class="org-string">'Dm4'</span>, <span class="org-string">'Dm5'</span>, <span class="org-string">'Dm6'</span>};
</pre>
</div>
</div>
</div>
<div id="outline-container-org5ae25be" class="outline-3">
<h3 id="org5ae25be"><span class="section-number-3">2.3</span> Decentralized Direct Velocity Feedback</h3>
<div class="outline-text-3" id="text-2-3">
<p>
Controller Design
</p>
<div class="org-src-container">
<pre class="src src-matlab">Kl = <span class="org-type">-</span>1e5<span class="org-type">*</span>s<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>2e2)<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>5e2) <span class="org-type">*</span> eye(6);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">isstable(feedback(G(1<span class="org-type">:</span>6,1<span class="org-type">:</span>6)<span class="org-type">*</span>Kl, eye(6), <span class="org-type">-</span>1))
</pre>
</div>
<pre class="example">
1
</pre>
</div>
</div>
<div id="outline-container-org3d014d0" class="outline-3">
<h3 id="org3d014d0"><span class="section-number-3">2.4</span> HAC</h3>
<div class="outline-text-3" id="text-2-4">
<div class="org-src-container">
<pre class="src src-matlab">Kx = tf(zeros(6));
controller = initializeController(<span class="org-string">'type'</span>, <span class="org-string">'ref-track-hac-dvf'</span>);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Name of the Simulink File</span></span>
mdl = <span class="org-string">'stewart_platform_model'</span>;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Input/Output definition</span></span>
clear io; io_i = 1;
io(io_i) = linio([mdl, <span class="org-string">'/Controller'</span>], 1, <span class="org-string">'input'</span>); io_i = io_i <span class="org-type">+</span> 1; <span class="org-comment">% Actuator Force Inputs [N]</span>
io(io_i) = linio([mdl, <span class="org-string">'/Relative Motion Sensor'</span>], 1, <span class="org-string">'openoutput'</span>); io_i = io_i <span class="org-type">+</span> 1; <span class="org-comment">% Relative Displacement Outputs [m]</span>
<span class="org-matlab-cellbreak"><span class="org-comment">%% Run the linearization</span></span>
G = linearize(mdl, io);
G.InputName = {<span class="org-string">'F1'</span>, <span class="org-string">'F2'</span>, <span class="org-string">'F3'</span>, <span class="org-string">'F4'</span>, <span class="org-string">'F5'</span>, <span class="org-string">'F6'</span>};
G.OutputName = {<span class="org-string">'Dx'</span>, <span class="org-string">'Dy'</span>, <span class="org-string">'Dz'</span>, <span class="org-string">'Rx'</span>, <span class="org-string">'Ry'</span>, <span class="org-string">'Rz'</span>};
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">Gl = <span class="org-type">-</span>stewart.kinematics.J<span class="org-type">*</span>G;
Gl.OutputName = {<span class="org-string">'D1'</span>, <span class="org-string">'D2'</span>, <span class="org-string">'D3'</span>, <span class="org-string">'D4'</span>, <span class="org-string">'D5'</span>, <span class="org-string">'D6'</span>};
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">wc = 2<span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">*</span>300;
Kl = diag(1<span class="org-type">./</span>diag(abs(freqresp(Gl, wc)))) <span class="org-type">*</span> wc<span class="org-type">/</span>s <span class="org-type">*</span> 1<span class="org-type">/</span>(1 <span class="org-type">+</span> s<span class="org-type">/</span>3<span class="org-type">/</span>wc);
</pre>
</div>
</div>
</div>
</div>
<div id="outline-container-org2b937bc" class="outline-2">
<h2 id="org2b937bc"><span class="section-number-2">3</span> Flexible Joint Specifications</h2>
<div class="outline-text-2" id="text-3">
</div>
<div id="outline-container-org775a387" class="outline-3">
<h3 id="org775a387"><span class="section-number-3">3.1</span> Stewart Platform Initialization</h3>
<div class="outline-text-3" id="text-3-1">
<div class="org-src-container">
<pre class="src src-matlab">stewart = initializeStewartPlatform();
stewart = initializeFramesPositions(stewart);
stewart = generateGeneralConfiguration(stewart);
stewart = computeJointsPose(stewart);
stewart = initializeAmplifiedStrutDynamics(stewart, <span class="org-string">'Ke'</span>, 1.5e6<span class="org-type">*</span>ones(6,1), <span class="org-string">'Ka'</span>, 43e6<span class="org-type">*</span>ones(6,1), <span class="org-string">'K1'</span>, 0.4e6<span class="org-type">*</span>ones(6,1), <span class="org-string">'C1'</span>, 10<span class="org-type">*</span>ones(6,1));
stewart = initializeCylindricalPlatforms(stewart);
stewart = initializeCylindricalStruts(stewart);
stewart = computeJacobian(stewart);
stewart = initializeStewartPose(stewart);
stewart = initializeInertialSensor(stewart);
references = initializeReferences(stewart);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">ground = initializeGround(<span class="org-string">'type'</span>, <span class="org-string">'none'</span>);
payload = initializePayload(<span class="org-string">'type'</span>, <span class="org-string">'rigid'</span>, <span class="org-string">'m'</span>, 50);
controller = initializeController(<span class="org-string">'type'</span>, <span class="org-string">'open-loop'</span>);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">disturbances = initializeDisturbances();
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">open(<span class="org-string">'stewart_platform_model.slx'</span>)
</pre>
</div>
</div>
</div>
<div id="outline-container-orgc430963" class="outline-3">
<h3 id="orgc430963"><span class="section-number-3">3.2</span> Effect of the Bending Stiffness</h3>
<div class="outline-text-3" id="text-3-2">
<div class="org-src-container">
<pre class="src src-matlab">Kfs = [1, 10, 100, 1000]; <span class="org-comment">% [Nm/rad]</span>
</pre>
</div>
</div>
</div>
<div id="outline-container-orgb29824b" class="outline-3">
<h3 id="orgb29824b"><span class="section-number-3">3.3</span> Effect of the Torsion Stiffness</h3>
<div class="outline-text-3" id="text-3-3">
<div class="org-src-container">
<pre class="src src-matlab">Kts = [10, 100, 500, 1000]; <span class="org-comment">% [Nm/rad]</span>
</pre>
</div>
</div>
</div>
<div id="outline-container-org6d029b0" class="outline-3">
<h3 id="org6d029b0"><span class="section-number-3">3.4</span> Effect of the Axial Stiffness</h3>
<div class="outline-text-3" id="text-3-4">
<div class="org-src-container">
<pre class="src src-matlab">Kas = [1e6, 1e7, 1e8, 5e8, 1e9]; <span class="org-comment">% [N/m]</span>
</pre>
</div>
</div>
</div>
<div id="outline-container-org5177329" class="outline-3">
<h3 id="org5177329"><span class="section-number-3">3.5</span> Effect of the Radial (Shear) Stiffness</h3>
<div class="outline-text-3" id="text-3-5">
<div class="org-src-container">
<pre class="src src-matlab">Krs = [1e4, 1e5, 1e6, 1e7]; <span class="org-comment">% [N/m]</span>
</pre>
</div>
</div>
</div>
<div id="outline-container-orge0f8240" class="outline-3">
<h3 id="orge0f8240"><span class="section-number-3">3.6</span> Comparison of perfect joint and worst specified joint</h3>
</div>
<div id="outline-container-org79b6e2d" class="outline-3">
<h3 id="org79b6e2d"><span class="section-number-3">3.7</span> Conclusion</h3>
<div class="outline-text-3" id="text-3-7">
<p>
Qualitatively:
</p>
<table border="2" cellspacing="0" cellpadding="6" rules="groups" frame="hsides">
<colgroup>
<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>Specification</b></th>
</tr>
</thead>
<tbody>
<tr>
<td class="org-left">Axial Stiffness</td>
<td class="org-left">Much larger than the Actuator axial stiffness</td>
</tr>
<tr>
<td class="org-left">Shear Stiffness</td>
<td class="org-left">&#xa0;</td>
</tr>
<tr>
<td class="org-left">Bending Stiffness</td>
<td class="org-left">Much smaller than the Actuator bending stiffness</td>
</tr>
<tr>
<td class="org-left">Torsion Stiffness</td>
<td class="org-left">&#xa0;</td>
</tr>
</tbody>
</table>
<p>
Quantitatively:
</p>
<table border="2" cellspacing="0" cellpadding="6" rules="groups" frame="hsides">
<colgroup>
<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>Specification</b></th>
</tr>
</thead>
<tbody>
<tr>
<td class="org-left">Axial Stiffness</td>
<td class="org-left">&gt; 200 [N/um]</td>
</tr>
<tr>
<td class="org-left">Shear Stiffness</td>
<td class="org-left">&gt; 1 [N/um]</td>
</tr>
<tr>
<td class="org-left">Bending Stiffness</td>
<td class="org-left">&lt; 100 [Nm/rad]</td>
</tr>
<tr>
<td class="org-left">Torsion Stiffness</td>
<td class="org-left">&lt; 500 [Nm/rad]</td>
</tr>
</tbody>
</table>
</div>
</div>
</div>
<div id="outline-container-org8798d60" class="outline-2">
<h2 id="org8798d60"><span class="section-number-2">4</span> Flexible Joint Specifications with the APA300ML</h2>
<div class="outline-text-2" id="text-4">
</div>
<div id="outline-container-org6d56b33" class="outline-3">
<h3 id="org6d56b33"><span class="section-number-3">4.1</span> Stewart Platform Initialization</h3>
<div class="outline-text-3" id="text-4-1">
<div class="org-src-container">
<pre class="src src-matlab">apa = load(<span class="org-string">'./mat/APA300ML.mat'</span>, <span class="org-string">'int_xyz'</span>, <span class="org-string">'int_i'</span>, <span class="org-string">'n_xyz'</span>, <span class="org-string">'n_i'</span>, <span class="org-string">'nodes'</span>, <span class="org-string">'M'</span>, <span class="org-string">'K'</span>);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">stewart = initializeStewartPlatform();
stewart = initializeFramesPositions(stewart);
stewart = generateGeneralConfiguration(stewart);
stewart = computeJointsPose(stewart);
stewart = initializeFlexibleStrutDynamics(stewart, <span class="org-string">'H'</span>, 0.03, <span class="org-string">'K'</span>, apa.K, <span class="org-string">'M'</span>, apa.M, <span class="org-string">'n_xyz'</span>, apa.n_xyz, <span class="org-string">'xi'</span>, 0.1, <span class="org-string">'step_file'</span>, <span class="org-string">'mat/APA300ML.STEP'</span>);
stewart = initializeCylindricalPlatforms(stewart);
stewart = initializeCylindricalStruts(stewart, <span class="org-string">'type_F'</span>, <span class="org-string">'none'</span>, <span class="org-string">'type_M'</span>, <span class="org-string">'none'</span>);
stewart = computeJacobian(stewart);
stewart = initializeStewartPose(stewart);
stewart = initializeInertialSensor(stewart);
references = initializeReferences(stewart);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">ground = initializeGround(<span class="org-string">'type'</span>, <span class="org-string">'none'</span>);
payload = initializePayload(<span class="org-string">'type'</span>, <span class="org-string">'rigid'</span>, <span class="org-string">'m'</span>, 50);
controller = initializeController(<span class="org-string">'type'</span>, <span class="org-string">'open-loop'</span>);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">disturbances = initializeDisturbances();
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">open(<span class="org-string">'stewart_platform_model.slx'</span>)
</pre>
</div>
</div>
</div>
<div id="outline-container-orgdc3d576" class="outline-3">
<h3 id="orgdc3d576"><span class="section-number-3">4.2</span> Comparison of perfect joint and worst specified joint</h3>
</div>
</div>
<div id="outline-container-orgbae1ad3" class="outline-2">
<h2 id="orgbae1ad3"><span class="section-number-2">5</span> Relative Motion Sensors</h2>
<div class="outline-text-2" id="text-5">
</div>
<div id="outline-container-org74f7ec9" class="outline-3">
<h3 id="org74f7ec9"><span class="section-number-3">5.1</span> Stewart Platform Initialization</h3>
<div class="outline-text-3" id="text-5-1">
<div class="org-src-container">
<pre class="src src-matlab">stewart = initializeStewartPlatform();
stewart = initializeFramesPositions(stewart);
stewart = generateGeneralConfiguration(stewart);
stewart = computeJointsPose(stewart);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">apa = load(<span class="org-string">'./mat/APA300ML.mat'</span>, <span class="org-string">'int_xyz'</span>, <span class="org-string">'int_i'</span>, <span class="org-string">'n_xyz'</span>, <span class="org-string">'n_i'</span>, <span class="org-string">'nodes'</span>, <span class="org-string">'M'</span>, <span class="org-string">'K'</span>);
stewart = initializeAmplifiedStrutDynamics(stewart, <span class="org-string">'Ke'</span>, 1.5e6<span class="org-type">*</span>ones(6,1), <span class="org-string">'Ka'</span>, 40.5e6<span class="org-type">*</span>ones(6,1), <span class="org-string">'K1'</span>, 0.4e6<span class="org-type">*</span>ones(6,1));
<span class="org-comment">% stewart = initializeFlexibleStrutDynamics(stewart, 'H', 0.03, 'K', apa.K, 'M', apa.M, 'n_xyz', apa.n_xyz, 'xi', 0.1, 'step_file', 'mat/APA300ML.STEP');</span>
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">flex_joint = load(<span class="org-string">'./mat/flexor_025.mat'</span>, <span class="org-string">'int_xyz'</span>, <span class="org-string">'int_i'</span>, <span class="org-string">'n_xyz'</span>, <span class="org-string">'n_i'</span>, <span class="org-string">'nodes'</span>, <span class="org-string">'M'</span>, <span class="org-string">'K'</span>);
stewart = initializeJointDynamics(stewart, <span class="org-string">'type_M'</span>, <span class="org-string">'spherical_3dof'</span>, ...
<span class="org-string">'Kr_M'</span>, flex_joint.K(1,1)<span class="org-type">*</span>ones(6,1), ...
<span class="org-string">'Ka_M'</span>, flex_joint.K(3,3)<span class="org-type">*</span>ones(6,1), ...
<span class="org-string">'Kf_M'</span>, flex_joint.K(4,4)<span class="org-type">*</span>ones(6,1), ...
<span class="org-string">'Kt_M'</span>, flex_joint.K(6,6)<span class="org-type">*</span>ones(6,1), ...
<span class="org-string">'type_F'</span>, <span class="org-string">'universal_3dof'</span>, ...
<span class="org-string">'Kr_F'</span>, flex_joint.K(1,1)<span class="org-type">*</span>ones(6,1), ...
<span class="org-string">'Ka_F'</span>, flex_joint.K(3,3)<span class="org-type">*</span>ones(6,1), ...
<span class="org-string">'Kf_F'</span>, flex_joint.K(4,4)<span class="org-type">*</span>ones(6,1), ...
<span class="org-string">'Kt_F'</span>, flex_joint.K(6,6)<span class="org-type">*</span>ones(6,1));
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">stewart = initializeCylindricalPlatforms(stewart);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">stewart = initializeCylindricalStruts(stewart);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">stewart = computeJacobian(stewart);
stewart = initializeStewartPose(stewart);
stewart = initializeInertialSensor(stewart);
references = initializeReferences(stewart);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">ground = initializeGround(<span class="org-string">'type'</span>, <span class="org-string">'none'</span>);
payload = initializePayload(<span class="org-string">'type'</span>, <span class="org-string">'rigid'</span>, <span class="org-string">'m'</span>, 50);
controller = initializeController(<span class="org-string">'type'</span>, <span class="org-string">'open-loop'</span>);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">disturbances = initializeDisturbances();
</pre>
</div>
</div>
</div>
</div>
<div id="outline-container-orgb454975" class="outline-2">
<h2 id="orgb454975"><span class="section-number-2">6</span> Struts with Encoders</h2>
<div class="outline-text-2" id="text-6">
</div>
<div id="outline-container-org6bde940" class="outline-3">
<h3 id="org6bde940"><span class="section-number-3">6.1</span> Flexible Strut</h3>
<div class="outline-text-3" id="text-6-1">
<div class="org-src-container">
<pre class="src src-matlab">apa = load(<span class="org-string">'./mat/strut_encoder.mat'</span>, <span class="org-string">'int_xyz'</span>, <span class="org-string">'int_i'</span>, <span class="org-string">'n_xyz'</span>, <span class="org-string">'n_i'</span>, <span class="org-string">'nodes'</span>, <span class="org-string">'M'</span>, <span class="org-string">'K'</span>);
</pre>
</div>
<table border="2" cellspacing="0" cellpadding="6" rules="groups" frame="hsides">
<colgroup>
<col class="org-left" />
<col class="org-right" />
</colgroup>
<tbody>
<tr>
<td class="org-left">Total number of Nodes</td>
<td class="org-right">8</td>
</tr>
<tr>
<td class="org-left">Number of interface Nodes</td>
<td class="org-right">8</td>
</tr>
<tr>
<td class="org-left">Number of Modes</td>
<td class="org-right">6</td>
</tr>
<tr>
<td class="org-left">Size of M and K matrices</td>
<td class="org-right">54</td>
</tr>
</tbody>
</table>
<table border="2" cellspacing="0" cellpadding="6" rules="groups" frame="hsides">
<caption class="t-above"><span class="table-number">Table 3:</span> Coordinates of the interface nodes</caption>
<colgroup>
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
</colgroup>
<thead>
<tr>
<th scope="col" class="org-right">Node i</th>
<th scope="col" class="org-right">Node Number</th>
<th scope="col" class="org-right">x [m]</th>
<th scope="col" class="org-right">y [m]</th>
<th scope="col" class="org-right">z [m]</th>
</tr>
</thead>
<tbody>
<tr>
<td class="org-right">1.0</td>
<td class="org-right">504411.0</td>
<td class="org-right">0.0</td>
<td class="org-right">0.0</td>
<td class="org-right">0.0405</td>
</tr>
<tr>
<td class="org-right">2.0</td>
<td class="org-right">504412.0</td>
<td class="org-right">0.0</td>
<td class="org-right">0.0</td>
<td class="org-right">-0.0405</td>
</tr>
<tr>
<td class="org-right">3.0</td>
<td class="org-right">504413.0</td>
<td class="org-right">-0.0325</td>
<td class="org-right">0.0</td>
<td class="org-right">0.0</td>
</tr>
<tr>
<td class="org-right">4.0</td>
<td class="org-right">504414.0</td>
<td class="org-right">-0.0125</td>
<td class="org-right">0.0</td>
<td class="org-right">0.0</td>
</tr>
<tr>
<td class="org-right">5.0</td>
<td class="org-right">504415.0</td>
<td class="org-right">-0.0075</td>
<td class="org-right">0.0</td>
<td class="org-right">0.0</td>
</tr>
<tr>
<td class="org-right">6.0</td>
<td class="org-right">504416.0</td>
<td class="org-right">0.0325</td>
<td class="org-right">0.0</td>
<td class="org-right">0.0</td>
</tr>
<tr>
<td class="org-right">7.0</td>
<td class="org-right">504417.0</td>
<td class="org-right">0.004</td>
<td class="org-right">0.0145</td>
<td class="org-right">-0.00175</td>
</tr>
<tr>
<td class="org-right">8.0</td>
<td class="org-right">504418.0</td>
<td class="org-right">0.004</td>
<td class="org-right">0.0166</td>
<td class="org-right">-0.00175</td>
</tr>
</tbody>
</table>
</div>
</div>
<div id="outline-container-org4b369e6" class="outline-3">
<h3 id="org4b369e6"><span class="section-number-3">6.2</span> Stewart Platform</h3>
<div class="outline-text-3" id="text-6-2">
<div class="org-src-container">
<pre class="src src-matlab">stewart = initializeStewartPlatform();
stewart = initializeFramesPositions(stewart, <span class="org-string">'H'</span>, 95e<span class="org-type">-</span>3, <span class="org-string">'MO_B'</span>, 220e<span class="org-type">-</span>3);
stewart = generateGeneralConfiguration(stewart, <span class="org-string">'FH'</span>, 22.5e<span class="org-type">-</span>3, <span class="org-string">'FR'</span>, 114e<span class="org-type">-</span>3, <span class="org-string">'FTh'</span>, [ <span class="org-type">-</span>11, 11, 120<span class="org-type">-</span>11, 120<span class="org-type">+</span>11, 240<span class="org-type">-</span>11, 240<span class="org-type">+</span>11]<span class="org-type">*</span>(<span class="org-constant">pi</span><span class="org-type">/</span>180), ...
<span class="org-string">'MH'</span>, 22.5e<span class="org-type">-</span>3, <span class="org-string">'MR'</span>, 110e<span class="org-type">-</span>3, <span class="org-string">'MTh'</span>, [<span class="org-type">-</span>60<span class="org-type">+</span>15, 60<span class="org-type">-</span>15, 60<span class="org-type">+</span>15, 180<span class="org-type">-</span>15, 180<span class="org-type">+</span>15, <span class="org-type">-</span>60<span class="org-type">-</span>15]<span class="org-type">*</span>(<span class="org-constant">pi</span><span class="org-type">/</span>180));
stewart = computeJointsPose(stewart);
stewart = initializeFlexibleStrutAndJointDynamics(stewart, <span class="org-string">'H'</span>, (apa.int_xyz(1,3) <span class="org-type">-</span> apa.int_xyz(2,3)), ...
<span class="org-string">'K'</span>, apa.K, ...
<span class="org-string">'M'</span>, apa.M, ...
<span class="org-string">'n_xyz'</span>, apa.n_xyz, ...
<span class="org-string">'xi'</span>, 0.1, ...
<span class="org-string">'Gf'</span>, <span class="org-type">-</span>2.65e7, ...
<span class="org-string">'step_file'</span>, <span class="org-string">'mat/APA300ML.STEP'</span>);
stewart = initializeSolidPlatforms(stewart);
stewart = initializeCylindricalStruts(stewart, <span class="org-string">'type_F'</span>, <span class="org-string">'none'</span>, <span class="org-string">'type_M'</span>, <span class="org-string">'none'</span>);
stewart = computeJacobian(stewart);
stewart = initializeStewartPose(stewart);
stewart = initializeInertialSensor(stewart);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab">disturbances = initializeDisturbances();
ground = initializeGround(<span class="org-string">'type'</span>, <span class="org-string">'none'</span>);
payload = initializePayload(<span class="org-string">'type'</span>, <span class="org-string">'rigid'</span>, <span class="org-string">'m'</span>, 1);
controller = initializeController(<span class="org-string">'type'</span>, <span class="org-string">'open-loop'</span>);
references = initializeReferences(stewart);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Options for Linearized</span></span>
options = linearizeOptions;
options.SampleTime = 0;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Name of the Simulink File</span></span>
mdl = <span class="org-string">'stewart_platform_model'</span>;
<span class="org-matlab-cellbreak"><span class="org-comment">%% Input/Output definition</span></span>
clear io; io_i = 1;
io(io_i) = linio([mdl, <span class="org-string">'/Controller'</span>], 1, <span class="org-string">'openinput'</span>); io_i = io_i <span class="org-type">+</span> 1; <span class="org-comment">% Actuator Force Inputs [N]</span>
io(io_i) = linio([mdl, <span class="org-string">'/Stewart Platform'</span>], 1, <span class="org-string">'openoutput'</span>, [], <span class="org-string">'dLm'</span>); io_i = io_i <span class="org-type">+</span> 1; <span class="org-comment">% Relative Displacement Outputs [m]</span>
io(io_i) = linio([mdl, <span class="org-string">'/Stewart Platform'</span>], 1, <span class="org-string">'openoutput'</span>, [], <span class="org-string">'Lm'</span>); io_i = io_i <span class="org-type">+</span> 1; <span class="org-comment">% Force Sensors [N]</span>
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-matlab-cellbreak"><span class="org-comment">%% Run the linearization</span></span>
G = linearize(mdl, io, options);
G.InputName = {<span class="org-string">'F1'</span>, <span class="org-string">'F2'</span>, <span class="org-string">'F3'</span>, <span class="org-string">'F4'</span>, <span class="org-string">'F5'</span>, <span class="org-string">'F6'</span>};
G.OutputName = {<span class="org-string">'Dm1'</span>, <span class="org-string">'Dm2'</span>, <span class="org-string">'Dm3'</span>, <span class="org-string">'Dm4'</span>, <span class="org-string">'Dm5'</span>, <span class="org-string">'Dm6'</span>, ...
<span class="org-string">'D1'</span>, <span class="org-string">'D2'</span>, <span class="org-string">'D3'</span>, <span class="org-string">'D4'</span>, <span class="org-string">'D5'</span>, <span class="org-string">'D6'</span>};
</pre>
</div>
<div id="org3e13f39" class="figure">
<p><img src="figs/comp_relative_motion_sensor_act_leg_encoder.png" alt="comp_relative_motion_sensor_act_leg_encoder.png" />
</p>
</div>
</div>
</div>
</div>
</div>
<div id="postamble" class="status">
<p class="author">Author: Dehaeze Thomas</p>
<p class="date">Created: 2021-01-08 ven. 15:52</p>
</div>
</body>
</html>