nass-simscape/kinematics/index.org
2019-12-12 12:49:03 +01:00

206 lines
9.0 KiB
Org Mode

#+TITLE: Kinematics of the station
:DRAWER:
#+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: <link rel="stylesheet" type="text/css" href="../css/zenburn.css"/>
#+HTML_HEAD: <script type="text/javascript" src="../js/jquery.min.js"></script>
#+HTML_HEAD: <script type="text/javascript" src="../js/bootstrap.min.js"></script>
#+HTML_HEAD: <script type="text/javascript" src="../js/jquery.stickytableheaders.min.js"></script>
#+HTML_HEAD: <script type="text/javascript" src="../js/readtheorg.js"></script>
#+HTML_MATHJAX: align: center tagside: right font: TeX
#+PROPERTY: header-args:matlab :session *MATLAB*
#+PROPERTY: header-args:matlab+ :comments org
#+PROPERTY: header-args:matlab+ :results none
#+PROPERTY: header-args:matlab+ :exports both
#+PROPERTY: header-args:matlab+ :eval no-export
#+PROPERTY: header-args:matlab+ :output-dir figs
#+PROPERTY: header-args:matlab+ :tangle matlab/modal_frf_coh.m
#+PROPERTY: header-args:matlab+ :mkdirp yes
#+PROPERTY: header-args:shell :eval no-export
#+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
#+PROPERTY: header-args:latex+ :results raw replace :buffer no
#+PROPERTY: header-args:latex+ :eval no-export
#+PROPERTY: header-args:latex+ :exports both
#+PROPERTY: header-args:latex+ :mkdirp yes
#+PROPERTY: header-args:latex+ :output-dir figs
:END:
* Introduction :ignore:
In this document, we discuss the way the motion of each stage is defined.
* Micro Hexapod
** How the Symetrie Hexapod is controlled on the micro station
For the Micro-Hexapod, the convention for the angles are defined in =MAN_A_Software API_4.0.150918_EN.pdf= on page 13 (section 2.4 - Rotation Vectors):
#+begin_quote
The *Euler type II convention* is used to express the rotation vector.
This convention is mainly used in the aeronautics field (standard ISO 1151 concerning flight mechanics).
This convention uses the concepts of rotation of vehicles (ship, car and plane).
Generally, we consider that the main movement of the vehicle is following the X-axis and the Z-axis is parallel to the axis of gravity (at the initial position).
The roll rotation is around the X-axis, the pitch is around the Y-axis and yaw is the rotation around the Z-axis.
*The order of rotation is: Rx, Ry and then Rz.*
In most case, rotations are related to a reference with fixed axis; thus we say the rotations are around fixed axes.
The combination of these three rotations enables to write a rotation matrix.
This writing is unique and equal to:
\[ \bm{R} = \bm{R}_z(\gamma) \cdot \bm{R}_y(\beta) \cdot \bm{R}_x(\alpha) \]
The Euler type II convention corresponding to the *succession of rotations with respect to fixed axes*: first around X0, then Y0 and Z0.
This is equivalent to the succession of rotations with respect to mobile axes: first around Z0, then Y1' and X2'.
#+end_quote
More generally on the Control of the Micro-Hexapod:
#+begin_quote
Note that for all control modes, *the rotation center coincides with Object coordinate system origin*.
Moreover, the movements are controlled with *translation components at first* (Tx, Ty, Tz) *then rotation components* (Rx, Ry, Rz).
#+end_quote
Thus, it does the translations and then the rotation around the new translated frame.
** Control of the Micro-Hexapod using Simscape
*** Introduction :ignore:
We can think of two main ways to position the Micro-Hexapod using Simscape.
The first one is to use only one Bushing Joint between the base and the mobile platform.
The advantage is that it is very easy to impose the wanted displacement, however, we loose the dynamical properties of the Hexapod.
The second way is to specify the wanted length of the legs of the Hexapod in order to have the wanted position of the mobile platform.
This require a little bit more of mathematical derivations but this is the chosen solution.
*** Using Bushing Joint
In the documentation of the Bushing Joint (=doc "Bushing Joint"=) that is used to position the Hexapods, it is mention that the following frame is positioned with respect to the base frame in a way shown in figure [[fig:bushing_joint_transform]].
#+name: fig:bushing_joint_transform
#+caption: Joint Transformation Sequence for the Bushing Joint
[[file:figs/bushing_joint_transform.png]]
Basically, it performs the translations, and then the rotation along the X, Y and Z axis of the moving frame.
The three rotations that we define thus corresponds to the Euler U-V-W angles.
We should have the *same behavior* for the Micro-Hexapod on Simscape (same inputs at least).
However, the Bushing Joint makes rotations around mobiles axes (X, Y' and then Z'') and not fixed axes (X, Y and Z).
*** Using Inverse Kinematics and Leg Actuators
Here, we can use the Inverse Kinematic of the Hexapod to determine the length of each leg in order to obtain some defined translation and rotation of the mobile platform.
The advantages are:
- we can position the Hexapod as we want by specifying a rotation matrix
- the hexapod keeps its full flexibility as we don't specify any wanted displacements, only leg's rest position
However:
- even though the rest position of each leg (the position where the stiffness force is zero) is set correctly, the hexapod will we deflected due to gravity
Thus, for this simulation, we *remove the gravity*.
**** Theory
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.
**** 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 :tangle no
simulinkproject('../');
#+end_src
**** Matlab Implementation
We open the Simulink file.
#+begin_src matlab
open('kinematics/matlab/hexapod_tests.slx')
#+end_src
We load the configuration and set a small =StopTime=.
#+begin_src matlab
load('mat/conf_simscape.mat');
set_param(conf_simscape, 'StopTime', '0.5');
#+end_src
We define the wanted position/orientation of the Hexapod under study.
#+begin_src matlab
tx = 0.1; % [rad]
ty = 0.2; % [rad]
tz = 0.05; % [rad]
Rx = [1 0 0;
0 cos(tx) -sin(tx);
0 sin(tx) cos(tx)];
Ry = [ cos(ty) 0 sin(ty);
0 1 0;
-sin(ty) 0 cos(ty)];
Rz = [cos(tz) -sin(tz) 0;
sin(tz) cos(tz) 0;
0 0 1];
ARB = Rz*Ry*Rx;
AP = [0.01; 0.02; 0.03]; % [m]
hexapod = initializeMicroHexapod(struct('AP', AP, 'ARB', ARB));
#+end_src
We run the simulation.
#+begin_src matlab
sim('hexapod_tests')
#+end_src
And we verify that we indeed succeed to go to the wanted position.
#+begin_src matlab :results table replace
[simout.x.Data(end) ; simout.y.Data(end) ; simout.z.Data(end)] - AP
#+end_src
#+RESULTS:
| 1.611e-10 |
| -1.3748e-10 |
| 8.4879e-11 |
#+begin_src matlab :results table replace
simout.R.Data(:, :, end)-ARB
#+end_src
#+RESULTS:
| -1.2659e-10 | 6.5603e-11 | 6.2183e-10 |
| 1.0354e-10 | -5.2439e-11 | -5.2425e-10 |
| -5.9816e-10 | 5.532e-10 | -1.7737e-10 |