stewart-simscape/docs/kinematic-study.html

1722 lines
70 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>Kinematic Study of the Stewart Platform</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>
<script>
MathJax = {
svg: {
scale: 1,
fontCache: "global"
},
tex: {
tags: "ams",
multlineWidth: "%MULTLINEWIDTH",
tagSide: "right",
macros: {bm: ["\\boldsymbol{#1}",1],},
tagIndent: ".8em"
}
};
</script>
<script id="MathJax-script" async
src="https://cdn.jsdelivr.net/npm/mathjax@3/es5/tex-svg.js"></script>
</head>
<body>
<div id="org-div-home-and-up">
<a accesskey="h" href="./index.html"> UP </a>
|
<a accesskey="H" href="./index.html"> HOME </a>
</div><div id="content">
<h1 class="title">Kinematic Study of the Stewart Platform</h1>
<div id="table-of-contents">
<h2>Table of Contents</h2>
<div id="text-table-of-contents">
<ul>
<li><a href="#org1b932a3">1. Jacobian Analysis</a>
<ul>
<li><a href="#orgbb5007b">1.1. Jacobian Computation</a></li>
<li><a href="#org307e5b8">1.2. Jacobian - Velocity loop closure</a></li>
<li><a href="#orgb3e2cfe">1.3. Jacobian - Static Force Transformation</a></li>
</ul>
</li>
<li><a href="#org9ad88f0">2. Stiffness Analysis</a>
<ul>
<li><a href="#org293ca49">2.1. Computation of the Stiffness and Compliance Matrix</a></li>
</ul>
</li>
<li><a href="#org8458ff5">3. Forward and Inverse Kinematics</a>
<ul>
<li><a href="#org0b29469">3.1. Inverse Kinematics</a></li>
<li><a href="#org663a95f">3.2. Forward Kinematics</a></li>
<li><a href="#org2a5ab6a">3.3. Approximate solution of the Forward and Inverse Kinematic problem for small displacement using the Jacobian matrix</a></li>
</ul>
</li>
<li><a href="#orgbb09f83">4. Estimation of the range validity of the approximate inverse kinematics</a>
<ul>
<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="#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>
</ul>
</li>
<li><a href="#orgb685a81">6. Estimated platform mobility from specified actuator stroke</a>
<ul>
<li><a href="#org555f3a5">6.1. Stewart architecture definition</a></li>
<li><a href="#orga6e12fe">6.2. Pure translations</a></li>
</ul>
</li>
<li><a href="#org5be8fc9">7. Estimation of the Joint required Stroke</a>
<ul>
<li><a href="#org461e0b6">7.1. Estimation with an analytical model</a></li>
<li><a href="#org6d0095b">7.2. Estimation using the Simscape Model</a>
<ul>
<li><a href="#org656927f">7.2.1. Model Init</a></li>
<li><a href="#orgc18819c">7.2.2. Controller design to be close to the wanted displacement</a></li>
<li><a href="#orgd125932">7.2.3. Simulations</a></li>
<li><a href="#orgbc09d7e">7.2.4. Results</a></li>
</ul>
</li>
</ul>
</li>
<li><a href="#orgc5835cc">8. Functions</a>
<ul>
<li><a href="#org7a0813a">8.1. <code>computeJacobian</code>: Compute the Jacobian Matrix</a>
<ul>
<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>
<li><a href="#orgebce485">Populate the <code>stewart</code> structure</a></li>
</ul>
</li>
<li><a href="#org710c2c8">8.2. <code>inverseKinematics</code>: Compute Inverse Kinematics</a>
<ul>
<li><a href="#orge7e6266">Theory</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="#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>
</ul>
</li>
</ul>
</div>
</div>
<p>
The kinematic analysis of a parallel manipulator is well described in (<a href="#citeproc_bib_item_1">Taghirad 2013</a>):
</p>
<blockquote>
<p>
Kinematic analysis refers to the study of the geometry of motion of a robot, without considering the forces an torques that cause the motion.
In this analysis, the relation between the geometrical parameters of the manipulator with the final motion of the moving platform is derived and analyzed.
</p>
</blockquote>
<p>
The current document is divided in the following sections:
</p>
<ul class="org-ul">
<li>Section <a href="#org538eefa">1</a>: The Jacobian matrix is derived from the geometry of the Stewart platform. Then it is shown that the Jacobian can link velocities and forces present in the system, and thus this matrix can be very useful for both analysis and control of the Stewart platform.</li>
<li>Section <a href="#org7de704b">2</a>: The stiffness and compliance matrices are derived from the Jacobian matrix and the stiffness of each strut.</li>
<li>Section <a href="#org81c3707">3</a>: The Forward and Inverse kinematic problems are presented.</li>
<li>Section <a href="#org5f8c5ea">4</a>: The approximate solution of the Inverse kinematic problem is compared with the exact solution in order to determine the validity of the approximation.</li>
<li>Section <a href="#orgb1464b6">5</a>: The Inverse kinematic solution is used to estimate required actuator stroke from the wanted mobility of the Stewart platform.</li>
</ul>
<div id="outline-container-org1b932a3" class="outline-2">
<h2 id="org1b932a3"><span class="section-number-2">1</span> Jacobian Analysis</h2>
<div class="outline-text-2" id="text-1">
<p>
<a id="org538eefa"></a>
</p>
<p>
From (<a href="#citeproc_bib_item_1">Taghirad 2013</a>):
</p>
<blockquote>
<p>
The Jacobian matrix not only reveals the <b>relation between the joint variable velocities of a parallel manipulator to the moving platform linear and angular velocities</b>, it also constructs the transformation needed to find the <b>actuator forces from the forces and moments acting on the moving platform</b>.
</p>
</blockquote>
</div>
<div id="outline-container-orgbb5007b" class="outline-3">
<h3 id="orgbb5007b"><span class="section-number-3">1.1</span> Jacobian Computation</h3>
<div class="outline-text-3" id="text-1-1">
<p>
If we note:
</p>
<ul class="org-ul">
<li>\({}^A\hat{\bm{s}}_i\) the unit vector representing the direction of the i&rsquo;th strut and expressed in frame \(\{A\}\)</li>
<li>\({}^A\bm{b}_i\) the position vector of the i&rsquo;th joint fixed to the mobile platform and expressed in frame \(\{A\}\)</li>
</ul>
<p>
Then, we can compute the Jacobian with the following equation (the superscript \(A\) is ignored):
</p>
\begin{equation*}
\bm{J} = \begin{bmatrix}
{\hat{\bm{s}}_1}^T & (\bm{b}_1 \times \hat{\bm{s}}_1)^T \\
{\hat{\bm{s}}_2}^T & (\bm{b}_2 \times \hat{\bm{s}}_2)^T \\
{\hat{\bm{s}}_3}^T & (\bm{b}_3 \times \hat{\bm{s}}_3)^T \\
{\hat{\bm{s}}_4}^T & (\bm{b}_4 \times \hat{\bm{s}}_4)^T \\
{\hat{\bm{s}}_5}^T & (\bm{b}_5 \times \hat{\bm{s}}_5)^T \\
{\hat{\bm{s}}_6}^T & (\bm{b}_6 \times \hat{\bm{s}}_6)^T
\end{bmatrix}
\end{equation*}
<p>
The Jacobian matrix \(\bm{J}\) can be computed using the <code>computeJacobian</code> function (accessible <a href="#org0a94753">here</a>).
For instance:
</p>
<div class="org-src-container">
<pre class="src src-matlab"> stewart = computeJacobian(stewart);
</pre>
</div>
<p>
This will add three new matrix to the <code>stewart</code> structure:
</p>
<ul class="org-ul">
<li><code>J</code> the Jacobian matrix</li>
<li><code>K</code> the stiffness matrix</li>
<li><code>C</code> the compliance matrix</li>
</ul>
</div>
</div>
<div id="outline-container-org307e5b8" class="outline-3">
<h3 id="org307e5b8"><span class="section-number-3">1.2</span> Jacobian - Velocity loop closure</h3>
<div class="outline-text-3" id="text-1-2">
<p>
The Jacobian matrix links the input joint rate \(\dot{\bm{\mathcal{L}}} = [ \dot{l}_1, \dot{l}_2, \dot{l}_3, \dot{l}_4, \dot{l}_5, \dot{l}_6 ]^T\) of each strut to the output twist vector of the mobile platform is denoted by \(\dot{\bm{X}} = [^A\bm{v}_p, {}^A\bm{\omega}]^T\):
</p>
\begin{equation*}
\dot{\bm{\mathcal{L}}} = \bm{J} \dot{\bm{\mathcal{X}}}
\end{equation*}
<p>
The input joint rate \(\dot{\bm{\mathcal{L}}}\) can be measured by taking the derivative of the relative motion sensor in each strut.
The output twist vector can be measured with a &ldquo;Transform Sensor&rdquo; block measuring the relative velocity and relative angular velocity of frame \(\{B\}\) with respect to frame \(\{A\}\).
</p>
<p>
If the Jacobian matrix is inversible, we can also compute \(\dot{\bm{\mathcal{X}}}\) from \(\dot{\bm{\mathcal{L}}}\).
</p>
\begin{equation*}
\dot{\bm{\mathcal{X}}} = \bm{J}^{-1} \dot{\bm{\mathcal{L}}}
\end{equation*}
<p>
The Jacobian matrix can also be used to approximate forward and inverse kinematics for small displacements.
This is explained in section <a href="#orga63a666">3.3</a>.
</p>
</div>
</div>
<div id="outline-container-orgb3e2cfe" class="outline-3">
<h3 id="orgb3e2cfe"><span class="section-number-3">1.3</span> Jacobian - Static Force Transformation</h3>
<div class="outline-text-3" id="text-1-3">
<p>
If we note:
</p>
<ul class="org-ul">
<li>\(\bm{\tau} = [\tau_1, \tau_2, \cdots, \tau_6]^T\): vector of actuator forces applied in each strut</li>
<li>\(\bm{\mathcal{F}} = [\bm{f}, \bm{n}]^T\): external force/torque action on the mobile platform at \(\bm{O}_B\)</li>
</ul>
<p>
We find that the transpose of the Jacobian matrix links the two by the following equation:
</p>
\begin{equation*}
\bm{\mathcal{F}} = \bm{J}^T \bm{\tau}
\end{equation*}
<p>
If the Jacobian matrix is inversible, we also have the following relation:
</p>
\begin{equation*}
\bm{\tau} = \bm{J}^{-T} \bm{\mathcal{F}}
\end{equation*}
</div>
</div>
</div>
<div id="outline-container-org9ad88f0" class="outline-2">
<h2 id="org9ad88f0"><span class="section-number-2">2</span> Stiffness Analysis</h2>
<div class="outline-text-2" id="text-2">
<p>
<a id="org7de704b"></a>
</p>
<p>
Here, we focus on the deflections of the manipulator moving platform that are the result of the external applied wrench to the mobile platform.
The amount of these deflections are a function of the applied wrench as well as the manipulator <b>structural stiffness</b>.
</p>
</div>
<div id="outline-container-org293ca49" class="outline-3">
<h3 id="org293ca49"><span class="section-number-3">2.1</span> Computation of the Stiffness and Compliance Matrix</h3>
<div class="outline-text-3" id="text-2-1">
<p>
As explain in <a href="stewart-architecture.html">this</a> document, each Actuator is modeled by 3 elements in parallel:
</p>
<ul class="org-ul">
<li>A spring with a stiffness \(k_{i}\)</li>
<li>A dashpot with a damping \(c_{i}\)</li>
<li>A force source \(\tau_i\)</li>
</ul>
<p>
The stiffness of the actuator \(k_i\) links the applied actuator force \(\delta \tau_i\) and the corresponding small deflection \(\delta l_i\):
</p>
\begin{equation*}
\tau_i = k_i \delta l_i, \quad i = 1,\ \dots,\ 6
\end{equation*}
<p>
If we combine these 6 relations:
</p>
\begin{equation*}
\bm{\tau} = \mathcal{K} \delta \bm{\mathcal{L}} \quad \mathcal{K} = \text{diag}\left[ k_1,\ \dots,\ k_6 \right]
\end{equation*}
<p>
Substituting \(\bm{\tau} = \bm{J}^{-T} \bm{\mathcal{F}}\) and \(\delta \bm{\mathcal{L}} = \bm{J} \cdot \delta \bm{\mathcal{X}}\) gives
</p>
\begin{equation*}
\bm{\mathcal{F}} = \bm{J}^T \mathcal{K} \bm{J} \cdot \delta \bm{\mathcal{X}}
\end{equation*}
<p>
And then we identify the stiffness matrix \(\bm{K}\):
</p>
\begin{equation*}
\bm{K} = \bm{J}^T \mathcal{K} \bm{J}
\end{equation*}
<p>
If the stiffness matrix \(\bm{K}\) is inversible, the <b>compliance matrix</b> of the manipulator is defined as
</p>
\begin{equation*}
\bm{C} = \bm{K}^{-1} = (\bm{J}^T \mathcal{K} \bm{J})^{-1}
\end{equation*}
<p>
The compliance matrix of a manipulator shows the mapping of the moving platform wrench applied at \(\bm{O}_B\) to its small deflection by
</p>
\begin{equation*}
\delta \bm{\mathcal{X}} = \bm{C} \cdot \bm{\mathcal{F}}
\end{equation*}
<p>
The stiffness and compliance matrices are computed using the <code>computeJacobian</code> function (accessible <a href="#org0a94753">here</a>).
</p>
</div>
</div>
</div>
<div id="outline-container-org8458ff5" class="outline-2">
<h2 id="org8458ff5"><span class="section-number-2">3</span> Forward and Inverse Kinematics</h2>
<div class="outline-text-2" id="text-3">
<p>
<a id="org81c3707"></a>
</p>
</div>
<div id="outline-container-org0b29469" class="outline-3">
<h3 id="org0b29469"><span class="section-number-3">3.1</span> Inverse Kinematics</h3>
<div class="outline-text-3" id="text-3-1">
<p>
<a id="org2af01da"></a>
</p>
<blockquote>
<p>
For <b>inverse kinematic analysis</b>, it is assumed that the position \({}^A\bm{P}\) and orientation of the moving platform \({}^A\bm{R}_B\) are given and the problem is to obtain the joint variables \(\bm{\mathcal{L}} = \left[ l_1, l_2, l_3, l_4, l_5, l_6 \right]^T\).
</p>
</blockquote>
<p>
This problem can be easily solved using the loop closures.
</p>
<p>
The obtain joint variables are:
</p>
\begin{equation*}
\begin{aligned}
l_i = &\Big[ {}^A\bm{P}^T {}^A\bm{P} + {}^B\bm{b}_i^T {}^B\bm{b}_i + {}^A\bm{a}_i^T {}^A\bm{a}_i - 2 {}^A\bm{P}^T {}^A\bm{a}_i + \dots\\
&2 {}^A\bm{P}^T \left[{}^A\bm{R}_B {}^B\bm{b}_i\right] - 2 \left[{}^A\bm{R}_B {}^B\bm{b}_i\right]^T {}^A\bm{a}_i \Big]^{1/2}
\end{aligned}
\end{equation*}
<p>
If the position and orientation of the platform lie in the feasible workspace, the solution is unique.
Otherwise, the solution gives complex numbers.
</p>
<p>
This inverse kinematic solution can be obtained using the function <code>inverseKinematics</code> (described <a href="#orgb533a06">here</a>).
</p>
</div>
</div>
<div id="outline-container-org663a95f" class="outline-3">
<h3 id="org663a95f"><span class="section-number-3">3.2</span> Forward Kinematics</h3>
<div class="outline-text-3" id="text-3-2">
<p>
<a id="org5320ae6"></a>
</p>
<blockquote>
<p>
In <b>forward kinematic analysis</b>, it is assumed that the vector of limb lengths \(\bm{L}\) is given and the problem is to find the position \({}^A\bm{P}\) and the orientation \({}^A\bm{R}_B\).
</p>
</blockquote>
<p>
This is a difficult problem that requires to solve nonlinear equations.
</p>
<p>
In a next section, an approximate solution of the forward kinematics problem is proposed for small displacements.
</p>
</div>
</div>
<div id="outline-container-org2a5ab6a" class="outline-3">
<h3 id="org2a5ab6a"><span class="section-number-3">3.3</span> Approximate solution of the Forward and Inverse Kinematic problem for small displacement using the Jacobian matrix</h3>
<div class="outline-text-3" id="text-3-3">
<p>
<a id="orga63a666"></a>
</p>
<p>
For small displacements mobile platform displacement \(\delta \bm{\mathcal{X}} = [\delta x, \delta y, \delta z, \delta \theta_x, \delta \theta_y, \delta \theta_z ]^T\) around \(\bm{\mathcal{X}}_0\), the associated joint displacement can be computed using the Jacobian (approximate solution of the inverse kinematic problem):
</p>
\begin{equation*}
\delta\bm{\mathcal{L}} = \bm{J} \delta\bm{\mathcal{X}}
\end{equation*}
<p>
Similarly, for small joint displacements \(\delta\bm{\mathcal{L}} = [ \delta l_1,\ \dots,\ \delta l_6 ]^T\) around \(\bm{\mathcal{L}}_0\), it is possible to find the induced small displacement of the mobile platform (approximate solution of the forward kinematic problem):
</p>
\begin{equation*}
\delta\bm{\mathcal{X}} = \bm{J}^{-1} \delta\bm{\mathcal{L}}
\end{equation*}
<p>
These two relations solve the forward and inverse kinematic problems for small displacement in a <b>approximate</b> way.
As the inverse kinematic can be easily solved exactly this is not much useful, however, as the forward kinematic problem is difficult to solve, this approximation can be very useful for small displacements.
</p>
<p>
The function <code>forwardKinematicsApprox</code> (described <a href="#orgb960aea">here</a>) can be used to solve the forward kinematic problem using the Jacobian matrix.
</p>
</div>
</div>
</div>
<div id="outline-container-orgbb09f83" class="outline-2">
<h2 id="orgbb09f83"><span class="section-number-2">4</span> Estimation of the range validity of the approximate inverse kinematics</h2>
<div class="outline-text-2" id="text-4">
<p>
<a id="org5f8c5ea"></a>
</p>
<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>
<p>
To run the script, open the Simulink Project, and type <code>run kinematic_study_approximation_validity.m</code>.
</p>
</div>
<p>
As we know how to exactly solve the Inverse kinematic problem, we can compare the exact solution with the approximate solution using the Jacobian matrix.
For small displacements, the approximate solution is expected to work well.
We would like here to determine up to what displacement this approximation can be considered as correct.
</p>
<p>
Then, we can determine the range for which the approximate inverse kinematic is valid.
This will also gives us the range for which the approximate forward kinematic is valid.
</p>
</div>
<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>
</div>
</div>
</div>
<div id="outline-container-org34777fa" class="outline-3">
<h3 id="org34777fa"><span class="section-number-3">4.2</span> Comparison for &ldquo;pure&rdquo; translations</h3>
<div class="outline-text-3" id="text-4-2">
<p>
Let&rsquo;s first compare the perfect and approximate solution of the inverse for pure \(x\) translations.
</p>
<p>
We compute the approximate and exact required strut stroke to have the wanted mobile platform \(x\) displacement.
The estimate required strut stroke for both the approximate and exact solutions are shown in Figure <a href="#orge29db09">1</a>.
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>
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>
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>
</pre>
</div>
<div id="orge29db09" class="figure">
<p><img src="figs/inverse_kinematics_approx_validity_x_translation.png" alt="inverse_kinematics_approx_validity_x_translation.png" />
</p>
<p><span class="figure-number">Figure 1: </span>Comparison of the Approximate solution and True solution for the Inverse kinematic problem (<a href="./figs/inverse_kinematics_approx_validity_x_translation.png">png</a>, <a href="./figs/inverse_kinematics_approx_validity_x_translation.pdf">pdf</a>)</p>
</div>
<div id="orgb451b90" class="figure">
<p><img src="figs/inverse_kinematics_approx_validity_x_translation_relative.png" alt="inverse_kinematics_approx_validity_x_translation_relative.png" />
</p>
<p><span class="figure-number">Figure 2: </span>Relative length error by using the Approximate solution of the Inverse kinematic problem (<a href="./figs/inverse_kinematics_approx_validity_x_translation_relative.png">png</a>, <a href="./figs/inverse_kinematics_approx_validity_x_translation_relative.pdf">pdf</a>)</p>
</div>
</div>
</div>
<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="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>
</div>
</div>
</div>
</div>
<div id="outline-container-org091e857" class="outline-2">
<h2 id="org091e857"><span class="section-number-2">5</span> Estimated required actuator stroke from specified platform mobility</h2>
<div class="outline-text-2" id="text-5">
<p>
<a id="orgb1464b6"></a>
</p>
<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>
<p>
To run the script, open the Simulink Project, and type <code>run kinematic_study_required_actuator_stroke.m</code>.
</p>
</div>
<p>
Let&rsquo;s say one want to design a Stewart platform with some specified mobility (position and orientation).
One may want to determine the required actuator stroke required to obtain the specified mobility.
This is what is analyzed in this section.
</p>
</div>
<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>
</div>
</div>
</div>
<div id="outline-container-org82ba572" class="outline-3">
<h3 id="org82ba572"><span class="section-number-3">5.2</span> Wanted translations and rotations</h3>
<div class="outline-text-3" id="text-5-2">
<p>
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>
</div>
</div>
</div>
<div id="outline-container-org5897eab" class="outline-3">
<h3 id="org5897eab"><span class="section-number-3">5.3</span> Needed stroke for &ldquo;pure&rdquo; rotations or translations</h3>
<div class="outline-text-3" id="text-5-3">
<p>
As a first estimation, we estimate the needed actuator stroke for &ldquo;pure&rdquo; rotations and translation.
We do that using either the Inverse Kinematic solution or the Jacobian matrix as an approximation.
</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>
</div>
<p>
The obtain required stroke is:
</p>
<pre class="example">
From -3.8e-05[m] to 3.8e-05[m]: Total stroke = 76.1[um]
</pre>
<p>
This is surely a low estimation of the required stroke.
</p>
</div>
</div>
<div id="outline-container-org1674055" class="outline-3">
<h3 id="org1674055"><span class="section-number-3">5.4</span> Needed stroke for &ldquo;combined&rdquo; rotations or translations</h3>
<div class="outline-text-3" id="text-5-4">
<p>
We know would like to have a more precise estimation.
</p>
<p>
To do so, we may estimate the required actuator stroke for all possible combination of translation and rotation.
</p>
<p>
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>
</div>
<table border="2" cellspacing="0" cellpadding="6" rules="groups" frame="hsides">
<colgroup>
<col class="org-right" />
<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"><b>Tx [m]</b></th>
<th scope="col" class="org-right"><b>Ty [m]</b></th>
<th scope="col" class="org-right"><b>Tz [m]</b></th>
<th scope="col" class="org-right"><b>Rx [rad]</b></th>
<th scope="col" class="org-right"><b>Ry [rad]</b></th>
<th scope="col" class="org-right"><b>Rz [rad]</b></th>
</tr>
</thead>
<tbody>
<tr>
<td class="org-right">-5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">0.0e+00</td>
</tr>
<tr>
<td class="org-right">-5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">3.0e-05</td>
<td class="org-right">0.0e+00</td>
</tr>
<tr>
<td class="org-right">-5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">3.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">0.0e+00</td>
</tr>
<tr>
<td class="org-right">-5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">3.0e-05</td>
<td class="org-right">3.0e-05</td>
<td class="org-right">0.0e+00</td>
</tr>
<tr>
<td class="org-right">-5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">5.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">0.0e+00</td>
</tr>
<tr>
<td class="org-right">-5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">5.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">3.0e-05</td>
<td class="org-right">0.0e+00</td>
</tr>
<tr>
<td class="org-right">-5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">5.0e-05</td>
<td class="org-right">3.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">0.0e+00</td>
</tr>
<tr>
<td class="org-right">-5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">5.0e-05</td>
<td class="org-right">3.0e-05</td>
<td class="org-right">3.0e-05</td>
<td class="org-right">0.0e+00</td>
</tr>
<tr>
<td class="org-right">-5.0e-05</td>
<td class="org-right">5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">0.0e+00</td>
</tr>
<tr>
<td class="org-right">-5.0e-05</td>
<td class="org-right">5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">3.0e-05</td>
<td class="org-right">0.0e+00</td>
</tr>
<tr>
<td class="org-right">-5.0e-05</td>
<td class="org-right">5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">3.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">0.0e+00</td>
</tr>
<tr>
<td class="org-right">-5.0e-05</td>
<td class="org-right">5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">3.0e-05</td>
<td class="org-right">3.0e-05</td>
<td class="org-right">0.0e+00</td>
</tr>
<tr>
<td class="org-right">-5.0e-05</td>
<td class="org-right">5.0e-05</td>
<td class="org-right">5.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">0.0e+00</td>
</tr>
<tr>
<td class="org-right">-5.0e-05</td>
<td class="org-right">5.0e-05</td>
<td class="org-right">5.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">3.0e-05</td>
<td class="org-right">0.0e+00</td>
</tr>
<tr>
<td class="org-right">-5.0e-05</td>
<td class="org-right">5.0e-05</td>
<td class="org-right">5.0e-05</td>
<td class="org-right">3.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">0.0e+00</td>
</tr>
<tr>
<td class="org-right">-5.0e-05</td>
<td class="org-right">5.0e-05</td>
<td class="org-right">5.0e-05</td>
<td class="org-right">3.0e-05</td>
<td class="org-right">3.0e-05</td>
<td class="org-right">0.0e+00</td>
</tr>
<tr>
<td class="org-right">5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">0.0e+00</td>
</tr>
<tr>
<td class="org-right">5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">3.0e-05</td>
<td class="org-right">0.0e+00</td>
</tr>
<tr>
<td class="org-right">5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">3.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">0.0e+00</td>
</tr>
<tr>
<td class="org-right">5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">3.0e-05</td>
<td class="org-right">3.0e-05</td>
<td class="org-right">0.0e+00</td>
</tr>
<tr>
<td class="org-right">5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">5.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">0.0e+00</td>
</tr>
<tr>
<td class="org-right">5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">5.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">3.0e-05</td>
<td class="org-right">0.0e+00</td>
</tr>
<tr>
<td class="org-right">5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">5.0e-05</td>
<td class="org-right">3.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">0.0e+00</td>
</tr>
<tr>
<td class="org-right">5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">5.0e-05</td>
<td class="org-right">3.0e-05</td>
<td class="org-right">3.0e-05</td>
<td class="org-right">0.0e+00</td>
</tr>
<tr>
<td class="org-right">5.0e-05</td>
<td class="org-right">5.0e-05</td>
<td class="org-right">-5.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">-3.0e-05</td>
<td class="org-right">0.0e+00</td>
</tr>
</tbody>
</table>
<p>
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;
<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))];
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;
0 0 1];
ARB = Rz<span class="org-type">*</span>Ry<span class="org-type">*</span>Rx;
[<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)
<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)
<span class="org-keyword">end</span>
<span class="org-keyword">end</span>
</pre>
</div>
<p>
We obtain the required actuator stroke:
</p>
<pre class="example">
From -8.9e-05[m] to 8.9e-05[m]: Total stroke = 177.2[um]
</pre>
<p>
This is probably a much realistic estimation of the required actuator stroke.
</p>
</div>
</div>
</div>
<div id="outline-container-orgb685a81" class="outline-2">
<h2 id="orgb685a81"><span class="section-number-2">6</span> Estimated platform mobility from specified actuator stroke</h2>
<div class="outline-text-2" id="text-6">
<p>
<a id="orge61164c"></a>
</p>
<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>
<p>
To run the script, open the Simulink Project, and type <code>run kinematic_study_mobility.m</code>.
</p>
</div>
<p>
Here, from some value of the actuator stroke, we would like to estimate the mobility of the Stewart platform.
</p>
<p>
As explained in section <a href="#org81c3707">3</a>, the forward kinematic problem of the Stewart platform is quite difficult to solve.
However, for small displacements, we can use the Jacobian as an approximate solution.
</p>
</div>
<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>
</div>
<p>
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>
</div>
</div>
</div>
<div id="outline-container-orga6e12fe" class="outline-3">
<h3 id="orga6e12fe"><span class="section-number-3">6.2</span> Pure translations</h3>
<div class="outline-text-3" id="text-6-2">
<p>
Let&rsquo;s first estimate the mobility in translation when the orientation of the Stewart platform stays the same.
</p>
<p>
As shown previously, for such small stroke, we can use the approximate Forward Dynamics solution using the Jacobian matrix:
</p>
\begin{equation*}
\delta\bm{\mathcal{L}} = \bm{J} \delta\bm{\mathcal{X}}
\end{equation*}
<p>
To obtain the mobility &ldquo;volume&rdquo; attainable by the Stewart platform when it&rsquo;s orientation is set to zero, we use the spherical coordinate \((r, \theta, \phi)\).
</p>
<p>
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));
<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>));
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>
<span class="org-keyword">end</span>
</pre>
</div>
<p>
Now that we have found the corresponding radius \(r\), we plot the obtained mobility.
We can also approximate the mobility by a sphere with a radius equal to the minimum obtained value of \(r\), this is however a pessimistic estimation of the mobility.
</p>
<table border="2" cellspacing="0" cellpadding="6" rules="groups" frame="hsides">
<colgroup>
<col class="org-right" />
<col class="org-right" />
<col class="org-right" />
</colgroup>
<thead>
<tr>
<th scope="col" class="org-right"><code>L_min</code> [\(\mu m\)]</th>
<th scope="col" class="org-right"><code>L_max</code> [\(\mu m\)]</th>
<th scope="col" class="org-right"><code>R</code> [\(\mu m\)]</th>
</tr>
</thead>
<tbody>
<tr>
<td class="org-right">-50.0</td>
<td class="org-right">50.0</td>
<td class="org-right">31.5</td>
</tr>
</tbody>
</table>
<div id="org631ea3b" class="figure">
<p><img src="figs/mobility_translations_null_rotation.png" alt="mobility_translations_null_rotation.png" />
</p>
<p><span class="figure-number">Figure 3: </span>Obtain mobility of the Stewart platform for zero rotations (<a href="./figs/mobility_translations_null_rotation.png">png</a>, <a href="./figs/mobility_translations_null_rotation.pdf">pdf</a>)</p>
</div>
</div>
</div>
</div>
<div id="outline-container-org5be8fc9" class="outline-2">
<h2 id="org5be8fc9"><span class="section-number-2">7</span> Estimation of the Joint required Stroke</h2>
<div class="outline-text-2" id="text-7">
</div>
<div id="outline-container-org461e0b6" class="outline-3">
<h3 id="org461e0b6"><span class="section-number-3">7.1</span> Estimation with an analytical model</h3>
<div class="outline-text-3" id="text-7-1">
<p>
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]);
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>
</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>
</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)
<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))];
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;
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>
</pre>
</div>
<p>
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>
</div>
<pre class="example">
1.1704
</pre>
<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>
</div>
<pre class="example">
0.075063
</pre>
<div class="org-src-container">
<pre class="src src-matlab">1e3<span class="org-type">*</span>max(max(Rzs))
</pre>
</div>
<pre class="example">
0.04666
</pre>
</div>
</div>
<div id="outline-container-org6d0095b" class="outline-3">
<h3 id="org6d0095b"><span class="section-number-3">7.2</span> Estimation using the Simscape Model</h3>
<div class="outline-text-3" id="text-7-2">
</div>
<div id="outline-container-org656927f" class="outline-4">
<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>
</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>
</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>
</div>
</div>
</div>
<div id="outline-container-orgc18819c" class="outline-4">
<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>;
<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>};
</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>
</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>
</div>
</div>
</div>
<div id="outline-container-orgd125932" class="outline-4">
<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>
</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>
</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>
<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>);
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>
<p>
Verify that the simulations are all correct:
</p>
<div class="org-src-container">
<pre class="src src-matlab">max(cl_perf)
</pre>
</div>
<pre class="example">
8.1147
</pre>
</div>
</div>
<div id="outline-container-orgbc09d7e" class="outline-4">
<h4 id="orgbc09d7e"><span class="section-number-4">7.2.4</span> Results</h4>
<div class="outline-text-4" id="text-7-2-4">
<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">&#xa0;</th>
<th scope="col" class="org-right">Stroke [mrad]</th>
</tr>
</thead>
<tbody>
<tr>
<td class="org-left">Rx bot</td>
<td class="org-right">1.03</td>
</tr>
<tr>
<td class="org-left">Ry bot</td>
<td class="org-right">0.93</td>
</tr>
<tr>
<td class="org-left">Rx top</td>
<td class="org-right">1.06</td>
</tr>
<tr>
<td class="org-left">Ry top</td>
<td class="org-right">0.95</td>
</tr>
<tr>
<td class="org-left">Rz top</td>
<td class="org-right">0.03</td>
</tr>
</tbody>
</table>
</div>
</div>
</div>
</div>
<div id="outline-container-orgc5835cc" class="outline-2">
<h2 id="orgc5835cc"><span class="section-number-2">8</span> Functions</h2>
<div class="outline-text-2" id="text-8">
<p>
<a id="orgadc4dc6"></a>
</p>
</div>
<div id="outline-container-org7a0813a" class="outline-3">
<h3 id="org7a0813a"><span class="section-number-3">8.1</span> <code>computeJacobian</code>: Compute the Jacobian Matrix</h3>
<div class="outline-text-3" id="text-8-1">
<p>
<a id="org0a94753"></a>
</p>
<p>
This Matlab function is accessible <a href="../src/computeJacobian.m">here</a>.
</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 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>
</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 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;
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;
</pre>
</div>
</div>
</div>
<div id="outline-container-org01f1158" class="outline-4">
<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>
</div>
</div>
</div>
<div id="outline-container-org91d652d" class="outline-4">
<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>
</div>
</div>
</div>
<div id="outline-container-org323b34e" class="outline-4">
<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>
</div>
</div>
</div>
<div id="outline-container-orgebce485" class="outline-4">
<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>
</div>
</div>
</div>
</div>
<div id="outline-container-org710c2c8" class="outline-3">
<h3 id="org710c2c8"><span class="section-number-3">8.2</span> <code>inverseKinematics</code>: Compute Inverse Kinematics</h3>
<div class="outline-text-3" id="text-8-2">
<p>
<a id="orgb533a06"></a>
</p>
<p>
This Matlab function is accessible <a href="../src/inverseKinematics.m">here</a>.
</p>
</div>
<div id="outline-container-orge7e6266" class="outline-4">
<h4 id="orge7e6266">Theory</h4>
<div class="outline-text-4" id="text-orge7e6266">
<p>
For inverse kinematic analysis, it is assumed that the position \({}^A\bm{P}\) and orientation of the moving platform \({}^A\bm{R}_B\) are given and the problem is to obtain the joint variables, namely, \(\bm{L} = [l_1, l_2, \dots, l_6]^T\).
</p>
<p>
From the geometry of the manipulator, the loop closure for each limb, \(i = 1, 2, \dots, 6\) can be written as
</p>
\begin{align*}
l_i {}^A\hat{\bm{s}}_i &= {}^A\bm{A} + {}^A\bm{b}_i - {}^A\bm{a}_i \\
&= {}^A\bm{A} + {}^A\bm{R}_b {}^B\bm{b}_i - {}^A\bm{a}_i
\end{align*}
<p>
To obtain the length of each actuator and eliminate \(\hat{\bm{s}}_i\), it is sufficient to dot multiply each side by itself:
</p>
\begin{equation}
l_i^2 \left[ {}^A\hat{\bm{s}}_i^T {}^A\hat{\bm{s}}_i \right] = \left[ {}^A\bm{P} + {}^A\bm{R}_B {}^B\bm{b}_i - {}^A\bm{a}_i \right]^T \left[ {}^A\bm{P} + {}^A\bm{R}_B {}^B\bm{b}_i - {}^A\bm{a}_i \right]
\end{equation}
<p>
Hence, for \(i = 1, 2, \dots, 6\), each limb length can be uniquely determined by:
</p>
\begin{equation}
l_i = \sqrt{{}^A\bm{P}^T {}^A\bm{P} + {}^B\bm{b}_i^T {}^B\bm{b}_i + {}^A\bm{a}_i^T {}^A\bm{a}_i - 2 {}^A\bm{P}^T {}^A\bm{a}_i + 2 {}^A\bm{P}^T \left[{}^A\bm{R}_B {}^B\bm{b}_i\right] - 2 \left[{}^A\bm{R}_B {}^B\bm{b}_i\right]^T {}^A\bm{a}_i}
\end{equation}
<p>
If the position and orientation of the moving platform lie in the feasible workspace of the manipulator, one unique solution to the limb length is determined by the above equation.
Otherwise, when the limbs&rsquo; lengths derived yield complex numbers, then the position or orientation of the moving platform is not reachable.
</p>
</div>
</div>
<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>
</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 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>
</div>
</div>
</div>
<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;
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;
</pre>
</div>
</div>
</div>
<div id="outline-container-org7189e65" class="outline-4">
<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>
</div>
<div class="org-src-container">
<pre class="src src-matlab">dLi = Li<span class="org-type">-</span>l;
</pre>
</div>
</div>
</div>
</div>
<div id="outline-container-orgdc218cd" class="outline-3">
<h3 id="orgdc218cd"><span class="section-number-3">8.3</span> <code>forwardKinematicsApprox</code>: Compute the Approximate Forward Kinematics</h3>
<div class="outline-text-3" id="text-8-3">
<p>
<a id="orgb960aea"></a>
</p>
<p>
This Matlab function is accessible <a href="../src/forwardKinematicsApprox.m">here</a>.
</p>
</div>
<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>
</div>
</div>
</div>
<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>
</div>
</div>
</div>
<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>
</div>
</div>
</div>
<div id="outline-container-orga496714" class="outline-4">
<h4 id="orga496714">Computation</h4>
<div class="outline-text-4" id="text-orga496714">
<p>
From a small displacement of each strut \(d\bm{\mathcal{L}}\), we can compute the
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>
</div>
<p>
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>
</div>
<p>
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>
</div>
<p>
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>
</div>
</div>
</div>
</div>
</div>
<p>
</p>
<style>.csl-entry{text-indent: -1.5em; margin-left: 1.5em;}</style><h2 class='citeproc-org-bib-h2'>Bibliography</h2>
<div class="csl-bib-body">
<div class="csl-entry"><a name="citeproc_bib_item_1"></a>Taghirad, Hamid. 2013. <i>Parallel Robots : Mechanics and Control</i>. Boca Raton, FL: CRC Press.</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>