stewart-simscape/org/kinematic-study.org

882 lines
37 KiB
Org Mode
Raw Normal View History

#+TITLE: Kinematic Study of the Stewart Platform
:DRAWER:
2020-02-11 15:50:52 +01:00
#+STARTUP: overview
#+LANGUAGE: en
#+EMAIL: dehaeze.thomas@gmail.com
#+AUTHOR: Dehaeze Thomas
#+HTML_LINK_HOME: ./index.html
#+HTML_LINK_UP: ./index.html
#+HTML_HEAD: <link rel="stylesheet" type="text/css" href="./css/htmlize.css"/>
#+HTML_HEAD: <link rel="stylesheet" type="text/css" href="./css/readtheorg.css"/>
#+HTML_HEAD: <script src="./js/jquery.min.js"></script>
#+HTML_HEAD: <script src="./js/bootstrap.min.js"></script>
#+HTML_HEAD: <script src="./js/jquery.stickytableheaders.min.js"></script>
#+HTML_HEAD: <script src="./js/readtheorg.js"></script>
#+PROPERTY: header-args:matlab :session *MATLAB*
#+PROPERTY: header-args:matlab+ :comments org
#+PROPERTY: header-args:matlab+ :exports both
#+PROPERTY: header-args:matlab+ :results none
#+PROPERTY: header-args:matlab+ :eval no-export
#+PROPERTY: header-args:matlab+ :noweb yes
#+PROPERTY: header-args:matlab+ :mkdirp yes
#+PROPERTY: header-args:matlab+ :output-dir figs
2020-02-11 15:27:39 +01:00
#+PROPERTY: header-args:latex :headers '("\\usepackage{tikz}" "\\usepackage{import}" "\\import{$HOME/Cloud/thesis/latex/}{config.tex}")
#+PROPERTY: header-args:latex+ :imagemagick t :fit yes
#+PROPERTY: header-args:latex+ :iminoptions -scale 100% -density 150
#+PROPERTY: header-args:latex+ :imoutoptions -quality 100
2020-02-11 15:50:52 +01:00
#+PROPERTY: header-args:latex+ :results file raw replace
#+PROPERTY: header-args:latex+ :buffer no
2020-02-11 15:27:39 +01:00
#+PROPERTY: header-args:latex+ :eval no-export
2020-02-11 15:50:52 +01:00
#+PROPERTY: header-args:latex+ :exports results
2020-02-11 15:27:39 +01:00
#+PROPERTY: header-args:latex+ :mkdirp yes
#+PROPERTY: header-args:latex+ :output-dir figs
2020-02-11 15:50:52 +01:00
#+PROPERTY: header-args:latex+ :post pdf2svg(file=*this*, ext="png")
:END:
2020-01-29 13:21:30 +01:00
* Introduction :ignore:
The kinematic analysis of a parallel manipulator is well described in cite:taghirad13_paral:
#+begin_quote
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.
#+end_quote
The current document is divided in the following sections:
- Section [[sec:jacobian_analysis]]: 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.
- Section [[sec:stiffness_analysis]]: The stiffness and compliance matrices are derived from the Jacobian matrix and the stiffness of each strut.
- Section [[sec:forward_inverse_kinematics]]: The Forward and Inverse kinematic problems are presented.
2020-02-13 16:46:47 +01:00
- Section [[sec:kinematic_study_approximation_validity]]: The approximate solution of the Inverse kinematic problem is compared with the exact solution in order to determine the validity of the approximation.
- Section [[sec:kinematic_study_required_actuator_stroke]]: The Inverse kinematic solution is used to estimate required actuator stroke from the wanted mobility of the Stewart platform.
* Jacobian Analysis
<<sec:jacobian_analysis>>
** Introduction :ignore:
From cite:taghirad13_paral:
#+begin_quote
The Jacobian matrix not only reveals the *relation between the joint variable velocities of a parallel manipulator to the moving platform linear and angular velocities*, it also constructs the transformation needed to find the *actuator forces from the forces and moments acting on the moving platform*.
#+end_quote
** Jacobian Computation
If we note:
- ${}^A\hat{\bm{s}}_i$ the unit vector representing the direction of the i'th strut and expressed in frame $\{A\}$
- ${}^A\bm{b}_i$ the position vector of the i'th joint fixed to the mobile platform and expressed in frame $\{A\}$
Then, we can compute the Jacobian with the following equation (the superscript $A$ is ignored):
\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*}
The Jacobian matrix $\bm{J}$ can be computed using the =computeJacobian= function (accessible [[sec:computeJacobian][here]]).
For instance:
#+begin_src matlab :eval no
stewart = computeJacobian(stewart);
#+end_src
This will add three new matrix to the =stewart= structure:
- =J= the Jacobian matrix
- =K= the stiffness matrix
- =C= the compliance matrix
** Jacobian - Velocity loop closure
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$:
\begin{equation*}
\dot{\bm{\mathcal{L}}} = \bm{J} \dot{\bm{\mathcal{X}}}
\end{equation*}
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 "Transform Sensor" block measuring the relative velocity and relative angular velocity of frame $\{B\}$ with respect to frame $\{A\}$.
If the Jacobian matrix is inversible, we can also compute $\dot{\bm{\mathcal{X}}}$ from $\dot{\bm{\mathcal{L}}}$.
\begin{equation*}
\dot{\bm{\mathcal{X}}} = \bm{J}^{-1} \dot{\bm{\mathcal{L}}}
\end{equation*}
The Jacobian matrix can also be used to approximate forward and inverse kinematics for small displacements.
This is explained in section [[sec:approximate_forward_inverse_kinematics]].
** Jacobian - Static Force Transformation
If we note:
- $\bm{\tau} = [\tau_1, \tau_2, \cdots, \tau_6]^T$: vector of actuator forces applied in each strut
- $\bm{\mathcal{F}} = [\bm{f}, \bm{n}]^T$: external force/torque action on the mobile platform at $\bm{O}_B$
We find that the transpose of the Jacobian matrix links the two by the following equation:
\begin{equation*}
\bm{\mathcal{F}} = \bm{J}^T \bm{\tau}
\end{equation*}
If the Jacobian matrix is inversible, we also have the following relation:
\begin{equation*}
\bm{\tau} = \bm{J}^{-T} \bm{\mathcal{F}}
\end{equation*}
* Stiffness Analysis
<<sec:stiffness_analysis>>
** Introduction :ignore:
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 *structural stiffness*.
** Computation of the Stiffness and Compliance Matrix
As explain in [[file:stewart-architecture.org][this]] document, each Actuator is modeled by 3 elements in parallel:
- A spring with a stiffness $k_{i}$
- A dashpot with a damping $c_{i}$
The stiffness of the actuator $k_i$ links the applied actuator force $\delta \tau_i$ and the corresponding small deflection $\delta l_i$:
\begin{equation*}
\tau_i = k_i \delta l_i, \quad i = 1,\ \dots,\ 6
\end{equation*}
If we combine these 6 relations:
\begin{equation*}
\bm{\tau} = \mathcal{K} \delta \bm{\mathcal{L}} \quad \mathcal{K} = \text{diag}\left[ k_1,\ \dots,\ k_6 \right]
\end{equation*}
Substituting $\bm{\tau} = \bm{J}^{-T} \bm{\mathcal{F}}$ and $\delta \bm{\mathcal{L}} = \bm{J} \cdot \delta \bm{\mathcal{X}}$ gives
\begin{equation*}
\bm{\mathcal{F}} = \bm{J}^T \mathcal{K} \bm{J} \cdot \delta \bm{\mathcal{X}}
\end{equation*}
And then we identify the stiffness matrix $\bm{K}$:
\begin{equation*}
\bm{K} = \bm{J}^T \mathcal{K} \bm{J}
\end{equation*}
If the stiffness matrix $\bm{K}$ is inversible, the *compliance matrix* of the manipulator is defined as
\begin{equation*}
\bm{C} = \bm{K}^{-1} = (\bm{J}^T \mathcal{K} \bm{J})^{-1}
\end{equation*}
The compliance matrix of a manipulator shows the mapping of the moving platform wrench applied at $\bm{O}_B$ to its small deflection by
\begin{equation*}
\delta \bm{\mathcal{X}} = \bm{C} \cdot \bm{\mathcal{F}}
\end{equation*}
The stiffness and compliance matrices are computed using the =computeJacobian= function (accessible [[sec:computeJacobian][here]]).
* Forward and Inverse Kinematics
<<sec:forward_inverse_kinematics>>
** Inverse Kinematics
<<sec:inverse_kinematics>>
#+begin_quote
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 $\bm{\mathcal{L}} = \left[ l_1, l_2, l_3, l_4, l_5, l_6 \right]^T$.
#+end_quote
This problem can be easily solved using the loop closures.
The obtain joint variables are:
\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*}
If the position and orientation of the platform lie in the feasible workspace, the solution is unique.
Otherwise, the solution gives complex numbers.
This inverse kinematic solution can be obtained using the function =inverseKinematics= (described [[sec:inverseKinematics][here]]).
** Forward Kinematics
<<sec:forward_kinematics>>
#+begin_quote
In *forward kinematic analysis*, 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$.
#+end_quote
This is a difficult problem that requires to solve nonlinear equations.
In a next section, an approximate solution of the forward kinematics problem is proposed for small displacements.
** Approximate solution of the Forward and Inverse Kinematic problem for small displacement using the Jacobian matrix
<<sec:approximate_forward_inverse_kinematics>>
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):
\begin{equation*}
\delta\bm{\mathcal{L}} = \bm{J} \delta\bm{\mathcal{X}}
\end{equation*}
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):
\begin{equation*}
\delta\bm{\mathcal{X}} = \bm{J}^{-1} \delta\bm{\mathcal{L}}
\end{equation*}
These two relations solve the forward and inverse kinematic problems for small displacement in a *approximate* 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.
The function =forwardKinematicsApprox= (described [[sec:forwardKinematicsApprox][here]]) can be used to solve the forward kinematic problem using the Jacobian matrix.
2020-02-13 16:46:47 +01:00
* Estimation of the range validity of the approximate inverse kinematics
2020-01-30 11:12:06 +01:00
:PROPERTIES:
2020-02-13 16:46:47 +01:00
:header-args:matlab+: :tangle ../matlab/kinematic_study_approximation_validity.m
2020-01-30 11:12:06 +01:00
:header-args:matlab+: :comments org :mkdirp yes
:END:
2020-02-13 16:46:47 +01:00
<<sec:kinematic_study_approximation_validity>>
2020-01-30 11:12:06 +01:00
2020-02-13 16:46:47 +01:00
#+begin_note
The Matlab script corresponding to this section is accessible [[file:../matlab/kinematic_study_approximation_validity.m][here]].
To run the script, open the Simulink Project, and type =run kinematic_study_approximation_validity.m=.
#+end_note
** Introduction :ignore:
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.
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.
2020-02-13 16:46:47 +01:00
** Matlab Init :noexport:ignore:
#+begin_src matlab :tangle no :exports none :results silent :noweb yes :var current_dir=(file-name-directory buffer-file-name)
<<matlab-dir>>
#+end_src
#+begin_src matlab :exports none :results silent :noweb yes
<<matlab-init>>
#+end_src
#+begin_src matlab :results none :exports none
2020-02-11 15:50:52 +01:00
simulinkproject('../');
#+end_src
2020-02-13 16:46:47 +01:00
** Stewart architecture definition
We first define some general Stewart architecture.
#+begin_src matlab
2020-02-11 15:21:39 +01:00
stewart = initializeStewartPlatform();
stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-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);
#+end_src
2020-02-13 16:46:47 +01:00
** Comparison for "pure" translations
Let's first compare the perfect and approximate solution of the inverse for pure $x$ translations.
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 [[fig:inverse_kinematics_approx_validity_x_translation]].
The relative strut length displacement is shown in Figure [[fig:inverse_kinematics_approx_validity_x_translation_relative]].
#+begin_src matlab
Xrs = logspace(-6, -1, 100); % Wanted X translation of the mobile platform [m]
Ls_approx = zeros(6, length(Xrs));
Ls_exact = zeros(6, length(Xrs));
for i = 1:length(Xrs)
Xr = Xrs(i);
L_approx(:, i) = stewart.kinematics.J*[Xr; 0; 0; 0; 0; 0;];
[~, L_exact(:, i)] = inverseKinematics(stewart, 'AP', [Xr; 0; 0]);
end
#+end_src
#+begin_src matlab :exports none
figure;
hold on;
for i = 1:6
set(gca,'ColorOrderIndex',i);
plot(Xrs, abs(L_approx(i, :)));
set(gca,'ColorOrderIndex',i);
plot(Xrs, abs(L_exact(i, :)), '--');
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
xlabel('Wanted $x$ displacement [m]');
ylabel('Estimated required stroke');
#+end_src
#+HEADER: :tangle no :exports results :results none :noweb yes
#+begin_src matlab :var filepath="figs/inverse_kinematics_approx_validity_x_translation.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png")
<<plt-matlab>>
#+end_src
#+NAME: fig:inverse_kinematics_approx_validity_x_translation
#+CAPTION: Comparison of the Approximate solution and True solution for the Inverse kinematic problem ([[./figs/inverse_kinematics_approx_validity_x_translation.png][png]], [[./figs/inverse_kinematics_approx_validity_x_translation.pdf][pdf]])
[[file:figs/inverse_kinematics_approx_validity_x_translation.png]]
#+begin_src matlab :exports none
figure;
hold on;
for i = 1:6
plot(Xrs, abs(L_approx(i, :) - L_exact(i, :))./abs(L_approx(i, :) + L_exact(i, :)), 'k-');
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
xlabel('Wanted $x$ displacement [m]');
ylabel('Relative Stroke Error');
#+end_src
#+HEADER: :tangle no :exports results :results none :noweb yes
#+begin_src matlab :var filepath="figs/inverse_kinematics_approx_validity_x_translation_relative.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png")
<<plt-matlab>>
#+end_src
#+NAME: fig:inverse_kinematics_approx_validity_x_translation_relative
#+CAPTION: Relative length error by using the Approximate solution of the Inverse kinematic problem ([[./figs/inverse_kinematics_approx_validity_x_translation_relative.png][png]], [[./figs/inverse_kinematics_approx_validity_x_translation_relative.pdf][pdf]])
[[file:figs/inverse_kinematics_approx_validity_x_translation_relative.png]]
2020-02-13 16:46:47 +01:00
** Conclusion
#+begin_important
For small wanted displacements (up to $\approx 1\%$ of the size of the Hexapod), the approximate inverse kinematic solution using the Jacobian matrix is quite correct.
#+end_important
* Estimated required actuator stroke from specified platform mobility
2020-01-30 11:12:06 +01:00
:PROPERTIES:
2020-02-13 16:46:47 +01:00
:header-args:matlab+: :tangle ../matlab/kinematic_study_required_actuator_stroke.m
2020-01-30 11:12:06 +01:00
:header-args:matlab+: :comments org :mkdirp yes
:END:
2020-02-13 16:46:47 +01:00
<<sec:kinematic_study_required_actuator_stroke>>
#+begin_note
The Matlab script corresponding to this section is accessible [[file:../matlab/kinematic_study_required_actuator_stroke.m][here]].
To run the script, open the Simulink Project, and type =run kinematic_study_required_actuator_stroke.m=.
#+end_note
** Introduction :ignore:
Let'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.
** Matlab Init :noexport:ignore:
2020-01-22 15:32:32 +01:00
#+begin_src matlab :tangle no :exports none :results silent :noweb yes :var current_dir=(file-name-directory buffer-file-name)
<<matlab-dir>>
#+end_src
#+begin_src matlab :exports none :results silent :noweb yes
<<matlab-init>>
2020-01-22 15:32:32 +01:00
#+end_src
#+begin_src matlab :results none :exports none
2020-02-11 15:50:52 +01:00
simulinkproject('../');
#+end_src
** Stewart architecture definition
Let's first define the Stewart platform architecture that we want to study.
#+begin_src matlab
2020-02-11 15:21:39 +01:00
stewart = initializeStewartPlatform();
stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-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);
#+end_src
** Wanted translations and rotations
Let's now define the wanted extreme translations and rotations.
#+begin_src matlab
Tx_max = 50e-6; % Translation [m]
Ty_max = 50e-6; % Translation [m]
Tz_max = 50e-6; % Translation [m]
Rx_max = 30e-6; % Rotation [rad]
Ry_max = 30e-6; % Rotation [rad]
Rz_max = 0; % Rotation [rad]
#+end_src
** Needed stroke for "pure" rotations or translations
As a first estimation, we estimate the needed actuator stroke for "pure" rotations and translation.
We do that using either the Inverse Kinematic solution or the Jacobian matrix as an approximation.
#+begin_src matlab
LTx = stewart.kinematics.J*[Tx_max 0 0 0 0 0]';
LTy = stewart.kinematics.J*[0 Ty_max 0 0 0 0]';
LTz = stewart.kinematics.J*[0 0 Tz_max 0 0 0]';
LRx = stewart.kinematics.J*[0 0 0 Rx_max 0 0]';
LRy = stewart.kinematics.J*[0 0 0 0 Ry_max 0]';
LRz = stewart.kinematics.J*[0 0 0 0 0 Rz_max]';
#+end_src
The obtain required stroke is:
#+begin_src matlab :results value replace :exports results
ans = sprintf('From %.2g[m] to %.2g[m]: Total stroke = %.1f[um]', min(min([LTx,LTy,LTz,LRx,LRy])), max(max([LTx,LTy,LTz,LRx,LRy])), 1e6*(max(max([LTx,LTy,LTz,LRx,LRy]))-min(min([LTx,LTy,LTz,LRx,LRy]))))
#+end_src
#+RESULTS:
: From -3.8e-05[m] to 3.8e-05[m]: Total stroke = 76.1[um]
This is surely a low estimation of the required stroke.
** Needed stroke for "combined" rotations or translations
We know would like to have a more precise estimation.
To do so, we may estimate the required actuator stroke for all possible combination of translation and rotation.
Let's first generate all the possible combination of maximum translation and rotations.
#+begin_src matlab
Ps = [2*(dec2bin(0:5^2-1,5)-'0')-1, zeros(5^2, 1)].*[Tx_max Ty_max Tz_max Rx_max Ry_max Rz_max];
#+end_src
#+begin_src matlab :exports results :results value table replace :tangle no :post addhdr(*this*)
data2orgtable(Ps, {}, {'*Tx [m]*', '*Ty [m]*', '*Tz [m]*', '*Rx [rad]*', '*Ry [rad]*', '*Rz [rad]*'}, ' %.1e ');
#+end_src
#+RESULTS:
| *Tx [m]* | *Ty [m]* | *Tz [m]* | *Rx [rad]* | *Ry [rad]* | *Rz [rad]* |
|----------+----------+----------+------------+------------+------------|
| -5.0e-05 | -5.0e-05 | -5.0e-05 | -3.0e-05 | -3.0e-05 | 0.0e+00 |
| -5.0e-05 | -5.0e-05 | -5.0e-05 | -3.0e-05 | 3.0e-05 | 0.0e+00 |
| -5.0e-05 | -5.0e-05 | -5.0e-05 | 3.0e-05 | -3.0e-05 | 0.0e+00 |
| -5.0e-05 | -5.0e-05 | -5.0e-05 | 3.0e-05 | 3.0e-05 | 0.0e+00 |
| -5.0e-05 | -5.0e-05 | 5.0e-05 | -3.0e-05 | -3.0e-05 | 0.0e+00 |
| -5.0e-05 | -5.0e-05 | 5.0e-05 | -3.0e-05 | 3.0e-05 | 0.0e+00 |
| -5.0e-05 | -5.0e-05 | 5.0e-05 | 3.0e-05 | -3.0e-05 | 0.0e+00 |
| -5.0e-05 | -5.0e-05 | 5.0e-05 | 3.0e-05 | 3.0e-05 | 0.0e+00 |
| -5.0e-05 | 5.0e-05 | -5.0e-05 | -3.0e-05 | -3.0e-05 | 0.0e+00 |
| -5.0e-05 | 5.0e-05 | -5.0e-05 | -3.0e-05 | 3.0e-05 | 0.0e+00 |
| -5.0e-05 | 5.0e-05 | -5.0e-05 | 3.0e-05 | -3.0e-05 | 0.0e+00 |
| -5.0e-05 | 5.0e-05 | -5.0e-05 | 3.0e-05 | 3.0e-05 | 0.0e+00 |
| -5.0e-05 | 5.0e-05 | 5.0e-05 | -3.0e-05 | -3.0e-05 | 0.0e+00 |
| -5.0e-05 | 5.0e-05 | 5.0e-05 | -3.0e-05 | 3.0e-05 | 0.0e+00 |
| -5.0e-05 | 5.0e-05 | 5.0e-05 | 3.0e-05 | -3.0e-05 | 0.0e+00 |
| -5.0e-05 | 5.0e-05 | 5.0e-05 | 3.0e-05 | 3.0e-05 | 0.0e+00 |
| 5.0e-05 | -5.0e-05 | -5.0e-05 | -3.0e-05 | -3.0e-05 | 0.0e+00 |
| 5.0e-05 | -5.0e-05 | -5.0e-05 | -3.0e-05 | 3.0e-05 | 0.0e+00 |
| 5.0e-05 | -5.0e-05 | -5.0e-05 | 3.0e-05 | -3.0e-05 | 0.0e+00 |
| 5.0e-05 | -5.0e-05 | -5.0e-05 | 3.0e-05 | 3.0e-05 | 0.0e+00 |
| 5.0e-05 | -5.0e-05 | 5.0e-05 | -3.0e-05 | -3.0e-05 | 0.0e+00 |
| 5.0e-05 | -5.0e-05 | 5.0e-05 | -3.0e-05 | 3.0e-05 | 0.0e+00 |
| 5.0e-05 | -5.0e-05 | 5.0e-05 | 3.0e-05 | -3.0e-05 | 0.0e+00 |
| 5.0e-05 | -5.0e-05 | 5.0e-05 | 3.0e-05 | 3.0e-05 | 0.0e+00 |
| 5.0e-05 | 5.0e-05 | -5.0e-05 | -3.0e-05 | -3.0e-05 | 0.0e+00 |
For all possible combination, we compute the required actuator stroke using the inverse kinematic solution.
#+begin_src matlab
L_min = 0;
L_max = 0;
for i = 1:size(Ps,1)
Rx = [1 0 0;
0 cos(Ps(i, 4)) -sin(Ps(i, 4));
0 sin(Ps(i, 4)) cos(Ps(i, 4))];
Ry = [ cos(Ps(i, 5)) 0 sin(Ps(i, 5));
0 1 0;
-sin(Ps(i, 5)) 0 cos(Ps(i, 5))];
Rz = [cos(Ps(i, 6)) -sin(Ps(i, 6)) 0;
sin(Ps(i, 6)) cos(Ps(i, 6)) 0;
0 0 1];
ARB = Rz*Ry*Rx;
[~, Ls] = inverseKinematics(stewart, 'AP', Ps(i, 1:3)', 'ARB', ARB);
if min(Ls) < L_min
L_min = min(Ls)
end
if max(Ls) > L_max
L_max = max(Ls)
end
end
#+end_src
We obtain the required actuator stroke:
#+begin_src matlab :results value replace :exports results
ans = sprintf('From %.2g[m] to %.2g[m]: Total stroke = %.1f[um]', L_min, L_max, 1e6*(L_max-L_min))
#+end_src
#+RESULTS:
: From -8.9e-05[m] to 8.9e-05[m]: Total stroke = 177.2[um]
This is probably a much realistic estimation of the required actuator stroke.
* Estimated platform mobility from specified actuator stroke
2020-01-30 11:12:06 +01:00
:PROPERTIES:
2020-02-13 16:46:47 +01:00
:header-args:matlab+: :tangle ../matlab/kinematic_study_mobility.m
2020-01-30 11:12:06 +01:00
:header-args:matlab+: :comments org :mkdirp yes
:END:
2020-02-13 16:46:47 +01:00
<<sec:kinematic_study_mobility>>
#+begin_note
The Matlab script corresponding to this section is accessible [[file:../matlab/kinematic_study_mobility.m][here]].
To run the script, open the Simulink Project, and type =run kinematic_study_mobility.m=.
#+end_note
** Introduction :ignore:
Here, from some value of the actuator stroke, we would like to estimate the mobility of the Stewart platform.
As explained in section [[sec:forward_inverse_kinematics]], 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.
** Matlab Init :noexport:ignore:
#+begin_src matlab :tangle no :exports none :results silent :noweb yes :var current_dir=(file-name-directory buffer-file-name)
<<matlab-dir>>
#+end_src
#+begin_src matlab :exports none :results silent :noweb yes
<<matlab-init>>
#+end_src
#+begin_src matlab :results none :exports none
2020-02-11 15:50:52 +01:00
simulinkproject('../');
#+end_src
** Stewart architecture definition
Let's first define the Stewart platform architecture that we want to study.
#+begin_src matlab
2020-02-11 15:21:39 +01:00
stewart = initializeStewartPlatform();
stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-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);
#+end_src
Let's now define the actuator stroke.
#+begin_src matlab
L_min = -50e-6; % [m]
L_max = 50e-6; % [m]
#+end_src
** Pure translations
Let's first estimate the mobility in translation when the orientation of the Stewart platform stays the same.
As shown previously, for such small stroke, we can use the approximate Forward Dynamics solution using the Jacobian matrix:
\begin{equation*}
\delta\bm{\mathcal{L}} = \bm{J} \delta\bm{\mathcal{X}}
\end{equation*}
To obtain the mobility "volume" attainable by the Stewart platform when it's orientation is set to zero, we use the spherical coordinate $(r, \theta, \phi)$.
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 =L_min= and =L_max=.
#+begin_src matlab
thetas = linspace(0, pi, 50);
phis = linspace(0, 2*pi, 50);
rs = zeros(length(thetas), length(phis));
for i = 1:length(thetas)
for j = 1:length(phis)
Tx = sin(thetas(i))*cos(phis(j));
Ty = sin(thetas(i))*sin(phis(j));
Tz = cos(thetas(i));
dL = stewart.kinematics.J*[Tx; Ty; Tz; 0; 0; 0;]; % dL required for 1m displacement in theta/phi direction
rs(i, j) = max([dL(dL<0)*L_min; dL(dL>0)*L_max]);
end
end
#+end_src
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.
#+begin_src matlab :exports results :results value table replace :tangle no :post addhdr(*this*)
data2orgtable([1e6*L_min, 1e6*L_max, 1e6*(min(min(rs)))], {}, {'=L_min= [$\mu m$]', '=L_max= [$\mu m$]', '=R= [$\mu m$]'}, ' %.1f ');
#+end_src
#+RESULTS:
| =L_min= [$\mu m$] | =L_max= [$\mu m$] | =R= [$\mu m$] |
|-------------------+-------------------+---------------|
| -50.0 | 50.0 | 31.5 |
#+begin_src matlab :exports none
figure;
plot3(reshape(rs.*(sin(thetas)'*cos(phis)), [1, length(thetas)*length(phis)]), ...
reshape(rs.*(sin(thetas)'*sin(phis)), [1, length(thetas)*length(phis)]), ...
reshape(rs.*(cos(thetas)'*ones(1, length(phis))), [1, length(thetas)*length(phis)]))
xlabel('X Translation [m]');
ylabel('Y Translation [m]');
zlabel('Z Translation [m]');
#+end_src
#+HEADER: :tangle no :exports results :results none :noweb yes
#+begin_src matlab :var filepath="figs/mobility_translations_null_rotation.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png")
<<plt-matlab>>
#+end_src
#+NAME: fig:mobility_translations_null_rotation
#+CAPTION: Obtain mobility of the Stewart platform for zero rotations ([[./figs/mobility_translations_null_rotation.png][png]], [[./figs/mobility_translations_null_rotation.pdf][pdf]])
[[file:figs/mobility_translations_null_rotation.png]]
*** TODO Do that by slice :noexport:
using this function https://fr.mathworks.com/help/matlab/ref/contour3.html
* Functions
<<sec:functions>>
2020-01-28 17:38:19 +01:00
** =computeJacobian=: Compute the Jacobian Matrix
:PROPERTIES:
2020-02-11 18:04:45 +01:00
:header-args:matlab+: :tangle ../src/computeJacobian.m
2020-01-28 17:38:19 +01:00
:header-args:matlab+: :comments none :mkdirp yes :eval no
:END:
<<sec:computeJacobian>>
2020-02-11 18:04:45 +01:00
This Matlab function is accessible [[file:../src/computeJacobian.m][here]].
2020-01-28 17:38:19 +01:00
*** Function description
:PROPERTIES:
:UNNUMBERED: t
:END:
2020-01-28 17:38:19 +01:00
#+begin_src matlab
function [stewart] = computeJacobian(stewart)
% computeJacobian -
%
% Syntax: [stewart] = computeJacobian(stewart)
%
% Inputs:
% - stewart - With at least the following fields:
% - geometry.As [3x6] - The 6 unit vectors for each strut expressed in {A}
% - geometry.Ab [3x6] - The 6 position of the joints bi expressed in {A}
% - actuators.K [6x1] - Total stiffness of the actuators
2020-01-28 17:38:19 +01:00
%
% Outputs:
% - stewart - With the 3 added field:
% - kinematics.J [6x6] - The Jacobian Matrix
% - kinematics.K [6x6] - The Stiffness Matrix
% - kinematics.C [6x6] - The Compliance Matrix
2020-01-28 17:38:19 +01:00
#+end_src
*** Check the =stewart= structure elements
:PROPERTIES:
:UNNUMBERED: t
:END:
#+begin_src matlab
assert(isfield(stewart.geometry, 'As'), 'stewart.geometry should have attribute As')
As = stewart.geometry.As;
assert(isfield(stewart.geometry, 'Ab'), 'stewart.geometry should have attribute Ab')
Ab = stewart.geometry.Ab;
assert(isfield(stewart.actuators, 'K'), 'stewart.actuators should have attribute K')
Ki = stewart.actuators.K;
#+end_src
2020-01-28 17:38:19 +01:00
*** Compute Jacobian Matrix
:PROPERTIES:
:UNNUMBERED: t
:END:
2020-01-28 17:38:19 +01:00
#+begin_src matlab
J = [As' , cross(Ab, As)'];
2020-01-28 17:38:19 +01:00
#+end_src
*** Compute Stiffness Matrix
:PROPERTIES:
:UNNUMBERED: t
:END:
2020-01-28 17:38:19 +01:00
#+begin_src matlab
K = J'*diag(Ki)*J;
2020-01-28 17:38:19 +01:00
#+end_src
*** Compute Compliance Matrix
:PROPERTIES:
:UNNUMBERED: t
:END:
2020-01-28 17:38:19 +01:00
#+begin_src matlab
C = inv(K);
2020-01-28 17:38:19 +01:00
#+end_src
*** Populate the =stewart= structure
:PROPERTIES:
:UNNUMBERED: t
:END:
#+begin_src matlab
stewart.kinematics.J = J;
stewart.kinematics.K = K;
stewart.kinematics.C = C;
#+end_src
2020-01-28 17:38:19 +01:00
** =inverseKinematics=: Compute Inverse Kinematics
:PROPERTIES:
2020-02-11 18:04:45 +01:00
:header-args:matlab+: :tangle ../src/inverseKinematics.m
2020-01-28 17:38:19 +01:00
:header-args:matlab+: :comments none :mkdirp yes :eval no
:END:
<<sec:inverseKinematics>>
2020-02-11 18:04:45 +01:00
This Matlab function is accessible [[file:../src/inverseKinematics.m][here]].
2020-01-28 17:38:19 +01:00
*** Theory
:PROPERTIES:
:UNNUMBERED: t
:END:
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$.
From the geometry of the manipulator, the loop closure for each limb, $i = 1, 2, \dots, 6$ can be written as
\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*}
To obtain the length of each actuator and eliminate $\hat{\bm{s}}_i$, it is sufficient to dot multiply each side by itself:
\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}
Hence, for $i = 1, 2, \dots, 6$, each limb length can be uniquely determined by:
\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}
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' lengths derived yield complex numbers, then the position or orientation of the moving platform is not reachable.
2020-01-28 17:38:19 +01:00
*** Function description
:PROPERTIES:
:UNNUMBERED: t
:END:
2020-01-28 17:38:19 +01:00
#+begin_src matlab
function [Li, dLi] = inverseKinematics(stewart, args)
% inverseKinematics - Compute the needed length of each strut to have the wanted position and orientation of {B} with respect to {A}
%
% Syntax: [stewart] = inverseKinematics(stewart)
%
% Inputs:
% - stewart - A structure with the following fields
% - geometry.Aa [3x6] - The positions ai expressed in {A}
% - geometry.Bb [3x6] - The positions bi expressed in {B}
% - geometry.l [6x1] - Length of each strut
2020-01-28 17:38:19 +01:00
% - args - Can have the following fields:
% - AP [3x1] - The wanted position of {B} with respect to {A}
% - ARB [3x3] - The rotation matrix that gives the wanted orientation of {B} with respect to {A}
%
% Outputs:
% - Li [6x1] - The 6 needed length of the struts in [m] to have the wanted pose of {B} w.r.t. {A}
% - 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}
#+end_src
*** Optional Parameters
:PROPERTIES:
:UNNUMBERED: t
:END:
2020-01-28 17:38:19 +01:00
#+begin_src matlab
arguments
stewart
args.AP (3,1) double {mustBeNumeric} = zeros(3,1)
args.ARB (3,3) double {mustBeNumeric} = eye(3)
end
#+end_src
*** Check the =stewart= structure elements
:PROPERTIES:
:UNNUMBERED: t
:END:
#+begin_src matlab
assert(isfield(stewart.geometry, 'Aa'), 'stewart.geometry should have attribute Aa')
Aa = stewart.geometry.Aa;
2020-01-28 17:38:19 +01:00
assert(isfield(stewart.geometry, 'Bb'), 'stewart.geometry should have attribute Bb')
Bb = stewart.geometry.Bb;
2020-01-28 17:38:19 +01:00
assert(isfield(stewart.geometry, 'l'), 'stewart.geometry should have attribute l')
l = stewart.geometry.l;
#+end_src
2020-01-28 17:38:19 +01:00
*** Compute
:PROPERTIES:
:UNNUMBERED: t
:END:
2020-01-28 17:38:19 +01:00
#+begin_src matlab
Li = sqrt(args.AP'*args.AP + diag(Bb'*Bb) + diag(Aa'*Aa) - (2*args.AP'*Aa)' + (2*args.AP'*(args.ARB*Bb))' - diag(2*(args.ARB*Bb)'*Aa));
2020-01-28 17:38:19 +01:00
#+end_src
#+begin_src matlab
dLi = Li-l;
2020-01-28 17:38:19 +01:00
#+end_src
** =forwardKinematicsApprox=: Compute the Approximate Forward Kinematics
:PROPERTIES:
2020-02-11 18:04:45 +01:00
:header-args:matlab+: :tangle ../src/forwardKinematicsApprox.m
2020-01-28 17:38:19 +01:00
:header-args:matlab+: :comments none :mkdirp yes :eval no
:END:
<<sec:forwardKinematicsApprox>>
2020-02-11 18:04:45 +01:00
This Matlab function is accessible [[file:../src/forwardKinematicsApprox.m][here]].
2020-01-28 17:38:19 +01:00
*** Function description
:PROPERTIES:
:UNNUMBERED: t
:END:
2020-01-28 17:38:19 +01:00
#+begin_src matlab
function [P, R] = forwardKinematicsApprox(stewart, args)
% forwardKinematicsApprox - Computed the approximate pose of {B} with respect to {A} from the length of each strut and using
% the Jacobian Matrix
%
% Syntax: [P, R] = forwardKinematicsApprox(stewart, args)
%
% Inputs:
% - stewart - A structure with the following fields
% - kinematics.J [6x6] - The Jacobian Matrix
2020-01-28 17:38:19 +01:00
% - args - Can have the following fields:
% - dL [6x1] - Displacement of each strut [m]
%
% Outputs:
% - P [3x1] - The estimated position of {B} with respect to {A}
% - R [3x3] - The estimated rotation matrix that gives the orientation of {B} with respect to {A}
#+end_src
*** Optional Parameters
:PROPERTIES:
:UNNUMBERED: t
:END:
2020-01-28 17:38:19 +01:00
#+begin_src matlab
arguments
stewart
args.dL (6,1) double {mustBeNumeric} = zeros(6,1)
end
#+end_src
*** Check the =stewart= structure elements
:PROPERTIES:
:UNNUMBERED: t
:END:
#+begin_src matlab
assert(isfield(stewart.kinematics, 'J'), 'stewart.kinematics should have attribute J')
J = stewart.kinematics.J;
#+end_src
2020-01-28 17:38:19 +01:00
*** Computation
:PROPERTIES:
:UNNUMBERED: t
:END:
2020-01-28 17:38:19 +01:00
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}} \]
#+begin_src matlab
X = J\args.dL;
2020-01-28 17:38:19 +01:00
#+end_src
The position vector corresponds to the first 3 elements.
#+begin_src matlab
P = X(1:3);
#+end_src
The next 3 elements are the orientation of {B} with respect to {A} expressed
using the screw axis.
#+begin_src matlab
theta = norm(X(4:6));
s = X(4:6)/theta;
#+end_src
We then compute the corresponding rotation matrix.
#+begin_src matlab
R = [s(1)^2*(1-cos(theta)) + cos(theta) , s(1)*s(2)*(1-cos(theta)) - s(3)*sin(theta), s(1)*s(3)*(1-cos(theta)) + s(2)*sin(theta);
s(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);
s(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)];
#+end_src
* Bibliography :ignore:
bibliographystyle:unsrt
bibliography:ref.bib