Change all indentation

This commit is contained in:
2021-01-08 15:54:58 +01:00
parent f5922ca970
commit ed0c18829b
29 changed files with 8682 additions and 8683 deletions

View File

@@ -3,7 +3,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>
<!-- 2021-01-08 ven. 15:17 -->
<!-- 2021-01-08 ven. 15:52 -->
<meta http-equiv="Content-Type" content="text/html;charset=utf-8" />
<title>Kinematic Study of the Stewart Platform</title>
<meta name="generator" content="Org mode" />
@@ -11,22 +11,22 @@
<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>
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">
@@ -60,14 +60,14 @@
</li>
<li><a href="#orgbb09f83">4. Estimation of the range validity of the approximate inverse kinematics</a>
<ul>
<li><a href="#org78ce060">4.1. Stewart architecture definition</a></li>
<li><a href="#orga79cde2">4.1. Stewart architecture definition</a></li>
<li><a href="#org34777fa">4.2. Comparison for &ldquo;pure&rdquo; translations</a></li>
<li><a href="#org76d9fc1">4.3. Conclusion</a></li>
</ul>
</li>
<li><a href="#org091e857">5. Estimated required actuator stroke from specified platform mobility</a>
<ul>
<li><a href="#org34f6e0e">5.1. Stewart architecture definition</a></li>
<li><a href="#org7b16d1f">5.1. Stewart architecture definition</a></li>
<li><a href="#org82ba572">5.2. Wanted translations and rotations</a></li>
<li><a href="#org5897eab">5.3. Needed stroke for &ldquo;pure&rdquo; rotations or translations</a></li>
<li><a href="#org1674055">5.4. Needed stroke for &ldquo;combined&rdquo; rotations or translations</a></li>
@@ -75,7 +75,7 @@
</li>
<li><a href="#orgb685a81">6. Estimated platform mobility from specified actuator stroke</a>
<ul>
<li><a href="#orga79cde2">6.1. Stewart architecture definition</a></li>
<li><a href="#org555f3a5">6.1. Stewart architecture definition</a></li>
<li><a href="#orga6e12fe">6.2. Pure translations</a></li>
</ul>
</li>
@@ -96,8 +96,8 @@
<ul>
<li><a href="#org7a0813a">8.1. <code>computeJacobian</code>: Compute the Jacobian Matrix</a>
<ul>
<li><a href="#org7f0fcca">Function description</a></li>
<li><a href="#orgf06bd47">Check the <code>stewart</code> structure elements</a></li>
<li><a href="#org8a3d2ba">Function description</a></li>
<li><a href="#org5f6ad77">Check the <code>stewart</code> structure elements</a></li>
<li><a href="#org01f1158">Compute Jacobian Matrix</a></li>
<li><a href="#org91d652d">Compute Stiffness Matrix</a></li>
<li><a href="#org323b34e">Compute Compliance Matrix</a></li>
@@ -107,17 +107,17 @@
<li><a href="#org710c2c8">8.2. <code>inverseKinematics</code>: Compute Inverse Kinematics</a>
<ul>
<li><a href="#orge7e6266">Theory</a></li>
<li><a href="#org39a0af1">Function description</a></li>
<li><a href="#orgcb9b73a">Optional Parameters</a></li>
<li><a href="#org31e89c1">Check the <code>stewart</code> structure elements</a></li>
<li><a href="#org6586e8a">Function description</a></li>
<li><a href="#orgf078a15">Optional Parameters</a></li>
<li><a href="#org4151034">Check the <code>stewart</code> structure elements</a></li>
<li><a href="#org7189e65">Compute</a></li>
</ul>
</li>
<li><a href="#orgdc218cd">8.3. <code>forwardKinematicsApprox</code>: Compute the Approximate Forward Kinematics</a>
<ul>
<li><a href="#org8a3d2ba">Function description</a></li>
<li><a href="#orgf078a15">Optional Parameters</a></li>
<li><a href="#org5f6ad77">Check the <code>stewart</code> structure elements</a></li>
<li><a href="#org9b19ae7">Function description</a></li>
<li><a href="#orgdf60206">Optional Parameters</a></li>
<li><a href="#org2c19f08">Check the <code>stewart</code> structure elements</a></li>
<li><a href="#orga496714">Computation</a></li>
</ul>
</li>
@@ -442,7 +442,7 @@ The function <code>forwardKinematicsApprox</code> (described <a href="#orgb960ae
<a id="org5f8c5ea"></a>
</p>
<div class="note" id="org919aba4">
<div class="note" id="org9501cc6">
<p>
The Matlab script corresponding to this section is accessible <a href="../matlab/kinematic_study_approximation_validity.m">here</a>.
</p>
@@ -464,23 +464,23 @@ This will also gives us the range for which the approximate forward kinematic is
</p>
</div>
<div id="outline-container-org78ce060" class="outline-3">
<h3 id="org78ce060"><span class="section-number-3">4.1</span> Stewart architecture definition</h3>
<div id="outline-container-orga79cde2" class="outline-3">
<h3 id="orga79cde2"><span class="section-number-3">4.1</span> Stewart architecture definition</h3>
<div class="outline-text-3" id="text-4-1">
<p>
We first define some general Stewart architecture.
</p>
<div class="org-src-container">
<pre class="src src-matlab"> stewart = initializeStewartPlatform();
stewart = initializeFramesPositions(stewart, <span class="org-string">'H'</span>, 90e<span class="org-type">-</span>3, <span class="org-string">'MO_B'</span>, 45e<span class="org-type">-</span>3);
stewart = generateGeneralConfiguration(stewart);
stewart = computeJointsPose(stewart);
stewart = initializeStewartPose(stewart);
stewart = initializeCylindricalPlatforms(stewart);
stewart = initializeCylindricalStruts(stewart);
stewart = initializeStrutDynamics(stewart);
stewart = initializeJointDynamics(stewart);
stewart = computeJacobian(stewart);
<pre class="src src-matlab">stewart = initializeStewartPlatform();
stewart = initializeFramesPositions(stewart, <span class="org-string">'H'</span>, 90e<span class="org-type">-</span>3, <span class="org-string">'MO_B'</span>, 45e<span class="org-type">-</span>3);
stewart = generateGeneralConfiguration(stewart);
stewart = computeJointsPose(stewart);
stewart = initializeStewartPose(stewart);
stewart = initializeCylindricalPlatforms(stewart);
stewart = initializeCylindricalStruts(stewart);
stewart = initializeStrutDynamics(stewart);
stewart = initializeJointDynamics(stewart);
stewart = computeJacobian(stewart);
</pre>
</div>
</div>
@@ -499,16 +499,16 @@ The estimate required strut stroke for both the approximate and exact solutions
The relative strut length displacement is shown in Figure <a href="#orgb451b90">2</a>.
</p>
<div class="org-src-container">
<pre class="src src-matlab"> Xrs = logspace(<span class="org-type">-</span>6, <span class="org-type">-</span>1, 100); <span class="org-comment">% Wanted X translation of the mobile platform [m]</span>
<pre class="src src-matlab">Xrs = logspace(<span class="org-type">-</span>6, <span class="org-type">-</span>1, 100); <span class="org-comment">% Wanted X translation of the mobile platform [m]</span>
Ls_approx = zeros(6, length(Xrs));
Ls_exact = zeros(6, length(Xrs));
Ls_approx = zeros(6, length(Xrs));
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>
<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.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>
<span class="org-keyword">end</span>
</pre>
</div>
@@ -531,7 +531,7 @@ The relative strut length displacement is shown in Figure <a href="#orgb451b90">
<div id="outline-container-org76d9fc1" class="outline-3">
<h3 id="org76d9fc1"><span class="section-number-3">4.3</span> Conclusion</h3>
<div class="outline-text-3" id="text-4-3">
<div class="important" id="org3d5a817">
<div class="important" id="orgfe0578a">
<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>
@@ -548,7 +548,7 @@ For small wanted displacements (up to \(\approx 1\%\) of the size of the Hexapod
<a id="orgb1464b6"></a>
</p>
<div class="note" id="org7858fd4">
<div class="note" id="org4fab0bc">
<p>
The Matlab script corresponding to this section is accessible <a href="../matlab/kinematic_study_required_actuator_stroke.m">here</a>.
</p>
@@ -565,23 +565,23 @@ This is what is analyzed in this section.
</p>
</div>
<div id="outline-container-org34f6e0e" class="outline-3">
<h3 id="org34f6e0e"><span class="section-number-3">5.1</span> Stewart architecture definition</h3>
<div id="outline-container-org7b16d1f" class="outline-3">
<h3 id="org7b16d1f"><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.
</p>
<div class="org-src-container">
<pre class="src src-matlab"> stewart = initializeStewartPlatform();
stewart = initializeFramesPositions(stewart, <span class="org-string">'H'</span>, 90e<span class="org-type">-</span>3, <span class="org-string">'MO_B'</span>, 45e<span class="org-type">-</span>3);
stewart = generateGeneralConfiguration(stewart);
stewart = computeJointsPose(stewart);
stewart = initializeStewartPose(stewart);
stewart = initializeCylindricalPlatforms(stewart);
stewart = initializeCylindricalStruts(stewart);
stewart = initializeStrutDynamics(stewart);
stewart = initializeJointDynamics(stewart);
stewart = computeJacobian(stewart);
<pre class="src src-matlab">stewart = initializeStewartPlatform();
stewart = initializeFramesPositions(stewart, <span class="org-string">'H'</span>, 90e<span class="org-type">-</span>3, <span class="org-string">'MO_B'</span>, 45e<span class="org-type">-</span>3);
stewart = generateGeneralConfiguration(stewart);
stewart = computeJointsPose(stewart);
stewart = initializeStewartPose(stewart);
stewart = initializeCylindricalPlatforms(stewart);
stewart = initializeCylindricalStruts(stewart);
stewart = initializeStrutDynamics(stewart);
stewart = initializeJointDynamics(stewart);
stewart = computeJacobian(stewart);
</pre>
</div>
</div>
@@ -594,12 +594,12 @@ Let&rsquo;s first define the Stewart platform architecture that we want to study
Let&rsquo;s now define the wanted extreme translations and rotations.
</p>
<div class="org-src-container">
<pre class="src src-matlab"> Tx_max = 50e<span class="org-type">-</span>6; <span class="org-comment">% Translation [m]</span>
Ty_max = 50e<span class="org-type">-</span>6; <span class="org-comment">% Translation [m]</span>
Tz_max = 50e<span class="org-type">-</span>6; <span class="org-comment">% Translation [m]</span>
Rx_max = 30e<span class="org-type">-</span>6; <span class="org-comment">% Rotation [rad]</span>
Ry_max = 30e<span class="org-type">-</span>6; <span class="org-comment">% Rotation [rad]</span>
Rz_max = 0; <span class="org-comment">% Rotation [rad]</span>
<pre class="src src-matlab">Tx_max = 50e<span class="org-type">-</span>6; <span class="org-comment">% Translation [m]</span>
Ty_max = 50e<span class="org-type">-</span>6; <span class="org-comment">% Translation [m]</span>
Tz_max = 50e<span class="org-type">-</span>6; <span class="org-comment">% Translation [m]</span>
Rx_max = 30e<span class="org-type">-</span>6; <span class="org-comment">% Rotation [rad]</span>
Ry_max = 30e<span class="org-type">-</span>6; <span class="org-comment">% Rotation [rad]</span>
Rz_max = 0; <span class="org-comment">% Rotation [rad]</span>
</pre>
</div>
</div>
@@ -614,12 +614,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.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 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>
@@ -652,7 +652,7 @@ To do so, we may estimate the required actuator stroke for all possible combinat
Let&rsquo;s first generate all the possible combination of maximum translation and rotations.
</p>
<div class="org-src-container">
<pre class="src src-matlab"> Ps = [2<span class="org-type">*</span>(dec2bin(0<span class="org-type">:</span>5<span class="org-type">^</span>2<span class="org-type">-</span>1,5)<span class="org-type">-</span><span class="org-string">'0'</span>)<span class="org-type">-</span>1, zeros(5<span class="org-type">^</span>2, 1)]<span class="org-type">.*</span>[Tx_max Ty_max Tz_max Rx_max Ry_max Rz_max];
<pre class="src src-matlab">Ps = [2<span class="org-type">*</span>(dec2bin(0<span class="org-type">:</span>5<span class="org-type">^</span>2<span class="org-type">-</span>1,5)<span class="org-type">-</span><span class="org-string">'0'</span>)<span class="org-type">-</span>1, zeros(5<span class="org-type">^</span>2, 1)]<span class="org-type">.*</span>[Tx_max Ty_max Tz_max Rx_max Ry_max Rz_max];
</pre>
</div>
@@ -914,17 +914,17 @@ Let&rsquo;s first generate all the possible combination of maximum translation a
For all possible combination, we compute the required actuator stroke using the inverse kinematic solution.
</p>
<div class="org-src-container">
<pre class="src src-matlab"> L_min = 0;
L_max = 0;
<pre class="src src-matlab">L_min = 0;
L_max = 0;
<span class="org-keyword">for</span> <span class="org-variable-name"><span class="org-constant">i</span></span> = <span class="org-constant">1:size(Ps,1)</span>
<span class="org-keyword">for</span> <span class="org-variable-name"><span class="org-constant">i</span></span> = <span class="org-constant">1:size(Ps,1)</span>
Rx = [1 0 0;
0 cos(Ps(<span class="org-constant">i</span>, 4)) <span class="org-type">-</span>sin(Ps(<span class="org-constant">i</span>, 4));
0 sin(Ps(<span class="org-constant">i</span>, 4)) cos(Ps(<span class="org-constant">i</span>, 4))];
Ry = [ cos(Ps(<span class="org-constant">i</span>, 5)) 0 sin(Ps(<span class="org-constant">i</span>, 5));
0 1 0;
<span class="org-type">-</span>sin(Ps(<span class="org-constant">i</span>, 5)) 0 cos(Ps(<span class="org-constant">i</span>, 5))];
0 1 0;
<span class="org-type">-</span>sin(Ps(<span class="org-constant">i</span>, 5)) 0 cos(Ps(<span class="org-constant">i</span>, 5))];
Rz = [cos(Ps(<span class="org-constant">i</span>, 6)) <span class="org-type">-</span>sin(Ps(<span class="org-constant">i</span>, 6)) 0;
sin(Ps(<span class="org-constant">i</span>, 6)) cos(Ps(<span class="org-constant">i</span>, 6)) 0;
@@ -934,12 +934,12 @@ For all possible combination, we compute the required actuator stroke using the
[<span class="org-type">~</span>, Ls] = inverseKinematics(stewart, <span class="org-string">'AP'</span>, Ps(<span class="org-constant">i</span>, 1<span class="org-type">:</span>3)<span class="org-type">'</span>, <span class="org-string">'ARB'</span>, ARB);
<span class="org-keyword">if</span> min(Ls) <span class="org-type">&lt;</span> L_min
L_min = min(Ls)
L_min = min(Ls)
<span class="org-keyword">end</span>
<span class="org-keyword">if</span> max(Ls) <span class="org-type">&gt;</span> L_max
L_max = max(Ls)
L_max = max(Ls)
<span class="org-keyword">end</span>
<span class="org-keyword">end</span>
<span class="org-keyword">end</span>
</pre>
</div>
@@ -965,7 +965,7 @@ This is probably a much realistic estimation of the required actuator stroke.
<a id="orge61164c"></a>
</p>
<div class="note" id="orge5bfdd7">
<div class="note" id="orgc9ecb6b">
<p>
The Matlab script corresponding to this section is accessible <a href="../matlab/kinematic_study_mobility.m">here</a>.
</p>
@@ -985,23 +985,23 @@ However, for small displacements, we can use the Jacobian as an approximate solu
</p>
</div>
<div id="outline-container-orga79cde2" class="outline-3">
<h3 id="orga79cde2"><span class="section-number-3">6.1</span> Stewart architecture definition</h3>
<div id="outline-container-org555f3a5" class="outline-3">
<h3 id="org555f3a5"><span class="section-number-3">6.1</span> Stewart architecture definition</h3>
<div class="outline-text-3" id="text-6-1">
<p>
Let&rsquo;s first define the Stewart platform architecture that we want to study.
</p>
<div class="org-src-container">
<pre class="src src-matlab"> stewart = initializeStewartPlatform();
stewart = initializeFramesPositions(stewart, <span class="org-string">'H'</span>, 90e<span class="org-type">-</span>3, <span class="org-string">'MO_B'</span>, 45e<span class="org-type">-</span>3);
stewart = generateGeneralConfiguration(stewart);
stewart = computeJointsPose(stewart);
stewart = initializeStewartPose(stewart);
stewart = initializeCylindricalPlatforms(stewart);
stewart = initializeCylindricalStruts(stewart);
stewart = initializeStrutDynamics(stewart);
stewart = initializeJointDynamics(stewart);
stewart = computeJacobian(stewart);
<pre class="src src-matlab">stewart = initializeStewartPlatform();
stewart = initializeFramesPositions(stewart, <span class="org-string">'H'</span>, 90e<span class="org-type">-</span>3, <span class="org-string">'MO_B'</span>, 45e<span class="org-type">-</span>3);
stewart = generateGeneralConfiguration(stewart);
stewart = computeJointsPose(stewart);
stewart = initializeStewartPose(stewart);
stewart = initializeCylindricalPlatforms(stewart);
stewart = initializeCylindricalStruts(stewart);
stewart = initializeStrutDynamics(stewart);
stewart = initializeJointDynamics(stewart);
stewart = computeJacobian(stewart);
</pre>
</div>
@@ -1009,8 +1009,8 @@ Let&rsquo;s first define the Stewart platform architecture that we want to study
Let&rsquo;s now define the actuator stroke.
</p>
<div class="org-src-container">
<pre class="src src-matlab"> L_min = <span class="org-type">-</span>50e<span class="org-type">-</span>6; <span class="org-comment">% [m]</span>
L_max = 50e<span class="org-type">-</span>6; <span class="org-comment">% [m]</span>
<pre class="src src-matlab">L_min = <span class="org-type">-</span>50e<span class="org-type">-</span>6; <span class="org-comment">% [m]</span>
L_max = 50e<span class="org-type">-</span>6; <span class="org-comment">% [m]</span>
</pre>
</div>
</div>
@@ -1038,21 +1038,21 @@ To obtain the mobility &ldquo;volume&rdquo; attainable by the Stewart platform w
For each possible value of \((\theta, \phi)\), we compute the maximum radius \(r\) attainable with the constraint that the stroke of each actuator should be between <code>L_min</code> and <code>L_max</code>.
</p>
<div class="org-src-container">
<pre class="src src-matlab"> thetas = linspace(0, <span class="org-constant">pi</span>, 50);
phis = linspace(0, 2<span class="org-type">*</span><span class="org-constant">pi</span>, 50);
rs = zeros(length(thetas), length(phis));
<pre class="src src-matlab">thetas = linspace(0, <span class="org-constant">pi</span>, 50);
phis = linspace(0, 2<span class="org-type">*</span><span class="org-constant">pi</span>, 50);
rs = zeros(length(thetas), length(phis));
<span class="org-keyword">for</span> <span class="org-variable-name"><span class="org-constant">i</span></span> = <span class="org-constant">1:length(thetas)</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(thetas)</span>
<span class="org-keyword">for</span> <span class="org-variable-name"><span class="org-constant">j</span></span> = <span class="org-constant">1:length(phis)</span>
Tx = sin(thetas(<span class="org-constant">i</span>))<span class="org-type">*</span>cos(phis(<span class="org-constant">j</span>));
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>));
Tx = sin(thetas(<span class="org-constant">i</span>))<span class="org-type">*</span>cos(phis(<span class="org-constant">j</span>));
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.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>
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]);
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>
<span class="org-keyword">end</span>
<span class="org-keyword">end</span>
</pre>
</div>
@@ -1109,63 +1109,63 @@ We can also approximate the mobility by a sphere with a radius equal to the mini
Let&rsquo;s first define the Stewart Platform Geometry.
</p>
<div class="org-src-container">
<pre class="src src-matlab"> stewart = initializeStewartPlatform();
stewart = initializeFramesPositions(stewart, <span class="org-string">'H'</span>, 90e<span class="org-type">-</span>3, <span class="org-string">'MO_B'</span>, 150e<span class="org-type">-</span>3);
stewart = generateGeneralConfiguration(stewart);
stewart = computeJointsPose(stewart, <span class="org-string">'AP'</span>, [0; 0; 0]);
<pre class="src src-matlab">stewart = initializeStewartPlatform();
stewart = initializeFramesPositions(stewart, <span class="org-string">'H'</span>, 90e<span class="org-type">-</span>3, <span class="org-string">'MO_B'</span>, 150e<span class="org-type">-</span>3);
stewart = generateGeneralConfiguration(stewart);
stewart = computeJointsPose(stewart, <span class="org-string">'AP'</span>, [0; 0; 0]);
As_init = stewart.geometry.As;
As_init = stewart.geometry.As;
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab"> Tx_max = 60e<span class="org-type">-</span>6; <span class="org-comment">% Translation [m]</span>
Ty_max = 60e<span class="org-type">-</span>6; <span class="org-comment">% Translation [m]</span>
Tz_max = 60e<span class="org-type">-</span>6; <span class="org-comment">% Translation [m]</span>
Rx_max = 30e<span class="org-type">-</span>6; <span class="org-comment">% Rotation [rad]</span>
Ry_max = 30e<span class="org-type">-</span>6; <span class="org-comment">% Rotation [rad]</span>
Rz_max = 0; <span class="org-comment">% Rotation [rad]</span>
<pre class="src src-matlab">Tx_max = 60e<span class="org-type">-</span>6; <span class="org-comment">% Translation [m]</span>
Ty_max = 60e<span class="org-type">-</span>6; <span class="org-comment">% Translation [m]</span>
Tz_max = 60e<span class="org-type">-</span>6; <span class="org-comment">% Translation [m]</span>
Rx_max = 30e<span class="org-type">-</span>6; <span class="org-comment">% Rotation [rad]</span>
Ry_max = 30e<span class="org-type">-</span>6; <span class="org-comment">% Rotation [rad]</span>
Rz_max = 0; <span class="org-comment">% Rotation [rad]</span>
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab"> Ps = [2<span class="org-type">*</span>(dec2bin(0<span class="org-type">:</span>5<span class="org-type">^</span>2<span class="org-type">-</span>1,5)<span class="org-type">-</span><span class="org-string">'0'</span>)<span class="org-type">-</span>1, zeros(5<span class="org-type">^</span>2, 1)]<span class="org-type">.*</span>[Tx_max Ty_max Tz_max Rx_max Ry_max Rz_max];
<pre class="src src-matlab">Ps = [2<span class="org-type">*</span>(dec2bin(0<span class="org-type">:</span>5<span class="org-type">^</span>2<span class="org-type">-</span>1,5)<span class="org-type">-</span><span class="org-string">'0'</span>)<span class="org-type">-</span>1, zeros(5<span class="org-type">^</span>2, 1)]<span class="org-type">.*</span>[Tx_max Ty_max Tz_max Rx_max Ry_max Rz_max];
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab"> flex_ang = zeros(size(Ps, 1), 6);
Rxs = zeros(size(Ps, 1), 6)
Rys = zeros(size(Ps, 1), 6)
Rzs = zeros(size(Ps, 1), 6)
<pre class="src src-matlab">flex_ang = zeros(size(Ps, 1), 6);
Rxs = zeros(size(Ps, 1), 6)
Rys = zeros(size(Ps, 1), 6)
Rzs = zeros(size(Ps, 1), 6)
<span class="org-keyword">for</span> <span class="org-variable-name">Ps_i</span> = <span class="org-constant">1:size(Ps, 1)</span>
Rx = [1 0 0;
0 cos(Ps(Ps_i, 4)) <span class="org-type">-</span>sin(Ps(Ps_i, 4));
0 sin(Ps(Ps_i, 4)) cos(Ps(Ps_i, 4))];
<span class="org-keyword">for</span> <span class="org-variable-name">Ps_i</span> = <span class="org-constant">1:size(Ps, 1)</span>
Rx = [1 0 0;
0 cos(Ps(Ps_i, 4)) <span class="org-type">-</span>sin(Ps(Ps_i, 4));
0 sin(Ps(Ps_i, 4)) cos(Ps(Ps_i, 4))];
Ry = [ cos(Ps(Ps_i, 5)) 0 sin(Ps(Ps_i, 5));
0 1 0;
<span class="org-type">-</span>sin(Ps(Ps_i, 5)) 0 cos(Ps(Ps_i, 5))];
Ry = [ cos(Ps(Ps_i, 5)) 0 sin(Ps(Ps_i, 5));
0 1 0;
<span class="org-type">-</span>sin(Ps(Ps_i, 5)) 0 cos(Ps(Ps_i, 5))];
Rz = [cos(Ps(Ps_i, 6)) <span class="org-type">-</span>sin(Ps(Ps_i, 6)) 0;
sin(Ps(Ps_i, 6)) cos(Ps(Ps_i, 6)) 0;
0 0 1];
Rz = [cos(Ps(Ps_i, 6)) <span class="org-type">-</span>sin(Ps(Ps_i, 6)) 0;
sin(Ps(Ps_i, 6)) cos(Ps(Ps_i, 6)) 0;
0 0 1];
ARB = Rz<span class="org-type">*</span>Ry<span class="org-type">*</span>Rx;
ARB = Rz<span class="org-type">*</span>Ry<span class="org-type">*</span>Rx;
stewart = computeJointsPose(stewart, <span class="org-string">'AP'</span>, Ps(Ps_i, 1<span class="org-type">:</span>3)<span class="org-type">'</span>, <span class="org-string">'ARB'</span>, ARB);
stewart = computeJointsPose(stewart, <span class="org-string">'AP'</span>, Ps(Ps_i, 1<span class="org-type">:</span>3)<span class="org-type">'</span>, <span class="org-string">'ARB'</span>, ARB);
flex_ang(Ps_i, <span class="org-type">:</span>) = acos(sum(As_init<span class="org-type">.*</span>stewart.geometry.As));
<span class="org-keyword">for</span> <span class="org-variable-name">l_i</span> = <span class="org-constant">1:6</span>
MRf = stewart.platform_M.MRb(<span class="org-type">:</span>,<span class="org-type">:</span>,l_i)<span class="org-type">*</span>(ARB<span class="org-type">'</span>)<span class="org-type">*</span>(stewart.platform_F.FRa(<span class="org-type">:</span>,<span class="org-type">:</span>,l_i)<span class="org-type">'</span>);
Rys(Ps_i, l_i) = atan2(MRf(1,3), sqrt(MRf(1,1)<span class="org-type">^</span>2 <span class="org-type">+</span> MRf(2,2)<span class="org-type">^</span>2));
Rxs(Ps_i, l_i) = atan2(<span class="org-type">-</span>MRf(2,3)<span class="org-type">/</span>cos(Rys(Ps_i, l_i)), MRf(3,3)<span class="org-type">/</span>cos(Rys(Ps_i, l_i)));
Rzs(Ps_i, l_i) = atan2(<span class="org-type">-</span>MRf(1,2)<span class="org-type">/</span>cos(Rys(Ps_i, l_i)), MRf(1,1)<span class="org-type">/</span>cos(Rys(Ps_i, l_i)));
<span class="org-keyword">end</span>
<span class="org-keyword">end</span>
flex_ang(Ps_i, <span class="org-type">:</span>) = acos(sum(As_init<span class="org-type">.*</span>stewart.geometry.As));
<span class="org-keyword">for</span> <span class="org-variable-name">l_i</span> = <span class="org-constant">1:6</span>
MRf = stewart.platform_M.MRb(<span class="org-type">:</span>,<span class="org-type">:</span>,l_i)<span class="org-type">*</span>(ARB<span class="org-type">'</span>)<span class="org-type">*</span>(stewart.platform_F.FRa(<span class="org-type">:</span>,<span class="org-type">:</span>,l_i)<span class="org-type">'</span>);
Rys(Ps_i, l_i) = atan2(MRf(1,3), sqrt(MRf(1,1)<span class="org-type">^</span>2 <span class="org-type">+</span> MRf(2,2)<span class="org-type">^</span>2));
Rxs(Ps_i, l_i) = atan2(<span class="org-type">-</span>MRf(2,3)<span class="org-type">/</span>cos(Rys(Ps_i, l_i)), MRf(3,3)<span class="org-type">/</span>cos(Rys(Ps_i, l_i)));
Rzs(Ps_i, l_i) = atan2(<span class="org-type">-</span>MRf(1,2)<span class="org-type">/</span>cos(Rys(Ps_i, l_i)), MRf(1,1)<span class="org-type">/</span>cos(Rys(Ps_i, l_i)));
<span class="org-keyword">end</span>
<span class="org-keyword">end</span>
</pre>
</div>
@@ -1173,7 +1173,7 @@ Let&rsquo;s first define the Stewart Platform Geometry.
And the maximum bending of the flexible joints is: (in [mrad])
</p>
<div class="org-src-container">
<pre class="src src-matlab"> 1e3<span class="org-type">*</span>max(max(abs(flex_ang)))
<pre class="src src-matlab">1e3<span class="org-type">*</span>max(max(abs(flex_ang)))
</pre>
</div>
@@ -1183,7 +1183,7 @@ And the maximum bending of the flexible joints is: (in [mrad])
<div class="org-src-container">
<pre class="src src-matlab"> 1e3<span class="org-type">*</span>max(max(sqrt(Rxs<span class="org-type">.^</span>2 <span class="org-type">+</span> Rys<span class="org-type">.^</span>2)))
<pre class="src src-matlab">1e3<span class="org-type">*</span>max(max(sqrt(Rxs<span class="org-type">.^</span>2 <span class="org-type">+</span> Rys<span class="org-type">.^</span>2)))
</pre>
</div>
@@ -1193,7 +1193,7 @@ And the maximum bending of the flexible joints is: (in [mrad])
<div class="org-src-container">
<pre class="src src-matlab"> 1e3<span class="org-type">*</span>max(max(Rzs))
<pre class="src src-matlab">1e3<span class="org-type">*</span>max(max(Rzs))
</pre>
</div>
@@ -1211,31 +1211,31 @@ And the maximum bending of the flexible joints is: (in [mrad])
<h4 id="org656927f"><span class="section-number-4">7.2.1</span> Model Init</h4>
<div class="outline-text-4" id="text-7-2-1">
<div class="org-src-container">
<pre class="src src-matlab"> open(<span class="org-string">'stewart_platform_model.slx'</span>)
<pre class="src src-matlab">open(<span class="org-string">'stewart_platform_model.slx'</span>)
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab"> stewart = initializeStewartPlatform();
stewart = initializeFramesPositions(stewart, <span class="org-string">'H'</span>, 90e<span class="org-type">-</span>3, <span class="org-string">'MO_B'</span>, 45e<span class="org-type">-</span>3);
stewart = generateGeneralConfiguration(stewart);
stewart = computeJointsPose(stewart);
stewart = initializeStrutDynamics(stewart);
stewart = initializeJointDynamics(stewart, <span class="org-string">'type_F'</span>, <span class="org-string">'universal_p'</span>, <span class="org-string">'type_M'</span>, <span class="org-string">'spherical_p'</span>);
stewart = initializeCylindricalPlatforms(stewart);
stewart = initializeCylindricalStruts(stewart);
stewart = computeJacobian(stewart);
stewart = initializeStewartPose(stewart);
stewart = initializeInertialSensor(stewart, <span class="org-string">'type'</span>, <span class="org-string">'accelerometer'</span>, <span class="org-string">'freq'</span>, 5e3);
<pre class="src src-matlab">stewart = initializeStewartPlatform();
stewart = initializeFramesPositions(stewart, <span class="org-string">'H'</span>, 90e<span class="org-type">-</span>3, <span class="org-string">'MO_B'</span>, 45e<span class="org-type">-</span>3);
stewart = generateGeneralConfiguration(stewart);
stewart = computeJointsPose(stewart);
stewart = initializeStrutDynamics(stewart);
stewart = initializeJointDynamics(stewart, <span class="org-string">'type_F'</span>, <span class="org-string">'universal_p'</span>, <span class="org-string">'type_M'</span>, <span class="org-string">'spherical_p'</span>);
stewart = initializeCylindricalPlatforms(stewart);
stewart = initializeCylindricalStruts(stewart);
stewart = computeJacobian(stewart);
stewart = initializeStewartPose(stewart);
stewart = initializeInertialSensor(stewart, <span class="org-string">'type'</span>, <span class="org-string">'accelerometer'</span>, <span class="org-string">'freq'</span>, 5e3);
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab"> ground = initializeGround(<span class="org-string">'type'</span>, <span class="org-string">'rigid'</span>);
payload = initializePayload(<span class="org-string">'type'</span>, <span class="org-string">'none'</span>);
controller = initializeController(<span class="org-string">'type'</span>, <span class="org-string">'open-loop'</span>);
disturbances = initializeDisturbances();
references = initializeReferences(stewart);
<pre class="src src-matlab">ground = initializeGround(<span class="org-string">'type'</span>, <span class="org-string">'rigid'</span>);
payload = initializePayload(<span class="org-string">'type'</span>, <span class="org-string">'none'</span>);
controller = initializeController(<span class="org-string">'type'</span>, <span class="org-string">'open-loop'</span>);
disturbances = initializeDisturbances();
references = initializeReferences(stewart);
</pre>
</div>
</div>
@@ -1245,29 +1245,29 @@ And the maximum bending of the flexible joints is: (in [mrad])
<h4 id="orgc18819c"><span class="section-number-4">7.2.2</span> Controller design to be close to the wanted displacement</h4>
<div class="outline-text-4" id="text-7-2-2">
<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>;
<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">'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>
<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>
<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">'L1'</span>, <span class="org-string">'L2'</span>, <span class="org-string">'L3'</span>, <span class="org-string">'L4'</span>, <span class="org-string">'L5'</span>, <span class="org-string">'L6'</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">'L1'</span>, <span class="org-string">'L2'</span>, <span class="org-string">'L3'</span>, <span class="org-string">'L4'</span>, <span class="org-string">'L5'</span>, <span class="org-string">'L6'</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>30;
Kl = diag(1<span class="org-type">./</span>diag(abs(freqresp(G, 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 class="src src-matlab">wc = 2<span class="org-type">*</span><span class="org-constant">pi</span><span class="org-type">*</span>30;
Kl = diag(1<span class="org-type">./</span>diag(abs(freqresp(G, 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 class="org-src-container">
<pre class="src src-matlab"> controller = initializeController(<span class="org-string">'type'</span>, <span class="org-string">'ref-track-L'</span>);
<pre class="src src-matlab">controller = initializeController(<span class="org-string">'type'</span>, <span class="org-string">'ref-track-L'</span>);
</pre>
</div>
</div>
@@ -1277,34 +1277,34 @@ And the maximum bending of the flexible joints is: (in [mrad])
<h4 id="orgd125932"><span class="section-number-4">7.2.3</span> Simulations</h4>
<div class="outline-text-4" id="text-7-2-3">
<div class="org-src-container">
<pre class="src src-matlab"> Tx_max = 60e<span class="org-type">-</span>6; <span class="org-comment">% Translation [m]</span>
Ty_max = 60e<span class="org-type">-</span>6; <span class="org-comment">% Translation [m]</span>
Tz_max = 60e<span class="org-type">-</span>6; <span class="org-comment">% Translation [m]</span>
Rx_max = 30e<span class="org-type">-</span>6; <span class="org-comment">% Rotation [rad]</span>
Ry_max = 30e<span class="org-type">-</span>6; <span class="org-comment">% Rotation [rad]</span>
Rz_max = 0; <span class="org-comment">% Rotation [rad]</span>
<pre class="src src-matlab">Tx_max = 60e<span class="org-type">-</span>6; <span class="org-comment">% Translation [m]</span>
Ty_max = 60e<span class="org-type">-</span>6; <span class="org-comment">% Translation [m]</span>
Tz_max = 60e<span class="org-type">-</span>6; <span class="org-comment">% Translation [m]</span>
Rx_max = 30e<span class="org-type">-</span>6; <span class="org-comment">% Rotation [rad]</span>
Ry_max = 30e<span class="org-type">-</span>6; <span class="org-comment">% Rotation [rad]</span>
Rz_max = 0; <span class="org-comment">% Rotation [rad]</span>
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab"> Ps = [2<span class="org-type">*</span>(dec2bin(0<span class="org-type">:</span>5<span class="org-type">^</span>2<span class="org-type">-</span>1,5)<span class="org-type">-</span><span class="org-string">'0'</span>)<span class="org-type">-</span>1, zeros(5<span class="org-type">^</span>2, 1)]<span class="org-type">.*</span>[Tx_max Ty_max Tz_max Rx_max Ry_max Rz_max];
<pre class="src src-matlab">Ps = [2<span class="org-type">*</span>(dec2bin(0<span class="org-type">:</span>5<span class="org-type">^</span>2<span class="org-type">-</span>1,5)<span class="org-type">-</span><span class="org-string">'0'</span>)<span class="org-type">-</span>1, zeros(5<span class="org-type">^</span>2, 1)]<span class="org-type">.*</span>[Tx_max Ty_max Tz_max Rx_max Ry_max Rz_max];
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab"> cl_perf = zeros(size(Ps, 1), 1); <span class="org-comment">% Closed loop performance [percentage]</span>
Rs = zeros(size(Ps, 1), 5); <span class="org-comment">% Max Flexor angles for the 6 legs [mrad]</span>
<pre class="src src-matlab">cl_perf = zeros(size(Ps, 1), 1); <span class="org-comment">% Closed loop performance [percentage]</span>
Rs = zeros(size(Ps, 1), 5); <span class="org-comment">% Max Flexor angles for the 6 legs [mrad]</span>
<span class="org-keyword">for</span> <span class="org-variable-name">Ps_i</span> = <span class="org-constant">1:size(Ps, 1)</span>
fprintf(<span class="org-string">'Experiment %i over %i'</span>, Ps_i, size(Ps, 1));
references = initializeReferences(stewart, <span class="org-string">'t'</span>, 0, <span class="org-string">'r'</span>, Ps(Ps_i, <span class="org-type">:</span>)<span class="org-type">'</span>);
<span class="org-matlab-simulink-keyword">set_param</span>(<span class="org-string">'stewart_platform_model'</span>,<span class="org-string">'StopTime'</span>,<span class="org-string">'0.1'</span>);
<span class="org-matlab-simulink-keyword">sim</span>(<span class="org-string">'stewart_platform_model'</span>);
<span class="org-keyword">for</span> <span class="org-variable-name">Ps_i</span> = <span class="org-constant">1:size(Ps, 1)</span>
fprintf(<span class="org-string">'Experiment %i over %i'</span>, Ps_i, size(Ps, 1));
cl_perf(Ps_i) = 100<span class="org-type">*</span>max(abs((simout.y.dLm.Data(end, <span class="org-type">:</span>) <span class="org-type">-</span> references.rL.Data(<span class="org-type">:</span>,1,1)<span class="org-type">'</span>)<span class="org-type">./</span>simout.y.dLm.Data(end, <span class="org-type">:</span>)));
Rs(Ps_i, <span class="org-type">:</span>) = [max(abs(1e3<span class="org-type">*</span>simout.y.Rf.Data(end, 1<span class="org-type">:</span>2<span class="org-type">:</span>end))), max(abs(1e3<span class="org-type">*</span>simout.y.Rf.Data(end, 2<span class="org-type">:</span>2<span class="org-type">:</span>end))), max(abs(1e3<span class="org-type">*</span>simout.y.Rm.Data(end, 1<span class="org-type">:</span>3<span class="org-type">:</span>end))), max(abs(1e3<span class="org-type">*</span>simout.y.Rm.Data(end, 2<span class="org-type">:</span>3<span class="org-type">:</span>end))), max(abs(1e3<span class="org-type">*</span>simout.y.Rm.Data(end, 3<span class="org-type">:</span>3<span class="org-type">:</span>end)))]<span class="org-type">'</span>;
<span class="org-keyword">end</span>
references = initializeReferences(stewart, <span class="org-string">'t'</span>, 0, <span class="org-string">'r'</span>, Ps(Ps_i, <span class="org-type">:</span>)<span class="org-type">'</span>);
<span class="org-matlab-simulink-keyword">set_param</span>(<span class="org-string">'stewart_platform_model'</span>,<span class="org-string">'StopTime'</span>,<span class="org-string">'0.1'</span>);
<span class="org-matlab-simulink-keyword">sim</span>(<span class="org-string">'stewart_platform_model'</span>);
cl_perf(Ps_i) = 100<span class="org-type">*</span>max(abs((simout.y.dLm.Data(end, <span class="org-type">:</span>) <span class="org-type">-</span> references.rL.Data(<span class="org-type">:</span>,1,1)<span class="org-type">'</span>)<span class="org-type">./</span>simout.y.dLm.Data(end, <span class="org-type">:</span>)));
Rs(Ps_i, <span class="org-type">:</span>) = [max(abs(1e3<span class="org-type">*</span>simout.y.Rf.Data(end, 1<span class="org-type">:</span>2<span class="org-type">:</span>end))), max(abs(1e3<span class="org-type">*</span>simout.y.Rf.Data(end, 2<span class="org-type">:</span>2<span class="org-type">:</span>end))), max(abs(1e3<span class="org-type">*</span>simout.y.Rm.Data(end, 1<span class="org-type">:</span>3<span class="org-type">:</span>end))), max(abs(1e3<span class="org-type">*</span>simout.y.Rm.Data(end, 2<span class="org-type">:</span>3<span class="org-type">:</span>end))), max(abs(1e3<span class="org-type">*</span>simout.y.Rm.Data(end, 3<span class="org-type">:</span>3<span class="org-type">:</span>end)))]<span class="org-type">'</span>;
<span class="org-keyword">end</span>
</pre>
</div>
@@ -1312,7 +1312,7 @@ And the maximum bending of the flexible joints is: (in [mrad])
Verify that the simulations are all correct:
</p>
<div class="org-src-container">
<pre class="src src-matlab"> max(cl_perf)
<pre class="src src-matlab">max(cl_perf)
</pre>
</div>
@@ -1390,43 +1390,43 @@ This Matlab function is accessible <a href="../src/computeJacobian.m">here</a>.
</p>
</div>
<div id="outline-container-org7f0fcca" class="outline-4">
<h4 id="org7f0fcca">Function description</h4>
<div class="outline-text-4" id="text-org7f0fcca">
<div id="outline-container-org8a3d2ba" class="outline-4">
<h4 id="org8a3d2ba">Function description</h4>
<div class="outline-text-4" id="text-org8a3d2ba">
<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>
<span class="org-comment">%</span>
<span class="org-comment">% Syntax: [stewart] = computeJacobian(stewart)</span>
<span class="org-comment">%</span>
<span class="org-comment">% Inputs:</span>
<span class="org-comment">% - stewart - With at least the following fields:</span>
<span class="org-comment">% - geometry.As [3x6] - The 6 unit vectors for each strut expressed in {A}</span>
<span class="org-comment">% - geometry.Ab [3x6] - The 6 position of the joints bi expressed in {A}</span>
<span class="org-comment">% - actuators.K [6x1] - Total stiffness of the actuators</span>
<span class="org-comment">%</span>
<span class="org-comment">% Outputs:</span>
<span class="org-comment">% - stewart - With the 3 added field:</span>
<span class="org-comment">% - kinematics.J [6x6] - The Jacobian Matrix</span>
<span class="org-comment">% - kinematics.K [6x6] - The Stiffness Matrix</span>
<span class="org-comment">% - kinematics.C [6x6] - The Compliance Matrix</span>
<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>
<span class="org-comment">%</span>
<span class="org-comment">% Syntax: [stewart] = computeJacobian(stewart)</span>
<span class="org-comment">%</span>
<span class="org-comment">% Inputs:</span>
<span class="org-comment">% - stewart - With at least the following fields:</span>
<span class="org-comment">% - geometry.As [3x6] - The 6 unit vectors for each strut expressed in {A}</span>
<span class="org-comment">% - geometry.Ab [3x6] - The 6 position of the joints bi expressed in {A}</span>
<span class="org-comment">% - actuators.K [6x1] - Total stiffness of the actuators</span>
<span class="org-comment">%</span>
<span class="org-comment">% Outputs:</span>
<span class="org-comment">% - stewart - With the 3 added field:</span>
<span class="org-comment">% - kinematics.J [6x6] - The Jacobian Matrix</span>
<span class="org-comment">% - kinematics.K [6x6] - The Stiffness Matrix</span>
<span class="org-comment">% - kinematics.C [6x6] - The Compliance Matrix</span>
</pre>
</div>
</div>
</div>
<div id="outline-container-orgf06bd47" class="outline-4">
<h4 id="orgf06bd47">Check the <code>stewart</code> structure elements</h4>
<div class="outline-text-4" id="text-orgf06bd47">
<div id="outline-container-org5f6ad77" class="outline-4">
<h4 id="org5f6ad77">Check the <code>stewart</code> structure elements</h4>
<div class="outline-text-4" id="text-org5f6ad77">
<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;
<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;
assert(isfield(stewart.geometry, <span class="org-string">'Ab'</span>), <span class="org-string">'stewart.geometry should have attribute Ab'</span>)
Ab = stewart.geometry.Ab;
assert(isfield(stewart.geometry, <span class="org-string">'Ab'</span>), <span class="org-string">'stewart.geometry should have attribute Ab'</span>)
Ab = stewart.geometry.Ab;
assert(isfield(stewart.actuators, <span class="org-string">'K'</span>), <span class="org-string">'stewart.actuators should have attribute K'</span>)
Ki = stewart.actuators.K;
assert(isfield(stewart.actuators, <span class="org-string">'K'</span>), <span class="org-string">'stewart.actuators should have attribute K'</span>)
Ki = stewart.actuators.K;
</pre>
</div>
</div>
@@ -1437,7 +1437,7 @@ This Matlab function is accessible <a href="../src/computeJacobian.m">here</a>.
<h4 id="org01f1158">Compute Jacobian Matrix</h4>
<div class="outline-text-4" id="text-org01f1158">
<div class="org-src-container">
<pre class="src src-matlab"> J = [As<span class="org-type">'</span> , cross(Ab, As)<span class="org-type">'</span>];
<pre class="src src-matlab">J = [As<span class="org-type">'</span> , cross(Ab, As)<span class="org-type">'</span>];
</pre>
</div>
</div>
@@ -1447,7 +1447,7 @@ This Matlab function is accessible <a href="../src/computeJacobian.m">here</a>.
<h4 id="org91d652d">Compute Stiffness Matrix</h4>
<div class="outline-text-4" id="text-org91d652d">
<div class="org-src-container">
<pre class="src src-matlab"> K = J<span class="org-type">'*</span>diag(Ki)<span class="org-type">*</span>J;
<pre class="src src-matlab">K = J<span class="org-type">'*</span>diag(Ki)<span class="org-type">*</span>J;
</pre>
</div>
</div>
@@ -1457,7 +1457,7 @@ This Matlab function is accessible <a href="../src/computeJacobian.m">here</a>.
<h4 id="org323b34e">Compute Compliance Matrix</h4>
<div class="outline-text-4" id="text-org323b34e">
<div class="org-src-container">
<pre class="src src-matlab"> C = inv(K);
<pre class="src src-matlab">C = inv(K);
</pre>
</div>
</div>
@@ -1467,9 +1467,9 @@ This Matlab function is accessible <a href="../src/computeJacobian.m">here</a>.
<h4 id="orgebce485">Populate the <code>stewart</code> structure</h4>
<div class="outline-text-4" id="text-orgebce485">
<div class="org-src-container">
<pre class="src src-matlab"> stewart.kinematics.J = J;
stewart.kinematics.K = K;
stewart.kinematics.C = C;
<pre class="src src-matlab">stewart.kinematics.J = J;
stewart.kinematics.K = K;
stewart.kinematics.C = C;
</pre>
</div>
</div>
@@ -1525,58 +1525,58 @@ Otherwise, when the limbs&rsquo; lengths derived yield complex numbers, then the
</div>
</div>
<div id="outline-container-org39a0af1" class="outline-4">
<h4 id="org39a0af1">Function description</h4>
<div class="outline-text-4" id="text-org39a0af1">
<div id="outline-container-org6586e8a" class="outline-4">
<h4 id="org6586e8a">Function description</h4>
<div class="outline-text-4" id="text-org6586e8a">
<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>
<span class="org-comment">%</span>
<span class="org-comment">% Syntax: [stewart] = inverseKinematics(stewart)</span>
<span class="org-comment">%</span>
<span class="org-comment">% Inputs:</span>
<span class="org-comment">% - stewart - A structure with the following fields</span>
<span class="org-comment">% - geometry.Aa [3x6] - The positions ai expressed in {A}</span>
<span class="org-comment">% - geometry.Bb [3x6] - The positions bi expressed in {B}</span>
<span class="org-comment">% - geometry.l [6x1] - Length of each strut</span>
<span class="org-comment">% - args - Can have the following fields:</span>
<span class="org-comment">% - AP [3x1] - The wanted position of {B} with respect to {A}</span>
<span class="org-comment">% - ARB [3x3] - The rotation matrix that gives the wanted orientation of {B} with respect to {A}</span>
<span class="org-comment">%</span>
<span class="org-comment">% Outputs:</span>
<span class="org-comment">% - Li [6x1] - The 6 needed length of the struts in [m] to have the wanted pose of {B} w.r.t. {A}</span>
<span class="org-comment">% - dLi [6x1] - The 6 needed displacement of the struts from the initial position in [m] to have the wanted pose of {B} w.r.t. {A}</span>
<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>
<span class="org-comment">%</span>
<span class="org-comment">% Syntax: [stewart] = inverseKinematics(stewart)</span>
<span class="org-comment">%</span>
<span class="org-comment">% Inputs:</span>
<span class="org-comment">% - stewart - A structure with the following fields</span>
<span class="org-comment">% - geometry.Aa [3x6] - The positions ai expressed in {A}</span>
<span class="org-comment">% - geometry.Bb [3x6] - The positions bi expressed in {B}</span>
<span class="org-comment">% - geometry.l [6x1] - Length of each strut</span>
<span class="org-comment">% - args - Can have the following fields:</span>
<span class="org-comment">% - AP [3x1] - The wanted position of {B} with respect to {A}</span>
<span class="org-comment">% - ARB [3x3] - The rotation matrix that gives the wanted orientation of {B} with respect to {A}</span>
<span class="org-comment">%</span>
<span class="org-comment">% Outputs:</span>
<span class="org-comment">% - Li [6x1] - The 6 needed length of the struts in [m] to have the wanted pose of {B} w.r.t. {A}</span>
<span class="org-comment">% - dLi [6x1] - The 6 needed displacement of the struts from the initial position in [m] to have the wanted pose of {B} w.r.t. {A}</span>
</pre>
</div>
</div>
</div>
<div id="outline-container-orgcb9b73a" class="outline-4">
<h4 id="orgcb9b73a">Optional Parameters</h4>
<div class="outline-text-4" id="text-orgcb9b73a">
<div id="outline-container-orgf078a15" class="outline-4">
<h4 id="orgf078a15">Optional Parameters</h4>
<div class="outline-text-4" id="text-orgf078a15">
<div class="org-src-container">
<pre class="src src-matlab"> <span class="org-keyword">arguments</span>
<span class="org-variable-name">stewart</span>
<span class="org-variable-name">args</span>.AP (3,1) double {mustBeNumeric} = zeros(3,1)
<span class="org-variable-name">args</span>.ARB (3,3) double {mustBeNumeric} = eye(3)
<span class="org-keyword">end</span>
<pre class="src src-matlab"><span class="org-keyword">arguments</span>
<span class="org-variable-name">stewart</span>
<span class="org-variable-name">args</span>.AP (3,1) double {mustBeNumeric} = zeros(3,1)
<span class="org-variable-name">args</span>.ARB (3,3) double {mustBeNumeric} = eye(3)
<span class="org-keyword">end</span>
</pre>
</div>
</div>
</div>
<div id="outline-container-org31e89c1" class="outline-4">
<h4 id="org31e89c1">Check the <code>stewart</code> structure elements</h4>
<div class="outline-text-4" id="text-org31e89c1">
<div id="outline-container-org4151034" class="outline-4">
<h4 id="org4151034">Check the <code>stewart</code> structure elements</h4>
<div class="outline-text-4" id="text-org4151034">
<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;
<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;
assert(isfield(stewart.geometry, <span class="org-string">'Bb'</span>), <span class="org-string">'stewart.geometry should have attribute Bb'</span>)
Bb = stewart.geometry.Bb;
assert(isfield(stewart.geometry, <span class="org-string">'Bb'</span>), <span class="org-string">'stewart.geometry should have attribute Bb'</span>)
Bb = stewart.geometry.Bb;
assert(isfield(stewart.geometry, <span class="org-string">'l'</span>), <span class="org-string">'stewart.geometry should have attribute l'</span>)
l = stewart.geometry.l;
assert(isfield(stewart.geometry, <span class="org-string">'l'</span>), <span class="org-string">'stewart.geometry should have attribute l'</span>)
l = stewart.geometry.l;
</pre>
</div>
</div>
@@ -1587,12 +1587,12 @@ Otherwise, when the limbs&rsquo; lengths derived yield complex numbers, then the
<h4 id="org7189e65">Compute</h4>
<div class="outline-text-4" id="text-org7189e65">
<div class="org-src-container">
<pre class="src src-matlab"> Li = sqrt(args.AP<span class="org-type">'*</span>args.AP <span class="org-type">+</span> diag(Bb<span class="org-type">'*</span>Bb) <span class="org-type">+</span> diag(Aa<span class="org-type">'*</span>Aa) <span class="org-type">-</span> (2<span class="org-type">*</span>args.AP<span class="org-type">'*</span>Aa)<span class="org-type">'</span> <span class="org-type">+</span> (2<span class="org-type">*</span>args.AP<span class="org-type">'*</span>(args.ARB<span class="org-type">*</span>Bb))<span class="org-type">'</span> <span class="org-type">-</span> diag(2<span class="org-type">*</span>(args.ARB<span class="org-type">*</span>Bb)<span class="org-type">'*</span>Aa));
<pre class="src src-matlab">Li = sqrt(args.AP<span class="org-type">'*</span>args.AP <span class="org-type">+</span> diag(Bb<span class="org-type">'*</span>Bb) <span class="org-type">+</span> diag(Aa<span class="org-type">'*</span>Aa) <span class="org-type">-</span> (2<span class="org-type">*</span>args.AP<span class="org-type">'*</span>Aa)<span class="org-type">'</span> <span class="org-type">+</span> (2<span class="org-type">*</span>args.AP<span class="org-type">'*</span>(args.ARB<span class="org-type">*</span>Bb))<span class="org-type">'</span> <span class="org-type">-</span> diag(2<span class="org-type">*</span>(args.ARB<span class="org-type">*</span>Bb)<span class="org-type">'*</span>Aa));
</pre>
</div>
<div class="org-src-container">
<pre class="src src-matlab"> dLi = Li<span class="org-type">-</span>l;
<pre class="src src-matlab">dLi = Li<span class="org-type">-</span>l;
</pre>
</div>
</div>
@@ -1611,49 +1611,49 @@ This Matlab function is accessible <a href="../src/forwardKinematicsApprox.m">he
</p>
</div>
<div id="outline-container-org8a3d2ba" class="outline-4">
<h4 id="org8a3d2ba">Function description</h4>
<div class="outline-text-4" id="text-org8a3d2ba">
<div id="outline-container-org9b19ae7" class="outline-4">
<h4 id="org9b19ae7">Function description</h4>
<div class="outline-text-4" id="text-org9b19ae7">
<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>
<span class="org-comment">% the Jacobian Matrix</span>
<span class="org-comment">%</span>
<span class="org-comment">% Syntax: [P, R] = forwardKinematicsApprox(stewart, args)</span>
<span class="org-comment">%</span>
<span class="org-comment">% Inputs:</span>
<span class="org-comment">% - stewart - A structure with the following fields</span>
<span class="org-comment">% - kinematics.J [6x6] - The Jacobian Matrix</span>
<span class="org-comment">% - args - Can have the following fields:</span>
<span class="org-comment">% - dL [6x1] - Displacement of each strut [m]</span>
<span class="org-comment">%</span>
<span class="org-comment">% Outputs:</span>
<span class="org-comment">% - P [3x1] - The estimated position of {B} with respect to {A}</span>
<span class="org-comment">% - R [3x3] - The estimated rotation matrix that gives the orientation of {B} with respect to {A}</span>
<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>
<span class="org-comment">% the Jacobian Matrix</span>
<span class="org-comment">%</span>
<span class="org-comment">% Syntax: [P, R] = forwardKinematicsApprox(stewart, args)</span>
<span class="org-comment">%</span>
<span class="org-comment">% Inputs:</span>
<span class="org-comment">% - stewart - A structure with the following fields</span>
<span class="org-comment">% - kinematics.J [6x6] - The Jacobian Matrix</span>
<span class="org-comment">% - args - Can have the following fields:</span>
<span class="org-comment">% - dL [6x1] - Displacement of each strut [m]</span>
<span class="org-comment">%</span>
<span class="org-comment">% Outputs:</span>
<span class="org-comment">% - P [3x1] - The estimated position of {B} with respect to {A}</span>
<span class="org-comment">% - R [3x3] - The estimated rotation matrix that gives the orientation of {B} with respect to {A}</span>
</pre>
</div>
</div>
</div>
<div id="outline-container-orgf078a15" class="outline-4">
<h4 id="orgf078a15">Optional Parameters</h4>
<div class="outline-text-4" id="text-orgf078a15">
<div id="outline-container-orgdf60206" class="outline-4">
<h4 id="orgdf60206">Optional Parameters</h4>
<div class="outline-text-4" id="text-orgdf60206">
<div class="org-src-container">
<pre class="src src-matlab"> <span class="org-keyword">arguments</span>
<span class="org-variable-name">stewart</span>
<span class="org-variable-name">args</span>.dL (6,1) double {mustBeNumeric} = zeros(6,1)
<span class="org-keyword">end</span>
<pre class="src src-matlab"><span class="org-keyword">arguments</span>
<span class="org-variable-name">stewart</span>
<span class="org-variable-name">args</span>.dL (6,1) double {mustBeNumeric} = zeros(6,1)
<span class="org-keyword">end</span>
</pre>
</div>
</div>
</div>
<div id="outline-container-org5f6ad77" class="outline-4">
<h4 id="org5f6ad77">Check the <code>stewart</code> structure elements</h4>
<div class="outline-text-4" id="text-org5f6ad77">
<div id="outline-container-org2c19f08" class="outline-4">
<h4 id="org2c19f08">Check the <code>stewart</code> structure elements</h4>
<div class="outline-text-4" id="text-org2c19f08">
<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;
<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;
</pre>
</div>
</div>
@@ -1668,7 +1668,7 @@ position and orientation of {B} with respect to {A} using the following formula:
\[ d \bm{\mathcal{X}} = \bm{J}^{-1} d\bm{\mathcal{L}} \]
</p>
<div class="org-src-container">
<pre class="src src-matlab"> X = J<span class="org-type">\</span>args.dL;
<pre class="src src-matlab">X = J<span class="org-type">\</span>args.dL;
</pre>
</div>
@@ -1676,7 +1676,7 @@ position and orientation of {B} with respect to {A} using the following formula:
The position vector corresponds to the first 3 elements.
</p>
<div class="org-src-container">
<pre class="src src-matlab"> P = X(1<span class="org-type">:</span>3);
<pre class="src src-matlab">P = X(1<span class="org-type">:</span>3);
</pre>
</div>
@@ -1685,8 +1685,8 @@ The next 3 elements are the orientation of {B} with respect to {A} expressed
using the screw axis.
</p>
<div class="org-src-container">
<pre class="src src-matlab"> theta = norm(X(4<span class="org-type">:</span>6));
s = X(4<span class="org-type">:</span>6)<span class="org-type">/</span>theta;
<pre class="src src-matlab">theta = norm(X(4<span class="org-type">:</span>6));
s = X(4<span class="org-type">:</span>6)<span class="org-type">/</span>theta;
</pre>
</div>
@@ -1694,9 +1694,9 @@ using the screw axis.
We then compute the corresponding rotation matrix.
</p>
<div class="org-src-container">
<pre class="src src-matlab"> R = [s(1)<span class="org-type">^</span>2<span class="org-type">*</span>(1<span class="org-type">-</span>cos(theta)) <span class="org-type">+</span> cos(theta) , s(1)<span class="org-type">*</span>s(2)<span class="org-type">*</span>(1<span class="org-type">-</span>cos(theta)) <span class="org-type">-</span> s(3)<span class="org-type">*</span>sin(theta), s(1)<span class="org-type">*</span>s(3)<span class="org-type">*</span>(1<span class="org-type">-</span>cos(theta)) <span class="org-type">+</span> s(2)<span class="org-type">*</span>sin(theta);
s<span class="org-type">(2)*s(1)*(1-cos(theta)) + s(3)*sin(theta), s(2)^2*(1-cos(theta)) + cos(theta), s(2)*s(3)*(1-cos(theta)) - s(1)*sin(theta);</span>
s<span class="org-type">(3)*s(1)*(1-cos(theta)) - s(2)*sin(theta), s(3)*s(2)*(1-cos(theta)) + s(1)*sin(theta), s(3)^2*(1-cos(theta)) + cos(theta)];</span>
<pre class="src src-matlab">R = [s(1)<span class="org-type">^</span>2<span class="org-type">*</span>(1<span class="org-type">-</span>cos(theta)) <span class="org-type">+</span> cos(theta) , s(1)<span class="org-type">*</span>s(2)<span class="org-type">*</span>(1<span class="org-type">-</span>cos(theta)) <span class="org-type">-</span> s(3)<span class="org-type">*</span>sin(theta), s(1)<span class="org-type">*</span>s(3)<span class="org-type">*</span>(1<span class="org-type">-</span>cos(theta)) <span class="org-type">+</span> s(2)<span class="org-type">*</span>sin(theta);
s<span class="org-type">(2)*s(1)*(1-cos(theta)) + s(3)*sin(theta), s(2)^2*(1-cos(theta)) + cos(theta), s(2)*s(3)*(1-cos(theta)) - s(1)*sin(theta);</span>
s<span class="org-type">(3)*s(1)*(1-cos(theta)) - s(2)*sin(theta), s(3)*s(2)*(1-cos(theta)) + s(1)*sin(theta), s(3)^2*(1-cos(theta)) + cos(theta)];</span>
</pre>
</div>
</div>
@@ -1715,7 +1715,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: 2021-01-08 ven. 15:17</p>
<p class="date">Created: 2021-01-08 ven. 15:52</p>
</div>
</body>
</html>