[DONE] Files are now compliant with the new model

This commit is contained in:
Thomas Dehaeze 2020-02-13 15:48:42 +01:00
parent c947ed116f
commit d12891df43
2 changed files with 68 additions and 63 deletions

View File

@ -4,7 +4,7 @@
"http://www.w3.org/TR/xhtml1/DTD/xhtml1-strict.dtd">
<html xmlns="http://www.w3.org/1999/xhtml" lang="en" xml:lang="en">
<head>
<!-- 2020-02-11 mar. 17:50 -->
<!-- 2020-02-12 mer. 10:22 -->
<meta http-equiv="Content-Type" content="text/html;charset=utf-8" />
<meta name="viewport" content="width=device-width, initial-scale=1" />
<title>Kinematic Study of the Stewart Platform</title>
@ -287,7 +287,7 @@ for the JavaScript code in this tag.
<li><a href="#org5a3ce80">3.3. Approximate solution of the Forward and Inverse Kinematic problem for small displacement using the Jacobian matrix</a></li>
<li><a href="#org86b4b35">3.4. Estimation of the range validity of the approximate inverse kinematics</a>
<ul>
<li><a href="#org8be231b">3.4.1. Stewart architecture definition</a></li>
<li><a href="#orgc3c7024">3.4.1. Stewart architecture definition</a></li>
<li><a href="#orgd83ccf3">3.4.2. Comparison for &ldquo;pure&rdquo; translations</a></li>
<li><a href="#org4871c83">3.4.3. Conclusion</a></li>
</ul>
@ -296,7 +296,7 @@ for the JavaScript code in this tag.
</li>
<li><a href="#org63255f9">4. Estimated required actuator stroke from specified platform mobility</a>
<ul>
<li><a href="#org4d97075">4.1. Stewart architecture definition</a></li>
<li><a href="#orgea4978b">4.1. Stewart architecture definition</a></li>
<li><a href="#orgde50dd3">4.2. Wanted translations and rotations</a></li>
<li><a href="#org24e45ca">4.3. Needed stroke for &ldquo;pure&rdquo; rotations or translations</a></li>
<li><a href="#orgf6ba90c">4.4. Needed stroke for &ldquo;combined&rdquo; rotations or translations</a></li>
@ -304,7 +304,7 @@ for the JavaScript code in this tag.
</li>
<li><a href="#orgbbbf7b3">5. Estimated platform mobility from specified actuator stroke</a>
<ul>
<li><a href="#orgc3c7024">5.1. Stewart architecture definition</a></li>
<li><a href="#orgbecdc67">5.1. Stewart architecture definition</a></li>
<li><a href="#org2c6819e">5.2. Pure translations</a></li>
</ul>
</li>
@ -312,8 +312,8 @@ for the JavaScript code in this tag.
<ul>
<li><a href="#org26e8b28">6.1. <code>computeJacobian</code>: Compute the Jacobian Matrix</a>
<ul>
<li><a href="#orgdfb3b70">Function description</a></li>
<li><a href="#org14aeafc">Check the <code>stewart</code> structure elements</a></li>
<li><a href="#org1a620fe">Function description</a></li>
<li><a href="#org9c3aa33">Check the <code>stewart</code> structure elements</a></li>
<li><a href="#org0cd57b5">Compute Jacobian Matrix</a></li>
<li><a href="#orge21dcfc">Compute Stiffness Matrix</a></li>
<li><a href="#orgae76071">Compute Compliance Matrix</a></li>
@ -323,17 +323,17 @@ for the JavaScript code in this tag.
<li><a href="#orgb82066f">6.2. <code>inverseKinematics</code>: Compute Inverse Kinematics</a>
<ul>
<li><a href="#org89930b7">Theory</a></li>
<li><a href="#orgfe68a5b">Function description</a></li>
<li><a href="#org7a9a427">Optional Parameters</a></li>
<li><a href="#org27c8a3f">Check the <code>stewart</code> structure elements</a></li>
<li><a href="#orgd97252a">Function description</a></li>
<li><a href="#org7be1dc4">Optional Parameters</a></li>
<li><a href="#orga7b29d7">Check the <code>stewart</code> structure elements</a></li>
<li><a href="#org0d64c23">Compute</a></li>
</ul>
</li>
<li><a href="#orgf5d8f0b">6.3. <code>forwardKinematicsApprox</code>: Compute the Approximate Forward Kinematics</a>
<ul>
<li><a href="#org1a620fe">Function description</a></li>
<li><a href="#org7be1dc4">Optional Parameters</a></li>
<li><a href="#org9c3aa33">Check the <code>stewart</code> structure elements</a></li>
<li><a href="#org1a280b0">Function description</a></li>
<li><a href="#orge4b0020">Optional Parameters</a></li>
<li><a href="#org08a6ec5">Check the <code>stewart</code> structure elements</a></li>
<li><a href="#orge5ade24">Computation</a></li>
</ul>
</li>
@ -666,8 +666,8 @@ This will also gives us the range for which the approximate forward kinematic is
</p>
</div>
<div id="outline-container-org8be231b" class="outline-4">
<h4 id="org8be231b"><span class="section-number-4">3.4.1</span> Stewart architecture definition</h4>
<div id="outline-container-orgc3c7024" class="outline-4">
<h4 id="orgc3c7024"><span class="section-number-4">3.4.1</span> Stewart architecture definition</h4>
<div class="outline-text-4" id="text-3-4-1">
<p>
We first define some general Stewart architecture.
@ -708,7 +708,7 @@ Ls_exact = zeros(6, length(Xrs));
<span class="org-keyword">for</span> <span class="org-variable-name"><span class="org-constant">i</span></span> = <span class="org-constant">1:length(Xrs)</span>
Xr = Xrs(<span class="org-constant">i</span>);
L_approx(<span class="org-type">:</span>, <span class="org-constant">i</span>) = stewart.J<span class="org-type">*</span>[Xr; 0; 0; 0; 0; 0;];
L_approx(<span class="org-type">:</span>, <span class="org-constant">i</span>) = stewart.kinematics.J<span class="org-type">*</span>[Xr; 0; 0; 0; 0; 0;];
[<span class="org-type">~</span>, L_exact(<span class="org-type">:</span>, <span class="org-constant">i</span>)] = inverseKinematics(stewart, <span class="org-string">'AP'</span>, [Xr; 0; 0]);
<span class="org-keyword">end</span>
</pre>
@ -733,9 +733,12 @@ Ls_exact = zeros(6, length(Xrs));
<div id="outline-container-org4871c83" class="outline-4">
<h4 id="org4871c83"><span class="section-number-4">3.4.3</span> Conclusion</h4>
<div class="outline-text-4" id="text-3-4-3">
<div class="important">
<p>
For small wanted displacements (up to \(\approx 1\%\) of the size of the Hexapod), the approximate inverse kinematic solution using the Jacobian matrix is quite correct.
</p>
</div>
</div>
</div>
</div>
@ -753,8 +756,8 @@ One may want to determine the required actuator stroke required to obtain the sp
This is what is analyzed in this section.
</p>
</div>
<div id="outline-container-org4d97075" class="outline-3">
<h3 id="org4d97075"><span class="section-number-3">4.1</span> Stewart architecture definition</h3>
<div id="outline-container-orgea4978b" class="outline-3">
<h3 id="orgea4978b"><span class="section-number-3">4.1</span> Stewart architecture definition</h3>
<div class="outline-text-3" id="text-4-1">
<p>
Let&rsquo;s first define the Stewart platform architecture that we want to study.
@ -767,7 +770,7 @@ stewart = computeJointsPose(stewart);
stewart = initializeStewartPose(stewart);
stewart = initializeCylindricalPlatforms(stewart);
stewart = initializeCylindricalStruts(stewart);
stewart = initializeStrutDynamics(stewart, <span class="org-string">'Ki'</span>, 1e6<span class="org-type">*</span>ones(6,1), <span class="org-string">'Ci'</span>, 1e2<span class="org-type">*</span>ones(6,1));
stewart = initializeStrutDynamics(stewart);
stewart = initializeJointDynamics(stewart);
stewart = computeJacobian(stewart);
</pre>
@ -802,12 +805,12 @@ We do that using either the Inverse Kinematic solution or the Jacobian matrix as
</p>
<div class="org-src-container">
<pre class="src src-matlab">LTx = stewart.J<span class="org-type">*</span>[Tx_max 0 0 0 0 0]<span class="org-type">'</span>;
LTy = stewart.J<span class="org-type">*</span>[0 Ty_max 0 0 0 0]<span class="org-type">'</span>;
LTz = stewart.J<span class="org-type">*</span>[0 0 Tz_max 0 0 0]<span class="org-type">'</span>;
LRx = stewart.J<span class="org-type">*</span>[0 0 0 Rx_max 0 0]<span class="org-type">'</span>;
LRy = stewart.J<span class="org-type">*</span>[0 0 0 0 Ry_max 0]<span class="org-type">'</span>;
LRz = stewart.J<span class="org-type">*</span>[0 0 0 0 0 Rz_max]<span class="org-type">'</span>;
<pre class="src src-matlab">LTx = stewart.kinematics.J<span class="org-type">*</span>[Tx_max 0 0 0 0 0]<span class="org-type">'</span>;
LTy = stewart.kinematics.J<span class="org-type">*</span>[0 Ty_max 0 0 0 0]<span class="org-type">'</span>;
LTz = stewart.kinematics.J<span class="org-type">*</span>[0 0 Tz_max 0 0 0]<span class="org-type">'</span>;
LRx = stewart.kinematics.J<span class="org-type">*</span>[0 0 0 Rx_max 0 0]<span class="org-type">'</span>;
LRy = stewart.kinematics.J<span class="org-type">*</span>[0 0 0 0 Ry_max 0]<span class="org-type">'</span>;
LRz = stewart.kinematics.J<span class="org-type">*</span>[0 0 0 0 0 Rz_max]<span class="org-type">'</span>;
</pre>
</div>
@ -1161,8 +1164,8 @@ As explained in section <a href="#orgca82bb8">3</a>, the forward kinematic probl
However, for small displacements, we can use the Jacobian as an approximate solution.
</p>
</div>
<div id="outline-container-orgc3c7024" class="outline-3">
<h3 id="orgc3c7024"><span class="section-number-3">5.1</span> Stewart architecture definition</h3>
<div id="outline-container-orgbecdc67" class="outline-3">
<h3 id="orgbecdc67"><span class="section-number-3">5.1</span> Stewart architecture definition</h3>
<div class="outline-text-3" id="text-5-1">
<p>
Let&rsquo;s first define the Stewart platform architecture that we want to study.
@ -1175,7 +1178,7 @@ stewart = computeJointsPose(stewart);
stewart = initializeStewartPose(stewart);
stewart = initializeCylindricalPlatforms(stewart);
stewart = initializeCylindricalStruts(stewart);
stewart = initializeStrutDynamics(stewart, <span class="org-string">'Ki'</span>, 1e6<span class="org-type">*</span>ones(6,1), <span class="org-string">'Ci'</span>, 1e2<span class="org-type">*</span>ones(6,1));
stewart = initializeStrutDynamics(stewart);
stewart = initializeJointDynamics(stewart);
stewart = computeJacobian(stewart);
</pre>
@ -1224,7 +1227,7 @@ rs = zeros(length(thetas), length(phis));
Ty = sin(thetas(<span class="org-constant">i</span>))<span class="org-type">*</span>sin(phis(<span class="org-constant">j</span>));
Tz = cos(thetas(<span class="org-constant">i</span>));
dL = stewart.J<span class="org-type">*</span>[Tx; Ty; Tz; 0; 0; 0;]; <span class="org-comment">% dL required for 1m displacement in theta/phi direction</span>
dL = stewart.kinematics.J<span class="org-type">*</span>[Tx; Ty; Tz; 0; 0; 0;]; <span class="org-comment">% dL required for 1m displacement in theta/phi direction</span>
rs(<span class="org-constant">i</span>, <span class="org-constant">j</span>) = max([dL(dL<span class="org-type">&lt;</span>0)<span class="org-type">*</span>L_min; dL(dL<span class="org-type">&gt;</span>0)<span class="org-type">*</span>L_max]);
<span class="org-keyword">end</span>
@ -1293,9 +1296,9 @@ This Matlab function is accessible <a href="../src/computeJacobian.m">here</a>.
</p>
</div>
<div id="outline-container-orgdfb3b70" class="outline-4">
<h4 id="orgdfb3b70">Function description</h4>
<div class="outline-text-4" id="text-orgdfb3b70">
<div id="outline-container-org1a620fe" class="outline-4">
<h4 id="org1a620fe">Function description</h4>
<div class="outline-text-4" id="text-org1a620fe">
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-keyword">function</span> <span class="org-variable-name">[stewart]</span> = <span class="org-function-name">computeJacobian</span>(<span class="org-variable-name">stewart</span>)
<span class="org-comment">% computeJacobian -</span>
@ -1318,9 +1321,9 @@ This Matlab function is accessible <a href="../src/computeJacobian.m">here</a>.
</div>
</div>
<div id="outline-container-org14aeafc" class="outline-4">
<h4 id="org14aeafc">Check the <code>stewart</code> structure elements</h4>
<div class="outline-text-4" id="text-org14aeafc">
<div id="outline-container-org9c3aa33" class="outline-4">
<h4 id="org9c3aa33">Check the <code>stewart</code> structure elements</h4>
<div class="outline-text-4" id="text-org9c3aa33">
<div class="org-src-container">
<pre class="src src-matlab">assert(isfield(stewart.geometry, <span class="org-string">'As'</span>), <span class="org-string">'stewart.geometry should have attribute As'</span>)
As = stewart.geometry.As;
@ -1428,9 +1431,9 @@ Otherwise, when the limbs&rsquo; lengths derived yield complex numbers, then the
</div>
</div>
<div id="outline-container-orgfe68a5b" class="outline-4">
<h4 id="orgfe68a5b">Function description</h4>
<div class="outline-text-4" id="text-orgfe68a5b">
<div id="outline-container-orgd97252a" class="outline-4">
<h4 id="orgd97252a">Function description</h4>
<div class="outline-text-4" id="text-orgd97252a">
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-keyword">function</span> <span class="org-variable-name">[Li, dLi]</span> = <span class="org-function-name">inverseKinematics</span>(<span class="org-variable-name">stewart</span>, <span class="org-variable-name">args</span>)
<span class="org-comment">% inverseKinematics - Compute the needed length of each strut to have the wanted position and orientation of {B} with respect to {A}</span>
@ -1454,9 +1457,9 @@ Otherwise, when the limbs&rsquo; lengths derived yield complex numbers, then the
</div>
</div>
<div id="outline-container-org7a9a427" class="outline-4">
<h4 id="org7a9a427">Optional Parameters</h4>
<div class="outline-text-4" id="text-org7a9a427">
<div id="outline-container-org7be1dc4" class="outline-4">
<h4 id="org7be1dc4">Optional Parameters</h4>
<div class="outline-text-4" id="text-org7be1dc4">
<div class="org-src-container">
<pre class="src src-matlab">arguments
stewart
@ -1468,9 +1471,9 @@ Otherwise, when the limbs&rsquo; lengths derived yield complex numbers, then the
</div>
</div>
<div id="outline-container-org27c8a3f" class="outline-4">
<h4 id="org27c8a3f">Check the <code>stewart</code> structure elements</h4>
<div class="outline-text-4" id="text-org27c8a3f">
<div id="outline-container-orga7b29d7" class="outline-4">
<h4 id="orga7b29d7">Check the <code>stewart</code> structure elements</h4>
<div class="outline-text-4" id="text-orga7b29d7">
<div class="org-src-container">
<pre class="src src-matlab">assert(isfield(stewart.geometry, <span class="org-string">'Aa'</span>), <span class="org-string">'stewart.geometry should have attribute Aa'</span>)
Aa = stewart.geometry.Aa;
@ -1514,9 +1517,9 @@ This Matlab function is accessible <a href="../src/forwardKinematicsApprox.m">he
</p>
</div>
<div id="outline-container-org1a620fe" class="outline-4">
<h4 id="org1a620fe">Function description</h4>
<div class="outline-text-4" id="text-org1a620fe">
<div id="outline-container-org1a280b0" class="outline-4">
<h4 id="org1a280b0">Function description</h4>
<div class="outline-text-4" id="text-org1a280b0">
<div class="org-src-container">
<pre class="src src-matlab"><span class="org-keyword">function</span> <span class="org-variable-name">[P, R]</span> = <span class="org-function-name">forwardKinematicsApprox</span>(<span class="org-variable-name">stewart</span>, <span class="org-variable-name">args</span>)
<span class="org-comment">% forwardKinematicsApprox - Computed the approximate pose of {B} with respect to {A} from the length of each strut and using</span>
@ -1538,9 +1541,9 @@ This Matlab function is accessible <a href="../src/forwardKinematicsApprox.m">he
</div>
</div>
<div id="outline-container-org7be1dc4" class="outline-4">
<h4 id="org7be1dc4">Optional Parameters</h4>
<div class="outline-text-4" id="text-org7be1dc4">
<div id="outline-container-orge4b0020" class="outline-4">
<h4 id="orge4b0020">Optional Parameters</h4>
<div class="outline-text-4" id="text-orge4b0020">
<div class="org-src-container">
<pre class="src src-matlab">arguments
stewart
@ -1551,9 +1554,9 @@ This Matlab function is accessible <a href="../src/forwardKinematicsApprox.m">he
</div>
</div>
<div id="outline-container-org9c3aa33" class="outline-4">
<h4 id="org9c3aa33">Check the <code>stewart</code> structure elements</h4>
<div class="outline-text-4" id="text-org9c3aa33">
<div id="outline-container-org08a6ec5" class="outline-4">
<h4 id="org08a6ec5">Check the <code>stewart</code> structure elements</h4>
<div class="outline-text-4" id="text-org08a6ec5">
<div class="org-src-container">
<pre class="src src-matlab">assert(isfield(stewart.kinematics, <span class="org-string">'J'</span>), <span class="org-string">'stewart.kinematics should have attribute J'</span>)
J = stewart.kinematics.J;
@ -1616,7 +1619,7 @@ We then compute the corresponding rotation matrix.
</div>
<div id="postamble" class="status">
<p class="author">Author: Dehaeze Thomas</p>
<p class="date">Created: 2020-02-11 mar. 17:50</p>
<p class="date">Created: 2020-02-12 mer. 10:22</p>
</div>
</body>
</html>

View File

@ -270,7 +270,7 @@ The relative strut length displacement is shown in Figure [[fig:inverse_kinemati
for i = 1:length(Xrs)
Xr = Xrs(i);
L_approx(:, i) = stewart.J*[Xr; 0; 0; 0; 0; 0;];
L_approx(:, i) = stewart.kinematics.J*[Xr; 0; 0; 0; 0; 0;];
[~, L_exact(:, i)] = inverseKinematics(stewart, 'AP', [Xr; 0; 0]);
end
#+end_src
@ -321,7 +321,9 @@ The relative strut length displacement is shown in Figure [[fig:inverse_kinemati
[[file:figs/inverse_kinematics_approx_validity_x_translation_relative.png]]
*** Conclusion
#+begin_important
For small wanted displacements (up to $\approx 1\%$ of the size of the Hexapod), the approximate inverse kinematic solution using the Jacobian matrix is quite correct.
#+end_important
* Estimated required actuator stroke from specified platform mobility
:PROPERTIES:
@ -357,7 +359,7 @@ Let's first define the Stewart platform architecture that we want to study.
stewart = initializeStewartPose(stewart);
stewart = initializeCylindricalPlatforms(stewart);
stewart = initializeCylindricalStruts(stewart);
stewart = initializeStrutDynamics(stewart, 'Ki', 1e6*ones(6,1), 'Ci', 1e2*ones(6,1));
stewart = initializeStrutDynamics(stewart);
stewart = initializeJointDynamics(stewart);
stewart = computeJacobian(stewart);
#+end_src
@ -378,12 +380,12 @@ As a first estimation, we estimate the needed actuator stroke for "pure" rotatio
We do that using either the Inverse Kinematic solution or the Jacobian matrix as an approximation.
#+begin_src matlab
LTx = stewart.J*[Tx_max 0 0 0 0 0]';
LTy = stewart.J*[0 Ty_max 0 0 0 0]';
LTz = stewart.J*[0 0 Tz_max 0 0 0]';
LRx = stewart.J*[0 0 0 Rx_max 0 0]';
LRy = stewart.J*[0 0 0 0 Ry_max 0]';
LRz = stewart.J*[0 0 0 0 0 Rz_max]';
LTx = stewart.kinematics.J*[Tx_max 0 0 0 0 0]';
LTy = stewart.kinematics.J*[0 Ty_max 0 0 0 0]';
LTz = stewart.kinematics.J*[0 0 Tz_max 0 0 0]';
LRx = stewart.kinematics.J*[0 0 0 Rx_max 0 0]';
LRy = stewart.kinematics.J*[0 0 0 0 Ry_max 0]';
LRz = stewart.kinematics.J*[0 0 0 0 0 Rz_max]';
#+end_src
The obtain required stroke is:
@ -514,7 +516,7 @@ Let's first define the Stewart platform architecture that we want to study.
stewart = initializeStewartPose(stewart);
stewart = initializeCylindricalPlatforms(stewart);
stewart = initializeCylindricalStruts(stewart);
stewart = initializeStrutDynamics(stewart, 'Ki', 1e6*ones(6,1), 'Ci', 1e2*ones(6,1));
stewart = initializeStrutDynamics(stewart);
stewart = initializeJointDynamics(stewart);
stewart = computeJacobian(stewart);
#+end_src
@ -547,7 +549,7 @@ For each possible value of $(\theta, \phi)$, we compute the maximum radius $r$ a
Ty = sin(thetas(i))*sin(phis(j));
Tz = cos(thetas(i));
dL = stewart.J*[Tx; Ty; Tz; 0; 0; 0;]; % dL required for 1m displacement in theta/phi direction
dL = stewart.kinematics.J*[Tx; Ty; Tz; 0; 0; 0;]; % dL required for 1m displacement in theta/phi direction
rs(i, j) = max([dL(dL<0)*L_min; dL(dL>0)*L_max]);
end