Tangle matlab files without comments
This commit is contained in:
parent
28c4fbe083
commit
6876adf4f7
@ -1,5 +1,3 @@
|
||||
% Matlab Init :noexport:ignore:
|
||||
|
||||
%% ustation_1_kinematics.m
|
||||
|
||||
%% Clear Workspace and Close figures
|
||||
@ -25,76 +23,6 @@ colors = colororder;
|
||||
%% Frequency Vector
|
||||
freqs = logspace(log10(10), log10(2e3), 1000);
|
||||
|
||||
% Micro-Station Kinematics
|
||||
% <<ssec:ustation_kinematics>>
|
||||
|
||||
% Each stage is described by two frames; one is attached to the fixed platform $\{A\}$ while the other is fixed to the mobile platform $\{B\}$.
|
||||
% At "rest" position, the two have the same pose and coincide with the point of interest ($O_A = O_B$).
|
||||
% An example of the tilt stage is shown in Figure ref:fig:ustation_stage_motion.
|
||||
% The mobile frame of the translation stage is equal to the fixed frame of the tilt stage: $\{B_{D_y}\} = \{A_{R_y}\}$.
|
||||
% Similarly, the mobile frame of the tilt stage is equal to the fixed frame of the spindle: $\{B_{R_y}\} = \{A_{R_z}\}$.
|
||||
|
||||
% #+name: fig:ustation_stage_motion
|
||||
% #+caption: Example of the motion induced by the tilt-stage $R_y$. "Rest" position in shown in blue while a arbitrary position in shown in red. Parasitic motions are here magnified for clarity.
|
||||
% [[file:figs/ustation_stage_motion.png]]
|
||||
|
||||
% The motion induced by a positioning stage can be described by a homogeneous transformation matrix from frame $\{A\}$ to frame $\{B\}$ as explain in Section ref:ssec:ustation_kinematics.
|
||||
% As any motion stage induces parasitic motion in all 6 DoF, the transformation matrix representing its induced motion can be written as in eqref:eq:ustation_translation_stage_errors.
|
||||
|
||||
% \begin{equation}\label{eq:ustation_translation_stage_errors}
|
||||
% {}^A\bm{T}_B(D_x, D_y, D_z, \theta_x, \theta_y, \theta_z) =
|
||||
% \left[ \begin{array}{ccc|c}
|
||||
% & & & D_x \\
|
||||
% & \bm{R}_x(\theta_x) \bm{R}_y(\theta_y) \bm{R}_z(\theta_z) & & D_y \\
|
||||
% & & & D_z \cr
|
||||
% \hline
|
||||
% 0 & 0 & 0 & 1
|
||||
% \end{array} \right]
|
||||
% \end{equation}
|
||||
|
||||
% The homogeneous transformation matrix corresponding to the micro-station $\bm{T}_{\mu\text{-station}}$ is simply equal to the matrix multiplication of the homogeneous transformation matrices of the individual stages as shown in Equation eqref:eq:ustation_transformation_station.
|
||||
|
||||
% \begin{equation}\label{eq:ustation_transformation_station}
|
||||
% \bm{T}_{\mu\text{-station}} = \bm{T}_{D_y} \cdot \bm{T}_{R_y} \cdot \bm{T}_{R_z} \cdot \bm{T}_{\mu\text{-hexapod}}
|
||||
% \end{equation}
|
||||
|
||||
% $\bm{T}_{\mu\text{-station}}$ represents the pose of the sample (supposed to be rigidly fixed on top of the positioning-hexapod) with respect to the granite.
|
||||
|
||||
% If the transformation matrices of the individual stages are each representing a perfect motion (i.e. the stages are supposed to have no parasitic motion), $\bm{T}_{\mu\text{-station}}$ then represent the pose setpoint of the sample with respect to the granite.
|
||||
% The transformation matrices for the translation stage, tilt stage, spindle, and positioning hexapod can be written as shown in Equation eqref:eq:ustation_transformation_matrices_stages.
|
||||
|
||||
% \begin{equation}\label{eq:ustation_transformation_matrices_stages}
|
||||
% \begin{align}
|
||||
% \bm{T}_{D_y} &= \begin{bmatrix}
|
||||
% 1 & 0 & 0 & 0 \\
|
||||
% 0 & 1 & 0 & D_y \\
|
||||
% 0 & 0 & 1 & 0 \\
|
||||
% 0 & 0 & 0 & 1
|
||||
% \end{bmatrix} \quad
|
||||
% \bm{T}_{\mu\text{-hexapod}} =
|
||||
% \left[ \begin{array}{ccc|c}
|
||||
% & & & D_{\mu x} \\
|
||||
% & \bm{R}_x(\theta_{\mu x}) \bm{R}_y(\theta_{\mu y}) \bm{R}_{z}(\theta_{\mu z}) & & D_{\mu y} \\
|
||||
% & & & D_{\mu z} \cr
|
||||
% \hline
|
||||
% 0 & 0 & 0 & 1
|
||||
% \end{array} \right] \\
|
||||
% \bm{T}_{R_z} &= \begin{bmatrix}
|
||||
% \cos(\theta_z) & -\sin(\theta_z) & 0 & 0 \\
|
||||
% \sin(\theta_z) & \cos(\theta_z) & 0 & 0 \\
|
||||
% 0 & 0 & 1 & 0 \\
|
||||
% 0 & 0 & 0 & 1
|
||||
% \end{bmatrix} \quad
|
||||
% \bm{T}_{R_y} = \begin{bmatrix}
|
||||
% \cos(\theta_y) & 0 & \sin(\theta_y) & 0 \\
|
||||
% 0 & 1 & 0 & 0 \\
|
||||
% -\sin(\theta_y) & 0 & \cos(\theta_y) & 0 \\
|
||||
% 0 & 0 & 0 & 1
|
||||
% \end{bmatrix}
|
||||
% \end{align}
|
||||
% \end{equation}
|
||||
|
||||
|
||||
%% Stage setpoints
|
||||
Dy = 1e-3; % Translation Stage [m]
|
||||
Ry = 3*pi/180; % Tilt Stage [rad]
|
||||
|
@ -1,5 +1,3 @@
|
||||
% Matlab Init :noexport:ignore:
|
||||
|
||||
%% ustation_2_modeling.m
|
||||
|
||||
%% Clear Workspace and Close figures
|
||||
@ -25,18 +23,6 @@ colors = colororder;
|
||||
%% Frequency Vector
|
||||
freqs = logspace(log10(10), log10(2e3), 1000);
|
||||
|
||||
% Comparison with the measured dynamics
|
||||
% <<ssec:ustation_model_comp_dynamics>>
|
||||
|
||||
% The dynamics of the micro-station was measured by placing accelerometers on each stage and by impacting the translation stage with an instrumented hammer in three directions.
|
||||
% The obtained FRFs were then projected at the CoM of each stage.
|
||||
|
||||
% To gain a first insight into the accuracy of the obtained model, the FRFs from the hammer impacts to the acceleration of each stage were extracted from the multi-body model and compared with the measurements in Figure ref:fig:ustation_comp_com_response.
|
||||
|
||||
% Even though there is some similarity between the model and the measurements (similar overall shapes and amplitudes), it is clear that the multi-body model does not accurately represent the complex micro-station dynamics.
|
||||
% Tuning the numerous model parameters to better match the measurements is a highly non-linear optimization problem that is difficult to solve in practice.
|
||||
|
||||
|
||||
%% Indentify the model dynamics from the 3 hammer imapcts
|
||||
% To the motion of each solid body at their CoM
|
||||
|
||||
@ -134,75 +120,6 @@ leg.ItemTokenSize(1) = 15;
|
||||
xlim([10, 200]);
|
||||
ylim([1e-6, 1e-1])
|
||||
|
||||
% Micro-station compliance
|
||||
% <<ssec:ustation_model_compliance>>
|
||||
|
||||
% As discussed in the previous section, the dynamics of the micro-station is complex, and tuning the multi-body model parameters to obtain a perfect match is difficult.
|
||||
|
||||
% When considering the NASS, the most important dynamical characteristics of the micro-station is its compliance, as it can affect the plant dynamics.
|
||||
% Therefore, the adopted strategy is to accurately model the micro-station compliance.
|
||||
|
||||
% The micro-station compliance was experimentally measured using the setup illustrated in Figure ref:fig:ustation_compliance_meas.
|
||||
% Four 3-axis accelerometers were fixed to the micro-hexapod top platform.
|
||||
% The micro-hexapod top platform was impacted at 10 different points.
|
||||
% For each impact position, 10 impacts were performed to average and improve the data quality.
|
||||
|
||||
% #+name: fig:ustation_compliance_meas
|
||||
% #+caption: Schematic of the measurement setup used to estimate the compliance of the micro-station. The top platform of the positioning hexapod is shown with four 3-axis accelerometers (shown in red) are on top. 10 hammer impacts are performed at different locations (shown in blue).
|
||||
% [[file:figs/ustation_compliance_meas.png]]
|
||||
|
||||
% To convert the 12 acceleration signals $a_{\mathcal{L}} = [a_{1x}\ a_{1y}\ a_{1z}\ a_{2x}\ \dots\ a_{4z}]$ to the acceleration expressed in the frame $\{\mathcal{X}\}$ $a_{\mathcal{X}} = [a_{dx}\ a_{dy}\ a_{dz}\ a_{rx}\ a_{ry}\ a_{rz}]$, a Jacobian matrix $\bm{J}_a$ is written based on the positions and orientations of the accelerometers eqref:eq:ustation_compliance_acc_jacobian.
|
||||
|
||||
% \begin{equation}\label{eq:ustation_compliance_acc_jacobian}
|
||||
% \bm{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 using eqref:eq:ustation_compute_cart_acc.
|
||||
|
||||
% \begin{equation}\label{eq:ustation_compute_cart_acc}
|
||||
% a_{\mathcal{X}} = \bm{J}_a^\dagger \cdot a_{\mathcal{L}}
|
||||
% \end{equation}
|
||||
|
||||
% Similar to what is done for the accelerometers, a Jacobian matrix $\bm{J}_F$ is computed eqref:eq:ustation_compliance_force_jacobian and used to convert the individual hammer forces $F_{\mathcal{L}}$ to force and torques $F_{\mathcal{X}}$ applied at the center of the micro-hexapod top plate (defined by frame $\{\mathcal{X}\}$ in Figure ref:fig:ustation_compliance_meas).
|
||||
|
||||
% \begin{equation}\label{eq:ustation_compliance_force_jacobian}
|
||||
% \bm{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}
|
||||
|
||||
% The equivalent forces and torques applied at center of $\{\mathcal{X}\}$ are then computed using eqref:eq:ustation_compute_cart_force.
|
||||
|
||||
% \begin{equation}\label{eq:ustation_compute_cart_force}
|
||||
% F_{\mathcal{X}} = \bm{J}_F^t \cdot F_{\mathcal{L}}
|
||||
% \end{equation}
|
||||
|
||||
% Using the two Jacobian matrices, the FRF from the 10 hammer impacts to the 12 accelerometer outputs can be converted to the FRF from 6 forces/torques applied at the origin of frame $\{\mathcal{X}\}$ to the 6 linear/angular accelerations of the top platform expressed with respect to $\{\mathcal{X}\}$.
|
||||
% These FRFs were then used for comparison with the multi-body model.
|
||||
|
||||
|
||||
% Positions and orientation of accelerometers
|
||||
% | *Num* | *Position* | *Orientation* | *Sensibility* | *Channels* |
|
||||
% |-------+------------+---------------+---------------+------------|
|
||||
@ -345,13 +262,6 @@ end
|
||||
% FRF_cartesian = inv(Ja) * FRF * inv(Jf)
|
||||
FRF_cartesian = pagemtimes(Ja_inv, pagemtimes(G_raw, Jf_inv));
|
||||
|
||||
|
||||
|
||||
% The compliance of the micro-station multi-body model was extracted by computing the transfer function from forces/torques applied on the hexapod's top platform to the "absolute" motion of the top platform.
|
||||
% These results are compared with the measurements in Figure ref:fig:ustation_frf_compliance_model.
|
||||
% Considering the complexity of the micro-station compliance dynamics, the model compliance matches sufficiently well for the current application.
|
||||
|
||||
|
||||
%% Identification of the compliance of the micro-station
|
||||
|
||||
% Initialize simulation with default parameters (flexible elements)
|
||||
|
@ -1,5 +1,3 @@
|
||||
% Matlab Init :noexport:ignore:
|
||||
|
||||
%% ustation_3_disturbances.m
|
||||
|
||||
%% Clear Workspace and Close figures
|
||||
@ -25,13 +23,6 @@ colors = colororder;
|
||||
%% Frequency Vector
|
||||
freqs = logspace(log10(10), log10(2e3), 1000);
|
||||
|
||||
% Ground Motion
|
||||
|
||||
% The ground motion was measured by using a sensitive 3-axis geophone[fn:ustation_11] placed on the ground.
|
||||
% The generated voltages were recorded with a high resolution DAC, and converted to displacement using the Geophone sensitivity transfer function.
|
||||
% The obtained ground motion displacement is shown in Figure ref:fig:ustation_ground_disturbance.
|
||||
|
||||
|
||||
%% Compute Floor Motion Spectral Density
|
||||
% Load floor motion data
|
||||
% velocity in [m/s] is measured in X, Y and Z directions
|
||||
@ -69,24 +60,6 @@ xlim([0, 5]); ylim([-2, 2])
|
||||
leg = legend('location', 'northeast', 'FontSize', 8, 'NumColumns', 1);
|
||||
leg.ItemTokenSize(1) = 15;
|
||||
|
||||
% Ty Stage
|
||||
|
||||
% To measure the positioning errors of the translation stage, the setup shown in Figure ref:fig:ustation_errors_ty_setup is used.
|
||||
% A special optical element (called a "straightness interferometer"[fn:ustation_9]) is fixed on top of the micro-station, while a laser source[fn:ustation_10] and a straightness reflector are fixed on the ground.
|
||||
% A similar setup was used to measure the horizontal deviation (i.e. in the $x$ direction), as well as the pitch and yaw errors of the translation stage.
|
||||
|
||||
% #+name: fig:ustation_errors_ty_setup
|
||||
% #+caption: Experimental setup to measure the flatness (vertical deviation) of the translation stage
|
||||
% [[file:figs/ustation_errors_ty_setup.png]]
|
||||
|
||||
% Six scans were performed between $-4.5\,mm$ and $4.5\,mm$.
|
||||
% The results for each individual scan are shown in Figure ref:fig:ustation_errors_dy_vertical.
|
||||
% The measurement axis may not be perfectly aligned with the translation stage axis; this, a linear fit is removed from the measurement.
|
||||
% The remaining vertical displacement is shown in Figure ref:fig:ustation_errors_dy_vertical_remove_mean.
|
||||
% A vertical error of $\pm300\,nm$ induced by the translation stage is expected.
|
||||
% Similar result is obtained for the $x$ lateral direction.
|
||||
|
||||
|
||||
%% Ty errors
|
||||
% Setpoint is in [mm]
|
||||
% Vertical error is in [um]
|
||||
@ -113,27 +86,6 @@ plot(ty_errors.setpoint, ty_errors.ty_z - straight_line, 'k-')
|
||||
xlabel('$D_y$ position [mm]'); ylabel('Vertical error [$\mu$m]');
|
||||
xlim([-5, 5]); ylim([-0.4, 0.4]);
|
||||
|
||||
|
||||
|
||||
% #+name: fig:ustation_errors_dy
|
||||
% #+caption: Measurement of the linear (vertical) deviation of the Translation stage (\subref{fig:ustation_errors_dy_vertical}). A linear fit is then removed from the data (\subref{fig:ustation_errors_dy_vertical_remove_mean}).
|
||||
% #+attr_latex: :options [htbp]
|
||||
% #+begin_figure
|
||||
% #+attr_latex: :caption \subcaption{\label{fig:ustation_errors_dy_vertical}Measured vertical error}
|
||||
% #+attr_latex: :options {0.49\textwidth}
|
||||
% #+begin_subfigure
|
||||
% #+attr_latex: :width 0.95\linewidth
|
||||
% [[file:figs/ustation_errors_dy_vertical.png]]
|
||||
% #+end_subfigure
|
||||
% #+attr_latex: :caption \subcaption{\label{fig:ustation_errors_dy_vertical_remove_mean}Error after removing linear fit}
|
||||
% #+attr_latex: :options {0.49\textwidth}
|
||||
% #+begin_subfigure
|
||||
% #+attr_latex: :width 0.95\linewidth
|
||||
% [[file:figs/ustation_errors_dy_vertical_remove_mean.png]]
|
||||
% #+end_subfigure
|
||||
% #+end_figure
|
||||
|
||||
|
||||
%% Convert the data to frequency domain
|
||||
% Suppose a certain constant velocity scan
|
||||
delta_ty = (ty_errors.setpoint(end) - ty_errors.setpoint(1))/(length(ty_errors.setpoint) - 1); % [mm]
|
||||
@ -154,40 +106,6 @@ pxx_dy_dz = mean(pxx_dy_dz')';
|
||||
% is a reasonable assumption (and verified in practice)
|
||||
pxx_dy_dx = pxx_dy_dz;
|
||||
|
||||
% Spindle
|
||||
|
||||
% To measure the positioning errors induced by the Spindle, a "Spindle error analyzer"[fn:ustation_7] is used as shown in Figure ref:fig:ustation_rz_meas_lion_setup.
|
||||
% A specific target is fixed on top of the micro-station, which consists of two sphere with 1 inch diameter precisely aligned with the spindle rotation axis.
|
||||
% Five capacitive sensors[fn:ustation_8] are pointing at the two spheres, as shown in Figure ref:fig:ustation_rz_meas_lion_zoom.
|
||||
% From the 5 measured displacements $[d_1,\,d_2,\,d_3,\,d_4,\,d_5]$, the translations and rotations $[D_x,\,D_y,\,D_z,\,R_x,\,R_y]$ of the target can be estimated.
|
||||
|
||||
% #+name: fig:ustation_rz_meas_lion_setup
|
||||
% #+caption: Experimental setup used to estimate the errors induced by the Spindle rotation (\subref{fig:ustation_rz_meas_lion}). The motion of the two reference spheres is measured using 5 capacitive sensors (\subref{fig:ustation_rz_meas_lion_zoom})
|
||||
% #+attr_latex: :options [htbp]
|
||||
% #+begin_figure
|
||||
% #+attr_latex: :caption \subcaption{\label{fig:ustation_rz_meas_lion}Micro-station and 5-DoF metrology}
|
||||
% #+attr_latex: :options {0.49\textwidth}
|
||||
% #+begin_subfigure
|
||||
% #+attr_latex: :width 0.9\linewidth
|
||||
% [[file:figs/ustation_rz_meas_lion.jpg]]
|
||||
% #+end_subfigure
|
||||
% #+attr_latex: :caption \subcaption{\label{fig:ustation_rz_meas_lion_zoom}Zoom on the metrology system}
|
||||
% #+attr_latex: :options {0.49\textwidth}
|
||||
% #+begin_subfigure
|
||||
% #+attr_latex: :width 0.9\linewidth
|
||||
% [[file:figs/ustation_rz_meas_lion_zoom.jpg]]
|
||||
% #+end_subfigure
|
||||
% #+end_figure
|
||||
|
||||
% A measurement was performed during a constant rotational velocity of the spindle of 60rpm and during 10 turns.
|
||||
% The obtained results are shown in Figure ref:fig:ustation_errors_spindle.
|
||||
% A large fraction of the radial (Figure ref:fig:ustation_errors_spindle_radial) and tilt (Figure ref:fig:ustation_errors_spindle_tilt) errors is linked to the fact that the two spheres are not perfectly aligned with the rotation axis of the Spindle.
|
||||
% This is displayed by the dashed circle.
|
||||
% After removing the best circular fit from the data, the vibrations induced by the Spindle may be viewed as stochastic disturbances.
|
||||
% However, some misalignment between the "point-of-interest" of the sample and the rotation axis will be considered because the alignment is not perfect in practice.
|
||||
% The vertical motion induced by scanning the spindle is in the order of $\pm 30\,nm$ (Figure ref:fig:ustation_errors_spindle_axial).
|
||||
|
||||
|
||||
%% Spindle Errors
|
||||
% Errors are already converted to x,y,z,Rx,Ry
|
||||
% Units are in [m] and [rad]
|
||||
@ -226,33 +144,6 @@ xlim([-35, 35]); ylim([-35, 35]);
|
||||
xticks([-30, -15, 0, 15, 30]);
|
||||
yticks([-30, -15, 0, 15, 30]);
|
||||
|
||||
|
||||
|
||||
% #+name: fig:ustation_errors_spindle
|
||||
% #+caption: Measurement of the radial (\subref{fig:ustation_errors_spindle_radial}), axial (\subref{fig:ustation_errors_spindle_axial}) and tilt (\subref{fig:ustation_errors_spindle_tilt}) Spindle errors during a 60rpm spindle rotation. The circular best fit is shown by the dashed circle. It represents the misalignment of the spheres with the rotation axis.
|
||||
% #+attr_latex: :options [htbp]
|
||||
% #+begin_figure
|
||||
% #+attr_latex: :caption \subcaption{\label{fig:ustation_errors_spindle_radial}Radial errors}
|
||||
% #+attr_latex: :options {0.33\textwidth}
|
||||
% #+begin_subfigure
|
||||
% #+attr_latex: :width 0.9\linewidth
|
||||
% [[file:figs/ustation_errors_spindle_radial.png]]
|
||||
% #+end_subfigure
|
||||
% #+attr_latex: :caption \subcaption{\label{fig:ustation_errors_spindle_axial}Axial error}
|
||||
% #+attr_latex: :options {0.33\textwidth}
|
||||
% #+begin_subfigure
|
||||
% #+attr_latex: :width 0.9\linewidth
|
||||
% [[file:figs/ustation_errors_spindle_axial.png]]
|
||||
% #+end_subfigure
|
||||
% #+attr_latex: :caption \subcaption{\label{fig:ustation_errors_spindle_tilt}Tilt errors}
|
||||
% #+attr_latex: :options {0.33\textwidth}
|
||||
% #+begin_subfigure
|
||||
% #+attr_latex: :width 0.9\linewidth
|
||||
% [[file:figs/ustation_errors_spindle_tilt.png]]
|
||||
% #+end_subfigure
|
||||
% #+end_figure
|
||||
|
||||
|
||||
%% Remove the circular fit from the data
|
||||
[x0, y0, R] = circlefit(spindle_errors.Dx, spindle_errors.Dy);
|
||||
|
||||
@ -279,14 +170,6 @@ Noverlap = floor(Nfft/2); % Overlap for frequency analysis
|
||||
[pxx_rz_dx, ~ ] = pwelch(spindle_errors.Dx_err, win, Noverlap, Nfft, Fs);
|
||||
[pxx_rz_dy, ~ ] = pwelch(spindle_errors.Dy_err, win, Noverlap, Nfft, Fs);
|
||||
|
||||
% Sensitivity to disturbances
|
||||
% <<ssec:ustation_disturbances_sensitivity>>
|
||||
|
||||
% To compute the disturbance source (i.e. forces) that induced the measured vibrations in Section ref:ssec:ustation_disturbances_meas, the transfer function from the disturbance sources to the stage vibration (i.e. the "sensitivity to disturbances") needs to be estimated.
|
||||
% This is achieved using the multi-body model presented in Section ref:sec:ustation_modeling.
|
||||
% The obtained transfer functions are shown in Figure ref:fig:ustation_model_sensitivity.
|
||||
|
||||
|
||||
%% Extract sensitivity to disturbances from the Simscape model
|
||||
% Initialize stages
|
||||
initializeGround();
|
||||
@ -361,13 +244,6 @@ ylim([1e-10, 1e-7]);
|
||||
leg = legend('location', 'northwest', 'FontSize', 8, 'NumColumns', 1);
|
||||
leg.ItemTokenSize(1) = 15;
|
||||
|
||||
% Obtained disturbance sources
|
||||
% <<ssec:ustation_disturbances_results>>
|
||||
|
||||
% From the measured effect of disturbances in Section ref:ssec:ustation_disturbances_meas and the sensitivity to disturbances extracted from the multi-body model in Section ref:ssec:ustation_disturbances_sensitivity, the power spectral density of the disturbance sources (i.e. forces applied in the stage's joint) can be estimated.
|
||||
% The obtained power spectral density of the disturbances are shown in Figure ref:fig:ustation_dist_sources.
|
||||
|
||||
|
||||
%% Compute the PSD of the equivalent disturbance sources
|
||||
pxx_rz_fx = pxx_rz_dx./abs(squeeze(freqresp(Gd('Dx', 'Frz_x'), f_rz, 'Hz'))).^2;
|
||||
pxx_rz_fy = pxx_rz_dy./abs(squeeze(freqresp(Gd('Dy', 'Frz_y'), f_rz, 'Hz'))).^2;
|
||||
@ -435,38 +311,6 @@ xlim([1, 200]); ylim([1e-3, 1e3]);
|
||||
leg = legend('location', 'northeast', 'FontSize', 8, 'NumColumns', 1);
|
||||
leg.ItemTokenSize(1) = 15;
|
||||
|
||||
|
||||
|
||||
% #+name: fig:ustation_dist_sources
|
||||
% #+caption: Measured spectral density of the micro-station disturbance sources. Ground motion (\subref{fig:ustation_dist_source_ground_motion}), translation stage (\subref{fig:ustation_dist_source_translation_stage}) and spindle (\subref{fig:ustation_dist_source_spindle}).
|
||||
% #+attr_latex: :options [htbp]
|
||||
% #+begin_figure
|
||||
% #+attr_latex: :caption \subcaption{\label{fig:ustation_dist_source_ground_motion}Ground Motion}
|
||||
% #+attr_latex: :options {0.33\textwidth}
|
||||
% #+begin_subfigure
|
||||
% #+attr_latex: :width 0.9\linewidth
|
||||
% [[file:figs/ustation_dist_source_ground_motion.png]]
|
||||
% #+end_subfigure
|
||||
% #+attr_latex: :caption \subcaption{\label{fig:ustation_dist_source_translation_stage}Translation Stage}
|
||||
% #+attr_latex: :options {0.33\textwidth}
|
||||
% #+begin_subfigure
|
||||
% #+attr_latex: :width 0.9\linewidth
|
||||
% [[file:figs/ustation_dist_source_translation_stage.png]]
|
||||
% #+end_subfigure
|
||||
% #+attr_latex: :caption \subcaption{\label{fig:ustation_dist_source_spindle}Spindle}
|
||||
% #+attr_latex: :options {0.33\textwidth}
|
||||
% #+begin_subfigure
|
||||
% #+attr_latex: :width 0.9\linewidth
|
||||
% [[file:figs/ustation_dist_source_spindle.png]]
|
||||
% #+end_subfigure
|
||||
% #+end_figure
|
||||
|
||||
% The disturbances are characterized by their power spectral densities, as shown in Figure ref:fig:ustation_dist_sources.
|
||||
% However, to perform time domain simulations, disturbances must be represented by a time domain signal.
|
||||
% To generate stochastic time-domain signals with a specific power spectral densities, the discrete inverse Fourier transform is used, as explained in [[cite:&preumont94_random_vibrat_spect_analy chap. 12.11]].
|
||||
% Examples of the obtained time-domain disturbance signals are shown in Figure ref:fig:ustation_dist_sources_time.
|
||||
|
||||
|
||||
%% Compute time domain disturbance signals
|
||||
initializeDisturbances();
|
||||
load('nass_model_disturbances.mat');
|
||||
|
@ -1,5 +1,3 @@
|
||||
% Matlab Init :noexport:ignore:
|
||||
|
||||
%% ustation_4_experiments.m
|
||||
|
||||
%% Clear Workspace and Close figures
|
||||
@ -25,17 +23,6 @@ colors = colororder;
|
||||
%% Frequency Vector
|
||||
freqs = logspace(log10(10), log10(2e3), 1000);
|
||||
|
||||
% Tomography Experiment
|
||||
% <<sec:ustation_experiments_tomography>>
|
||||
|
||||
% To simulate a tomography experiment, the setpoint of the Spindle is configured to perform a constant rotation with a rotational velocity of 60rpm.
|
||||
% Both ground motion and spindle vibration disturbances were simulated based on what was computed in Section ref:sec:ustation_disturbances.
|
||||
% A radial offset of $\approx 1\,\mu m$ between the "point-of-interest" and the spindle's rotation axis is introduced to represent what is experimentally observed.
|
||||
% During the 10 second simulation (i.e. 10 spindle turns), the position of the "point-of-interest" with respect to the granite was recorded.
|
||||
% Results are shown in Figure ref:fig:ustation_errors_model_spindle.
|
||||
% A good correlation with the measurements is observed both for radial errors (Figure ref:fig:ustation_errors_model_spindle_radial) and axial errors (Figure ref:fig:ustation_errors_model_spindle_axial).
|
||||
|
||||
|
||||
%% Tomography experiment
|
||||
% Sample is not centered with the rotation axis
|
||||
% This is done by offsetfing the micro-hexapod by 0.9um
|
||||
@ -100,16 +87,6 @@ xlim([0,2]); ylim([-40, 40]);
|
||||
leg = legend('location', 'southwest', 'FontSize', 8, 'NumColumns', 1);
|
||||
leg.ItemTokenSize(1) = 15;
|
||||
|
||||
% Raster Scans with the translation stage
|
||||
% <<sec:ustation_experiments_ty_scans>>
|
||||
|
||||
% A second experiment was performed in which the translation stage was scanned at constant velocity.
|
||||
% The translation stage setpoint is configured to have a "triangular" shape with stroke of $\pm 4.5\, mm$.
|
||||
% Both ground motion and translation stage vibrations were included in the simulation.
|
||||
% Similar to what was performed for the tomography simulation, the PoI position with respect to the granite was recorded and compared with the experimental measurements in Figure ref:fig:ustation_errors_model_dy_vertical.
|
||||
% A similar error amplitude was observed, thus indicating that the multi-body model with the included disturbances accurately represented the micro-station behavior in typical scientific experiments.
|
||||
|
||||
|
||||
%% Translation stage latteral scans
|
||||
set_param(conf_simulink, 'StopTime', '2');
|
||||
|
||||
|
@ -22,7 +22,7 @@
|
||||
#+BIND: org-latex-bib-compiler "biber"
|
||||
|
||||
#+PROPERTY: header-args:matlab :session *MATLAB*
|
||||
#+PROPERTY: header-args:matlab+ :comments org
|
||||
#+PROPERTY: header-args:matlab+ :comments no
|
||||
#+PROPERTY: header-args:matlab+ :exports none
|
||||
#+PROPERTY: header-args:matlab+ :results none
|
||||
#+PROPERTY: header-args:matlab+ :eval no-export
|
||||
|
Reference in New Issue
Block a user