137 KiB
Simscape Model - Micro Station
- Introduction
- Micro-Station Kinematics
- Stage Modeling
- Measurement of Positioning Errors
- Simulation of Scientific Experiments
- Estimation of disturbances
- Conclusion
- Bibliography
Introduction ignore
Micro-Station Kinematics
<<sec:ustation_kinematics>>
Introduction ignore
Motion Stages
Translation Stage
Tilt Stage
Spindle
Micro-Hexapod
Specification for each stage
<<ssec:spec_stage>>
Figure here: file:/home/thomas/Cloud/work-projects/ID31-NASS/documents/work-package-1/figures
For each stage, after a quick presentation, the specifications (stroke, precision, …) of the stage, the metrology used with that stage and the parasitic motions associated to it are given.
Translation along Y
Presentation
This is the first stage, it is fixed directly on the granite. In order to minimize the parasitic motions, two cylinders are used to guide the stage. The motor used to drive the stage is one linear motor. The 3D model of this translation stage is shown figure ref:fig:stage_translation.
Specifications
Metrology
A linear digital encoder is used to measure the displacement of the translation stage along the y axis.
Parasitic motions
Axial Motion ($y$) | Radial Motion ($y-z$) | Rotation motion ($\theta-z$) |
$10nm$ | $20nm$ | $< 1.7 \mu rad$ |
Rotation around Y
Presentation
This stage is mainly use for the reflectivity experiment. This permit to make the sample rotates around the y axis. The rotation axis should be parallel to the y-axis and cross the X-ray.
As it is located below the Spindle, it make the axis of rotation of the spindle to also tilt with respect to the X-ray.
4 joints are used in order to pre-stress the system.
The model of the stage is shown figure ref:fig:stage_tilt.
Specifications
Motion | Mode | Stroke | Repetability | MIM |
$\theta_y$ | S | $\pm51 mrad$ | $5 \mu rad$ | $2 \mu rad$ |
Speed: $\pm 3^o/min$ |
Metrology
Two linear digital encoders are used (one on each side).
Parasitic motions
Axial Error ($y$) | Radial Error ($z$) | Tilt error () |
$0.5\mu m$ | $10nm$ | $1.5 \mu rad$ |
Spindle
Presentation
The Spindle consist of one stator (attached to the tilt stage) and one rotor.
The rotor is separated from the stator thanks to an air bearing.
The spindle is represented figure ref:fig:stage_spindle.
It has been developed by Lab-Leuven4.
Specifications
Motion | Mode | Stroke | Repetability | MIM |
$\theta_z$ | S | $\pm51 mrad$ | $5 \mu rad$ | $2 \mu rad$ |
Speed: $\pm 3^o/min$ |
Metrology
There is an incremental rotation encoder.
Parasitic motions
Radial Error ($x$-$y$) | Vertical Error ($z$) |
$0.33\mu m$ | $0.07\mu m$ |
More complete measurements have been conducted at the PEL5.
Long Stroke Hexapod
Presentation
The long stroke hexapod consists of 6 legs, each composed of:
- one linear actuators
- one limit switch
- one absolute linear encoder
- one ball joint at each side, one is fixed on the fixed platform, the other on the mobile platform
This long stroke hexapod has been developed by Symetrie6 and is shown figure ref:fig:stage_hexapod.
Specifications
Motion | Stroke | Repetability | MIM | Stiffness |
$T_{\mu_x}$ | $\pm10mm$ | $\pm1\mu m$ | $0.5\mu m$ | $>12N/\mu m$ |
$T_{\mu_y}$ | $\pm10mm$ | $\pm1\mu m$ | $0.5\mu m$ | $>12N/\mu m$ |
$T_{\mu_z}$ | $\pm10mm$ | $\pm1\mu m$ | $0.5\mu m$ | $>135N/\mu m$ |
$\theta_{\mu_x}$ | $\pm3 deg$ | $\pm5 \mu rad$ | $2.5\mu rad$ | |
$\theta_{\mu_y}$ | $\pm3 deg$ | $\pm5 \mu rad$ | $2.5\mu rad$ | |
$\theta_{\mu_z}$ | $\pm0.5 deg$ | $\pm5 \mu rad$ | $2.5\mu rad$ |
Metrology
The metrology consist of one absolute linear encoder in each leg.
Parasitic motions
Movement | Resolution | Repeatability |
$T_{\mu_x}$ | $0.5\mu m$ | $\pm 1\mu m$ |
$T_{\mu_y}$ | $0.5\mu m$ | $\pm 1\mu m$ |
$T_{\mu_z}$ | $0.1\mu m$ | $\pm 1\mu m$ |
$\theta_{\mu_x}$ | $2.5\mu rad$ | $\pm 4\mu rad$ |
$\theta_{\mu_y}$ | $2.5\mu rad$ | $\pm 4\mu rad$ |
Short Stroke Hexapod
Presentation
This last stage is located just below the sample to study. This is the only stage that is not yet build nor designed.
Specifications
Motion | Stroke | Repetability | MIM |
$T_{\nu_x}$ | $\pm10\mu m$ | $10nm$ | $3nm$ |
$T_{\nu_y}$ | $\pm10\mu m$ | $10nm$ | $3nm$ |
$T_{\nu_z}$ | $\pm10\mu m$ | $10nm$ | $3nm$ |
$\theta_{\nu_x}$ | $\pm10\mu rad$ | $1.7\mu rad$ | |
$\theta_{\nu_y}$ | $\pm10\mu rad$ | $1.7\mu rad$ | |
$\theta_{\nu_z}$ | $\pm10\mu rad$ |
Dimensions
-
Bottom plate :
- Inner diameter: $>150mm$
- External diameter: $<305mm$
-
Top plate
- External diameter: $<300mm$
- Height: $90mm$
- Location of the rotation point: Centered, at $175mm$ above the top platform
Compute sample's motion from stage motion
Introduction ignore
Rx = [1 0 0; 0 cos(t) -sin(t); 0 sin(t) cos(t)];
Ry = [ cos(t) 0 sin(t); 0 1 0; -sin(t) 0 cos(t)];
Rz = [cos(t) -sin(t) 0; sin(t) cos(t) 0; 0 0 1];
Let's define the following frames:
- $\{W\}$ the frame that is fixed to the granite and its origin at the theoretical meeting point between the X-ray and the spindle axis.
- $\{S\}$ the frame attached to the sample (in reality attached to the top platform of the nano-hexapod) with its origin at 175mm above the top platform of the nano-hexapod. Its origin is $O_S$.
- $\{T\}$ the theoretical wanted frame that correspond to the wanted pose of the frame $\{S\}$. $\{T\}$ is computed from the wanted position of each stage. It is thus theoretical and does not correspond to a real position. The origin of $T$ is $O_T$ and is the wanted position of the sample.
Thus:
- the measurement of the position of the sample corresponds to ${}^W O_S = \begin{bmatrix} {}^WP_{x,m} & {}^WP_{y,m} & {}^WP_{z,m} \end{bmatrix}^T$ in translation and to $\theta_m {}^W\bm{s}_m = \theta_m \cdot \begin{bmatrix} {}^Ws_{x,m} & {}^Ws_{y,m} & {}^Ws_{z,m} \end{bmatrix}^T$ in rotations
- the wanted position of the sample expressed w.r.t. the granite is ${}^W O_T = \begin{bmatrix} {}^WP_{x,r} & {}^WP_{y,r} & {}^WP_{z,r} \end{bmatrix}^T$ in translation and to $\theta_r {}^W\bm{s}_r = \theta_r \cdot \begin{bmatrix} {}^Ws_{x,r} & {}^Ws_{y,r} & {}^Ws_{z,r} \end{bmatrix}^T$ in rotations
Wanted Position of the Sample with respect to the Granite
Let's define the wanted position of each stage.
Ty = 0; % [m]
Ry = 3*pi/180; % [rad]
Rz = 180*pi/180; % [rad]
% Hexapod (first consider only translations)
Thx = 0; % [m]
Thy = 0; % [m]
Thz = 0; % [m]
Now, we compute the corresponding wanted translation and rotation of the sample with respect to the granite frame $\{W\}$. This corresponds to ${}^WO_T$ and $\theta_m {}^Ws_m$.
To do so, we have to define the homogeneous transformation for each stage.
% Translation Stage
Rty = [1 0 0 0;
0 1 0 Ty;
0 0 1 0;
0 0 0 1];
% Tilt Stage - Pure rotating aligned with Ob
Rry = [ cos(Ry) 0 sin(Ry) 0;
0 1 0 0;
-sin(Ry) 0 cos(Ry) 0;
0 0 0 1];
% Spindle - Rotation along the Z axis
Rrz = [cos(Rz) -sin(Rz) 0 0 ;
sin(Rz) cos(Rz) 0 0 ;
0 0 1 0 ;
0 0 0 1 ];
% Micro-Hexapod (only rotations first)
Rh = [1 0 0 Thx ;
0 1 0 Thy ;
0 0 1 Thz ;
0 0 0 1 ];
We combine the individual homogeneous transformations into one homogeneous transformation for all the station.
Ttot = Rty*Rry*Rrz*Rh;
Using this homogeneous transformation, we can compute the wanted position and orientation of the sample with respect to the granite.
Translation.
WOr = Ttot*[0;0;0;1];
WOr = WOr(1:3);
Rotation.
thetar = acos((trace(Ttot(1:3, 1:3))-1)/2)
if thetar == 0
WSr = [0; 0; 0];
else
[V, D] = eig(Ttot(1:3, 1:3));
WSr = thetar*V(:, abs(diag(D) - 1) < eps(1));
end
WPr = [WOr ; WSr];
Measured Position of the Sample with respect to the Granite
The measurement of the position of the sample using the metrology system gives the position and orientation of the sample with respect to the granite.
% Measurements: Xm, Ym, Zm, Rx, Ry, Rz
Dxm = 0; % [m]
Dym = 0; % [m]
Dzm = 0; % [m]
Rxm = 0*pi/180; % [rad]
Rym = 0*pi/180; % [rad]
Rzm = 180*pi/180; % [rad]
Let's compute the corresponding orientation using screw axis.
Trxm = [1 0 0;
0 cos(Rxm) -sin(Rxm);
0 sin(Rxm) cos(Rxm)];
Trym = [ cos(Rym) 0 sin(Rym);
0 1 0;
-sin(Rym) 0 cos(Rym)];
Trzm = [cos(Rzm) -sin(Rzm) 0;
sin(Rzm) cos(Rzm) 0;
0 0 1];
STw = [[ Trym*Trxm*Trzm , [Dxm; Dym; Dzm]]; 0 0 0 1];
We then obtain the orientation measurement in the form of screw coordinate $\theta_m ({}^Ws_{x,m},\ {}^Ws_{y,m},\ {}^Ws_{z,m})^T$ where:
- $\theta_m = \cos^{-1} \frac{\text{Tr}(R) - 1}{2}$
- ${}^W\bm{s}_m$ is the eigen vector of the rotation matrix $R$ corresponding to the eigen value $\lambda = 1$
thetam = acos((trace(STw(1:3, 1:3))-1)/2); % [rad]
if thetam == 0
WSm = [0; 0; 0];
else
[V, D] = eig(STw(1:3, 1:3));
WSm = thetam*V(:, abs(diag(D) - 1) < eps(1));
end
WPm = [Dxm ; Dym ; Dzm ; WSm];
Positioning Error with respect to the Granite
The wanted position expressed with respect to the granite is ${}^WO_T$ and the measured position with respect to the granite is ${}^WO_S$, thus the position error expressed in $\{W\}$ is \[ {}^W E = {}^W O_T - {}^W O_S \] The same is true for rotations: \[ \theta_\epsilon {}^W\bm{s}_\epsilon = \theta_r {}^W\bm{s}_r - \theta_m {}^W\bm{s}_m \]
WPe = WPr - WPm;
Now we want to express this error in a frame attached to the base of the nano-hexapod with its origin at the same point where the Jacobian of the nano-hexapod is computed (175mm above the top platform + 90mm of total height of the nano-hexapod).
Or maybe should we want to express this error with respect to the top platform of the nano-hexapod? We are measuring the position of the top-platform, and we don't know exactly the position of the bottom platform. We could compute the position of the bottom platform in two ways:
- from the encoders of each stage
- from the measurement of the nano-hexapod top platform + the internal metrology in the nano-hexapod (capacitive sensors e.g)
A third option is to say that the maximum stroke of the nano-hexapod is so small that the error should no change to much by the change of base.
Position Error Expressed in the Nano-Hexapod Frame
We now want the position error to be expressed in $\{S\}$ (the frame attach to the sample) for control: \[ {}^S E = {}^S T_W \cdot {}^W E \]
Thus we need to compute the homogeneous transformation ${}^ST_W$. Fortunately, this homogeneous transformation can be computed from the measurement of the sample position and orientation with respect to the granite.
Trxm = [1 0 0;
0 cos(Rxm) -sin(Rxm);
0 sin(Rxm) cos(Rxm)];
Trym = [ cos(Rym) 0 sin(Rym);
0 1 0;
-sin(Rym) 0 cos(Rym)];
Trzm = [cos(Rzm) -sin(Rzm) 0;
sin(Rzm) cos(Rzm) 0;
0 0 1];
STw = [[ Trym*Trxm*Trzm , [Dxm; Dym; Dzm]]; 0 0 0 1];
Translation Error.
SEm = STw * [WPe(1:3); 0];
SEm = SEm(1:3);
Rotation Error.
SEr = STw * [WPe(4:6); 0];
SEr = SEr(1:3);
Etot = [SEm ; SEr]
Another try
Let's denote:
- $\{W\}$ the initial fixed frame
- $\{R\}$ the reference frame corresponding to the wanted pose of the sample
- $\{M\}$ the frame corresponding to the measured pose of the sample
We have then computed:
- ${}^WT_R$
- ${}^WT_M$
We have:
\begin{align} {}^MT_R &= {}^MT_W {}^WT_R \\ &= {}^WT_M^t {}^WT_R \end{align} MTr = STw'*Ttot;
Position error:
MTr(1:3, 1:4)*[0; 0; 0; 1]
Orientation error:
MTr(1:3, 1:3)
Verification
How can we verify that the computation is correct? Options:
-
Test with simscape multi-body
- Impose motion on each stage
- Measure the position error w.r.t. the NASS
- Compare with the computation
Stage Modeling
<<sec:ustation_kinematics>>
Introduction ignore
The goal here is to tune the Simscape model of the station in order to have a good dynamical representation of the real system.
In order to do so, we reproduce the Modal Analysis done on the station using the Simscape model.
We can then compare the measured Frequency Response Functions with the identified dynamics of the model.
Finally, this should help to tune the parameters of the model such that the dynamics is closer to the measured FRF.
Some notes about the Simscape Model
The Simscape Model of the micro-station consists of several solid bodies:
- Bottom Granite
- Top Granite
- Translation Stage
- Tilt Stage
- Spindle
- Hexapod
Each solid body has some characteristics: Center of Mass, mass, moment of inertia, etc… These parameters are automatically computed from the geometry and from the density of the materials.
Then, the solid bodies are connected with springs and dampers. Some of the springs and dampers values can be estimated from the joints/stages specifications, however, we here prefer to tune these values based on the measurements.
Compare with measurements at the CoM of each element
%% All stages are initialized
initializeGround( 'type', 'rigid');
initializeGranite( 'type', 'flexible');
initializeTy( 'type', 'flexible');
initializeRy( 'type', 'flexible');
initializeRz( 'type', 'flexible');
initializeMicroHexapod('type', 'flexible');
initializeLoggingConfiguration('log', 'none');
initializeReferences();
initializeDisturbances('enable', false);
We now use a new Simscape Model where 6DoF inertial sensors are located at the Center of Mass of each solid body.
We use the linearize
function in order to estimate the dynamics from forces applied on the Translation stage at the same position used for the real modal analysis to the inertial sensors.
%% Identification
% Input/Output definition
clear io; io_i = 1;
io(io_i) = linio([mdl, '/Micro-Station/Translation Stage/Flexible/F_hammer'], 1, 'openinput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Micro-Station/Granite/Flexible/accelerometer'], 1, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Micro-Station/Translation Stage/Flexible/accelerometer'], 1, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Micro-Station/Tilt Stage/Flexible/accelerometer'], 1, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Micro-Station/Spindle/Flexible/accelerometer'], 1, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Micro-Station/Micro Hexapod/Flexible/accelerometer'], 1, 'openoutput'); io_i = io_i + 1;
% Run the linearization
G_ms = linearize(mdl, io, 0);
% Input/Output definition
G_ms.InputName = {'Fx', 'Fy', 'Fz'};
G_ms.OutputName = {'gtop_x', 'gtop_y', 'gtop_z', 'gtop_rx', 'gtop_ry', 'gtop_rz', ...
'ty_x', 'ty_y', 'ty_z', 'ty_rx', 'ty_ry', 'ty_rz', ...
'ry_x', 'ry_y', 'ry_z', 'ry_rx', 'ry_ry', 'ry_rz', ...
'rz_x', 'rz_y', 'rz_z', 'rz_rx', 'rz_ry', 'rz_rz', ...
'hexa_x', 'hexa_y', 'hexa_z', 'hexa_rx', 'hexa_ry', 'hexa_rz'};
% Put the output of G in displacements instead of acceleration
G_ms = G_ms/s^2;
%% Load estimated FRF at CoM
load('/home/thomas/Cloud/work-projects/ID31-NASS/phd-thesis-chapters/A3-micro-station-modal-analysis/matlab/mat/frf_matrix.mat', 'freqs');
load('/home/thomas/Cloud/work-projects/ID31-NASS/phd-thesis-chapters/A3-micro-station-modal-analysis/matlab/mat/frf_com.mat', 'frfs_CoM');
Measured micro-station compliance
Introduction ignore
The most important dynamical characteristic of the micro-station that should be well modeled is its compliance. This is what can impact the nano-hexapod dynamics.
- Add schematic of the experiment with Micro-Hexapod top platform, location of accelerometers, of impacts, etc…
- 4 3-axis accelerometers
- 10 hammer impacts on the micro-hexapod top plaftorm
- Was the rotation compensation axis present? (I don't think so)
Position of inertial sensors on top of the micro-hexapod
4 accelerometers are fixed to the micro-hexapod top platform.
To convert the 12 acceleration signals $\mathbf{a}_{\mathcal{L}} = [a_{1x}\ a_{1y}\ a_{1z}\ a_{2x}\ \dots\ a_{4z}]$ to the acceleration expressed in cartesian coordinate $\mathbf{a}_{\mathcal{X}} [a_{dx}\ a_{dy}\ a_{dz}\ a_{rx}\ a_{ry}\ a_{rz}]$, a Jacobian matrix can be written based on the positions and orientations of the accelerometers.
\begin{equation} \mathbf{a}_{\mathcal{L}} = J_a \cdot \mathbf{a}_{\mathcal{X}} \end{equation} \begin{equation} J_a = \begin{bmatrix} 1 & 0 & 0 & 0 & 0 &-d \\ 0 & 1 & 0 & 0 & 0 & 0 \\ 0 & 0 & 1 & d & 0 & 0 \\ 1 & 0 & 0 & 0 & 0 & 0 \\ 0 & 1 & 0 & 0 & 0 &-d \\ 0 & 0 & 1 & 0 & d & 0 \\ 1 & 0 & 0 & 0 & 0 & d \\ 0 & 1 & 0 & 0 & 0 & 0 \\ 0 & 0 & 1 &-d & 0 & 0 \\ 1 & 0 & 0 & 0 & 0 & 0 \\ 0 & 1 & 0 & 0 & 0 & d \\ 0 & 0 & 1 & 0 &-d & 0 \end{bmatrix} \end{equation}Then, the acceleration in the cartesian frame can be computed
\begin{equation} \mathbf{a}_{\mathcal{X}} = J_a^\dagger \cdot \mathbf{a}_{\mathcal{L}} \end{equation}%% Jacobian for accelerometers
% L = Ja X
d = 0.14; % [m]
Ja = [1 0 0 0 0 -d;
0 1 0 0 0 0;
0 0 1 d 0 0;
1 0 0 0 0 0;
0 1 0 0 0 -d;
0 0 1 0 d 0;
1 0 0 0 0 d;
0 1 0 0 0 0;
0 0 1 -d 0 0;
1 0 0 0 0 0;
0 1 0 0 0 d;
0 0 1 0 -d 0];
Ja_inv = pinv(Ja);
d1x | d1y | d1z | d2x | d2y | d2z | d3x | d3y | d3z | d4x | d4y | d4z | |
---|---|---|---|---|---|---|---|---|---|---|---|---|
Dx | 0.25 | 0.0 | 0.0 | 0.25 | 0.0 | 0.0 | 0.25 | 0.0 | 0.0 | 0.25 | 0.0 | 0.0 |
Dy | 0.0 | 0.25 | 0.0 | 0.0 | 0.25 | 0.0 | 0.0 | 0.25 | 0.0 | 0.0 | 0.25 | 0.0 |
Dz | 0.0 | 0.0 | 0.25 | 0.0 | 0.0 | 0.25 | 0.0 | 0.0 | 0.25 | 0.0 | 0.0 | 0.25 |
Rx | 0.0 | 0.0 | 3.57143 | 0.0 | 0.0 | -0.0 | 0.0 | 0.0 | -3.57143 | 0.0 | 0.0 | -0.0 |
Ry | 0.0 | 0.0 | 0.0 | 0.0 | 0.0 | 3.57143 | 0.0 | 0.0 | 0.0 | 0.0 | 0.0 | -3.57143 |
Rz | -1.78571 | 0.0 | -0.0 | 0.0 | -1.78571 | 0.0 | 1.78571 | 0.0 | -0.0 | 0.0 | 1.78571 | -0.0 |
Hammer blow position/orientation
10 hammer hits are performed as shown in Figure …
Num | Direction | Position | Accelerometer position | Jacobian number |
---|---|---|---|---|
1 | -Y | [0, +A, 0] | 1 | -2 |
2 | -Z | [0, +A, 0] | 1 | -3 |
3 | X | [-B, 0, 0] | 2 | 4 |
4 | -Z | [-B, 0, 0] | 2 | -6 |
5 | Y | [0, -A, 0] | 3 | 8 |
6 | -Z | [0, -A, 0] | 3 | -9 |
7 | -X | [+B, 0, 0] | 4 | -10 |
8 | -Z | [+B, 0, 0] | 4 | -12 |
9 | -X | [0, -A, 0] | 3 | -7 |
10 | -X | [0, +A, 0] | 1 | -1 |
Similar to what is done for the accelerometers, a Jacobian matrix can be computed to convert the individual hammer forces to force and torques applied at the center of the micro-hexapod top plate.
\begin{equation} \mathbf{F}_{\mathcal{X}} = J_F^t \cdot \mathbf{F}_{\mathcal{L}} \end{equation} \begin{equation} J_F = \begin{bmatrix} 0 & -1 & 0 & 0 & 0 & 0\\ 0 & 0 & -1 & -d & 0 & 0\\ 1 & 0 & 0 & 0 & 0 & 0\\ 0 & 0 & -1 & 0 & -d & 0\\ 0 & 1 & 0 & 0 & 0 & 0\\ 0 & 0 & -1 & d & 0 & 0\\ -1 & 0 & 0 & 0 & 0 & 0\\ 0 & 0 & -1 & 0 & d & 0\\ -1 & 0 & 0 & 0 & 0 & -d\\ -1 & 0 & 0 & 0 & 0 & d \end{bmatrix} \end{equation}%% Jacobian for hammer impacts
% F = Jf' tau
Jf = [0 -1 0 0 0 0;
0 0 -1 -d 0 0;
1 0 0 0 0 0;
0 0 -1 0 -d 0;
0 1 0 0 0 0;
0 0 -1 d 0 0;
-1 0 0 0 0 0;
0 0 -1 0 d 0;
-1 0 0 0 0 -d;
-1 0 0 0 0 d]';
Jf_inv = pinv(Jf);
-F1y | -F1z | +F2x | -F2z | +F3y | -F3z | -F4x | -F4z | -F3x | -F1x | |
---|---|---|---|---|---|---|---|---|---|---|
Fx | 0.0 | 0.0 | 1.0 | 0.0 | 0.0 | 0.0 | -1.0 | 0.0 | -1.0 | -1.0 |
Fy | -1.0 | 0.0 | 0.0 | 0.0 | 1.0 | 0.0 | 0.0 | 0.0 | 0.0 | 0.0 |
Fz | 0.0 | -1.0 | 0.0 | -1.0 | 0.0 | -1.0 | 0.0 | -1.0 | 0.0 | 0.0 |
Mx | 0.0 | -0.14 | 0.0 | 0.0 | 0.0 | 0.14 | 0.0 | 0.0 | 0.0 | 0.0 |
My | 0.0 | 0.0 | 0.0 | -0.14 | 0.0 | 0.0 | 0.0 | 0.14 | 0.0 | 0.0 |
Mz | 0.0 | 0.0 | 0.0 | 0.0 | 0.0 | 0.0 | 0.0 | 0.0 | -0.14 | 0.14 |
Compute FRF
%% Load raw measurement data
% "Track1" to "Track12" are the 12 accelerometers
% "Track13" is the instrumented hammer force sensor
data = [
load('ustation_compliance_hammer_1.mat'), ...
load('ustation_compliance_hammer_2.mat'), ...
load('ustation_compliance_hammer_3.mat'), ...
load('ustation_compliance_hammer_4.mat'), ...
load('ustation_compliance_hammer_5.mat'), ...
load('ustation_compliance_hammer_6.mat'), ...
load('ustation_compliance_hammer_7.mat'), ...
load('ustation_compliance_hammer_8.mat'), ...
load('ustation_compliance_hammer_9.mat'), ...
load('ustation_compliance_hammer_10.mat')];
%% Prepare the FRF computation
Ts = 1e-3; % Sampling Time [s]
Nfft = floor(1/Ts); % Number of points for the FFT computation
win = ones(Nfft, 1); % Rectangular window
[~, f] = tfestimate(data(1).Track13, data(1).Track1, win, [], Nfft, 1/Ts);
% Samples taken before and after the hammer "impact"
pre_n = floor(0.1/Ts);
post_n = Nfft - pre_n - 1;
%% Compute the FRFs for the 10 hammer impact locations.
% The FRF from hammer force the 12 accelerometers are computed
% for each of the 10 hammer impacts and averaged
G_raw = zeros(12,10,length(f));
for i = 1:10 % For each impact location
% Find the 10 impacts
[~, impacts_i] = find(diff(data(i).Track13 > 50)==1);
% Only keep the first 10 impacts if there are more than 10 impacts
if length(impacts_i)>10
impacts_i(11:end) = [];
end
% Average the FRF for the 10 impacts
for impact_i = impacts_i
i_start = impact_i - pre_n;
i_end = impact_i + post_n;
data_in = data(i).Track13(i_start:i_end); % [N]
% Remove hammer DC offset
data_in = data_in - mean(data_in(end-pre_n:end));
% Combine all outputs [m/s^2]
data_out = [data(i).Track1( i_start:i_end); ...
data(i).Track2( i_start:i_end); ...
data(i).Track3( i_start:i_end); ...
data(i).Track4( i_start:i_end); ...
data(i).Track5( i_start:i_end); ...
data(i).Track6( i_start:i_end); ...
data(i).Track7( i_start:i_end); ...
data(i).Track8( i_start:i_end); ...
data(i).Track9( i_start:i_end); ...
data(i).Track10(i_start:i_end); ...
data(i).Track11(i_start:i_end); ...
data(i).Track12(i_start:i_end)];
[frf, ~] = tfestimate(data_in, data_out', win, [], Nfft, 1/Ts);
G_raw(:,i,:) = squeeze(G_raw(:,i,:)) + 0.1*frf'./(-(2*pi*f').^2);
end
end
%% Compute transfer function in cartesian frame using Jacobian matrices
% FRF_cartesian = inv(Ja) * FRF * inv(Jf)
FRF_cartesian = pagemtimes(Ja_inv, pagemtimes(G_raw, Jf_inv));
figure;
hold on;
plot(f, abs(squeeze(FRF_cartesian(4,4,:))), '-', 'color', colors(1,:), 'DisplayName', '$D_x/F_x$')
plot(f, abs(squeeze(FRF_cartesian(5,5,:))), '-', 'color', colors(2,:), 'DisplayName', '$D_y/F_y$')
plot(f, abs(squeeze(FRF_cartesian(6,6,:))), '-', 'color', colors(3,:), 'DisplayName', '$D_z/F_z$')
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
xlabel('Frequency [Hz]'); ylabel('Magnitude [m/N]');
xlim([30, 300]); ylim([1e-9, 2e-6]);
leg = legend('location', 'southwest', 'FontSize', 8, 'NumColumns', 1);
leg.ItemTokenSize(1) = 15;
Compare with the Model
%% Initialize simulation with default parameters (flexible elements)
initializeGround();
initializeGranite();
initializeTy();
initializeRy();
initializeRz();
initializeMicroHexapod();
initializeReferences();
initializeDisturbances();
initializeSimscapeConfiguration();
initializeLoggingConfiguration();
And we identify the dynamics from forces/torques applied on the micro-hexapod top platform to the motion of the micro-hexapod top platform at the same point.
%% Identification of the compliance
% Input/Output definition
clear io; io_i = 1;
io(io_i) = linio([mdl, '/Micro-Station/Micro Hexapod/Flexible/Fm'], 1, 'openinput'); io_i = io_i + 1; % Direct Forces/Torques applied on the micro-hexapod top platform
io(io_i) = linio([mdl, '/Micro-Station/Micro Hexapod/Flexible/Dm'], 1, 'output'); io_i = io_i + 1; % Absolute displacement of the top platform
% Run the linearization
Gm = linearize(mdl, io, 0);
Gm.InputName = {'Fmx', 'Fmy', 'Fmz', 'Mmx', 'Mmy', 'Mmz'};
Gm.OutputName = {'Dx', 'Dy', 'Dz', 'Drx', 'Dry', 'Drz'};
Get resonance frequencies
%% Initialize simulation with default parameters (flexible elements)
initializeGround();
initializeGranite();
initializeTy();
initializeRy();
initializeRz();
initializeMicroHexapod();
initializeReferences();
initializeDisturbances();
initializeSimscapeConfiguration();
initializeLoggingConfiguration();
And we identify the dynamics from forces/torques applied on the micro-hexapod top platform to the motion of the micro-hexapod top platform at the same point.
%% Identification of the compliance
% Input/Output definition
clear io; io_i = 1;
io(io_i) = linio([mdl, '/Micro-Station/Micro Hexapod/Flexible/Fm'], 1, 'openinput'); io_i = io_i + 1; % Direct Forces/Torques applied on the micro-hexapod top platform
io(io_i) = linio([mdl, '/Micro-Station/Micro Hexapod/Flexible/Dm'], 1, 'output'); io_i = io_i + 1; % Absolute displacement of the top platform
% Run the linearization
Gm = linearize(mdl, io, 0);
Gm.InputName = {'Fmx', 'Fmy', 'Fmz', 'Mmx', 'Mmy', 'Mmz'};
Gm.OutputName = {'Dx', 'Dy', 'Dz', 'Drx', 'Dry', 'Drz'};
modes_freq = imag(eig(Gm))/2/pi;
modes_freq = sort(modes_freq(modes_freq>0));
Mode | Simscape | Modal analysis |
---|---|---|
1 | 11.7 | 11.9 |
2 | 21.3 | 18.6 |
3 | 26.1 | 37.8 |
4 | 57.5 | 39.1 |
5 | 60.6 | 56.3 |
6 | 73.0 | 69.8 |
7 | 97.9 | 72.5 |
8 | 120.2 | 84.8 |
9 | 126.2 | 91.3 |
10 | 142.4 | 105.5 |
11 | 155.9 | 106.6 |
12 | 178.5 | 112.7 |
13 | 179.3 | 124.2 |
14 | 182.6 | 145.3 |
15 | 223.6 | 150.5 |
16 | 226.4 | 165.4 |
Conclusion
For such a complex system, we believe that the Simscape Model represents the dynamics of the system with enough fidelity.
Measurement of Positioning Errors
<<sec:ustation_kinematics>>
Simulation of Scientific Experiments
<<sec:ustation_kinematics>>
Introduction ignore
Estimation of disturbances
This was already done in uni-axial model.
Conclusion
<<sec:uniaxial_conclusion>>