nass-simscape/org/uncertainty_experiment.org

1906 lines
72 KiB
Org Mode
Raw Normal View History

#+TITLE: Evaluating the Plant Uncertainty in various experimental conditions
#+SETUPFILE: ./setup/org-setup-file.org
* Introduction :ignore:
The goal of this document is to study how the dynamics of the system is changing with the experimental conditions.
These experimental conditions are:
- Section [[sec:variability_sample_mass]]: Sample mass (from 1Kg to 50Kg)
- Section [[sec:variability_sample_freq]]: Sample dynamics (mostly main resonance frequency)
- Section [[sec:variability_spindle_angle]]: The spindle angle
- Section [[sec:variability_rotation_speed]]: The spindle rotation speed (from 1rpm to 60rpm)
- Section [[sec:variability_tilt_angle]]: The tilt angle (from -3 to 3 degrees)
- Section [[sec:micro_hexapod_pose]]: Pose of the micro-hexapod
We are interested in the dynamics from the nano-hexapod actuators to:
- the sensors included in the nano-hexapod (force sensor, relative motion sensor)
- the measured position of the sample with respect to the granite
The variability of the dynamics is studied for two nano-hexapod concepts:
- a soft nano-hexapod
- a stiff nano-hexapod
The conclusions are drawn in Section [[sec:conclusion]]
* 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
#+begin_src matlab
open('nass_model.slx')
#+end_src
* Variation of the Sample Mass
<<sec:variability_sample_mass>>
** Introduction :ignore:
We here study the change of dynamics due to the sample mass.
To see only the effect of the sample mass, we keep the same resonance frequency of the sample, and we set it to 10kHz so it is above the dynamics of interest.
** Identification :ignore:
We initialize all the stages with the default parameters.
#+begin_src matlab :exports none :noweb yes
<<init-sim>>
<<init-identification>>
#+end_src
We identify the dynamics for the following sample masses, both with a soft and stiff nano-hexapod.
#+begin_src matlab
masses = [1, 10, 50]; % [kg]
#+end_src
#+begin_src matlab :exports none
nano_hexapod = initializeNanoHexapod('actuator', 'lorentz');
Gm_vc_iff = {zeros(length(masses))};
Gm_vc_dvf = {zeros(length(masses))};
Gm_vc_err = {zeros(length(masses))};
for i = 1:length(masses)
initializeSample('mass', masses(i), 'freq', 1e4*ones(6,1));
%% Run the linearization
G = linearize(mdl, io);
G.InputName = {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'};
G.OutputName = {'Dnlm1', 'Dnlm2', 'Dnlm3', 'Dnlm4', 'Dnlm5', 'Dnlm6', ...
'Fnlm1', 'Fnlm2', 'Fnlm3', 'Fnlm4', 'Fnlm5', 'Fnlm6', ...
'Ex', 'Ey', 'Ez', 'Erx', 'Ery', 'Erz'};
Gm_vc_iff(i) = {minreal(G({'Fnlm1', 'Fnlm2', 'Fnlm3', 'Fnlm4', 'Fnlm5', 'Fnlm6'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))};
Gm_vc_dvf(i) = {minreal(G({'Dnlm1', 'Dnlm2', 'Dnlm3', 'Dnlm4', 'Dnlm5', 'Dnlm6'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))};
Jinvt = tf(inv(nano_hexapod.J)');
Jinvt.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
Jinvt.OutputName = {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'};
Gm_vc_err(i) = {-minreal(G({'Ex', 'Ey', 'Ez', 'Erx', 'Ery', 'Erz'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))*Jinvt};
end
#+end_src
#+begin_src matlab :exports none
nano_hexapod = initializeNanoHexapod('actuator', 'piezo');
Gm_pz_iff = {zeros(length(masses))};
Gm_pz_dvf = {zeros(length(masses))};
Gm_pz_err = {zeros(length(masses))};
for i = 1:length(masses)
initializeSample('mass', masses(i), 'freq', 1e4*ones(6,1));
%% Run the linearization
G = linearize(mdl, io);
G.InputName = {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'};
G.OutputName = {'Dnlm1', 'Dnlm2', 'Dnlm3', 'Dnlm4', 'Dnlm5', 'Dnlm6', ...
'Fnlm1', 'Fnlm2', 'Fnlm3', 'Fnlm4', 'Fnlm5', 'Fnlm6', ...
'Ex', 'Ey', 'Ez', 'Erx', 'Ery', 'Erz'};
Gm_pz_iff(i) = {minreal(G({'Fnlm1', 'Fnlm2', 'Fnlm3', 'Fnlm4', 'Fnlm5', 'Fnlm6'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))};
Gm_pz_dvf(i) = {minreal(G({'Dnlm1', 'Dnlm2', 'Dnlm3', 'Dnlm4', 'Dnlm5', 'Dnlm6'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))};
Jinvt = tf(inv(nano_hexapod.J)');
Jinvt.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
Jinvt.OutputName = {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'};
Gm_pz_err(i) = {-minreal(G({'Ex', 'Ey', 'Ez', 'Erx', 'Ery', 'Erz'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))*Jinvt};
end
#+end_src
#+begin_src matlab :exports none
save('./mat/dynamics_variability_mass.mat', 'masses', ...
'Gm_vc_iff', 'Gm_vc_dvf', 'Gm_vc_err', ...
'Gm_pz_iff', 'Gm_pz_dvf', 'Gm_pz_err');
#+end_src
** Plots :ignore:
#+begin_src matlab :exports none
load('./mat/dynamics_variability_mass.mat');
#+end_src
The following transfer functions are shown:
- Figure [[fig:dynamics_variability_iff_sample_mass]]: From actuator forces to force sensors in each nano-hexapod's leg
- Figure [[fig:dynamics_variability_dvf_sample_mass]]: From actuator forces to relative displacement of each nano-hexapod's leg
- Figure [[fig:dynamics_variability_err_x_sample_mass]] (resp. [[fig:dynamics_variability_err_z_sample_mass]]): From forces applied in the task space by the nano-hexapod to displacement of the sample in the X direction (resp. in the Z direction)
#+begin_src matlab :exports none
freqs = logspace(-1, 2, 1000);
figure;
ax1 = subplot(2, 2, 1);
hold on;
for i = 1:length(Gm_vc_iff)
plot(freqs, abs(squeeze(freqresp(Gm_vc_iff{i}('Fnlm1', 'Fnl1'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [N/N]'); set(gca, 'XTickLabel',[]);
title('Soft Nano-Hexapod');
ax2 = subplot(2, 2, 3);
hold on;
for i = 1:length(Gm_vc_iff)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gm_vc_iff{i}('Fnlm1', 'Fnl1'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$M = %.0f$ [kg]', masses(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
freqs = logspace(0, 3, 1000);
ax1 = subplot(2, 2, 2);
hold on;
for i = 1:length(Gm_pz_iff)
plot(freqs, abs(squeeze(freqresp(Gm_pz_iff{i}('Fnlm1', 'Fnl1'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [N/N]'); set(gca, 'XTickLabel',[]);
title('Stiff Nano-Hexapod');
ax2 = subplot(2, 2, 4);
hold on;
for i = 1:length(Gm_pz_iff)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gm_pz_iff{i}('Fnlm1', 'Fnl1'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$M = %.0f$ [kg]', masses(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
#+end_src
#+HEADER: :tangle no :exports results :results none :noweb yes
#+begin_src matlab :var filepath="figs/dynamics_variability_iff_sample_mass.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png")
<<plt-matlab>>
#+end_src
#+name: fig:dynamics_variability_iff_sample_mass
#+caption: Variability of the dynamics from actuator force to force sensor with the Sample Mass ([[./figs/dynamics_variability_iff_sample_mass.png][png]], [[./figs/dynamics_variability_iff_sample_mass.pdf][pdf]])
[[file:figs/dynamics_variability_iff_sample_mass.png]]
#+begin_src matlab :exports none
freqs = logspace(-1, 3, 1000);
figure;
ax1 = subplot(2, 2, 1);
hold on;
for i = 1:length(Gm_vc_dvf)
plot(freqs, abs(squeeze(freqresp(Gm_vc_dvf{i}('Dnlm1', 'Fnl1'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]);
title('Soft Nano-Hexapod');
ax2 = subplot(2, 2, 3);
hold on;
for i = 1:length(Gm_vc_dvf)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gm_vc_dvf{i}('Dnlm1', 'Fnl1'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$M = %.0f$ [kg]', masses(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
freqs = logspace(0, 3, 1000);
ax1 = subplot(2, 2, 2);
hold on;
for i = 1:length(Gm_pz_dvf)
plot(freqs, abs(squeeze(freqresp(Gm_pz_dvf{i}('Dnlm1', 'Fnl1'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]);
title('Stiff Nano-Hexapod');
ax2 = subplot(2, 2, 4);
hold on;
for i = 1:length(Gm_pz_dvf)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gm_pz_dvf{i}('Dnlm1', 'Fnl1'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$M = %.0f$ [kg]', masses(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
#+end_src
#+HEADER: :tangle no :exports results :results none :noweb yes
#+begin_src matlab :var filepath="figs/dynamics_variability_dvf_sample_mass.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png")
<<plt-matlab>>
#+end_src
#+name: fig:dynamics_variability_dvf_sample_mass
#+caption: Variability of the dynamics from actuator force to relative motion sensor with the Sample Mass ([[./figs/dynamics_variability_dvf_sample_mass.png][png]], [[./figs/dynamics_variability_dvf_sample_mass.pdf][pdf]])
[[file:figs/dynamics_variability_dvf_sample_mass.png]]
#+begin_src matlab :exports none
freqs = logspace(-1, 3, 1000);
figure;
ax1 = subplot(2, 2, 1);
hold on;
for i = 1:length(Gm_vc_err)
plot(freqs, abs(squeeze(freqresp(Gm_vc_err{i}('Erx', 'Mx'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]);
title('Soft Nano-Hexapod');
ax2 = subplot(2, 2, 3);
hold on;
for i = 1:length(Gm_vc_err)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gm_vc_err{i}('Erx', 'Mx'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$M = %.0f$ [kg]', masses(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
freqs = logspace(0, 3, 1000);
ax1 = subplot(2, 2, 2);
hold on;
for i = 1:length(Gm_pz_err)
plot(freqs, abs(squeeze(freqresp(Gm_pz_err{i}('Erx', 'Mx'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]);
title('Stiff Nano-Hexapod');
ax2 = subplot(2, 2, 4);
hold on;
for i = 1:length(Gm_pz_err)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gm_pz_err{i}('Erx', 'Mx'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$M = %.0f$ [kg]', masses(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
#+end_src
#+HEADER: :tangle no :exports results :results none :noweb yes
#+begin_src matlab :var filepath="figs/dynamics_variability_err_x_sample_mass.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png")
<<plt-matlab>>
#+end_src
#+name: fig:dynamics_variability_err_x_sample_mass
#+caption: Variability of the dynamics from Forces applied in task space (X direction) to the displacement of the sample in the X direction ([[./figs/dynamics_variability_err_x_sample_mass.png][png]], [[./figs/dynamics_variability_err_x_sample_mass.pdf][pdf]])
[[file:figs/dynamics_variability_err_x_sample_mass.png]]
#+begin_src matlab :exports none
freqs = logspace(-1, 3, 1000);
figure;
ax1 = subplot(2, 2, 1);
hold on;
for i = 1:length(Gm_vc_err)
plot(freqs, abs(squeeze(freqresp(Gm_vc_err{i}('Ez', 'Fz'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]);
title('Soft Nano-Hexapod');
ax2 = subplot(2, 2, 3);
hold on;
for i = 1:length(Gm_vc_err)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gm_vc_err{i}('Ez', 'Fz'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$M = %.0f$ [kg]', masses(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
freqs = logspace(0, 3, 1000);
ax1 = subplot(2, 2, 2);
hold on;
for i = 1:length(Gm_pz_err)
plot(freqs, abs(squeeze(freqresp(Gm_pz_err{i}('Ez', 'Fz'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]);
title('Stiff Nano-Hexapod');
ax2 = subplot(2, 2, 4);
hold on;
for i = 1:length(Gm_pz_err)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gm_pz_err{i}('Ez', 'Fz'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$M = %.0f$ [kg]', masses(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
#+end_src
#+HEADER: :tangle no :exports results :results none :noweb yes
#+begin_src matlab :var filepath="figs/dynamics_variability_err_z_sample_mass.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png")
<<plt-matlab>>
#+end_src
#+name: fig:dynamics_variability_err_z_sample_mass
#+caption: Variability of the dynamics from vertical forces applied in the task space to the displacement of the sample in the vertical direction ([[./figs/dynamics_variability_err_z_sample_mass.png][png]], [[./figs/dynamics_variability_err_z_sample_mass.pdf][pdf]])
[[file:figs/dynamics_variability_err_z_sample_mass.png]]
** Conclusion :ignore:
#+begin_important
Let's note $\omega_0$ the first resonance which corresponds to the resonance of the payload+nano-hexapod top platform resonating on top of the nano-hexapod base.
An increase of the payload mass decreases $\omega_0$.
This is more easily seem with the soft nano-hexapod as the resonance $\omega_0$ is separated from the resonances of the micro-station.
- For the soft nano-hexapod, the main effect is the change of $\omega_0$.
- For the stiff nano-hexapod, it also affects the others resonances corresponding to the resonances of the micro-station
| | $\frac{\tau_{mi}}{\tau_m}$ | $\frac{d\mathcal{L}_i}{\tau_i}$ | $\frac{\mathcal{X}_i}{\mathcal{F}_i}$ |
|--------------------+----------------------------------------------------------+-----------------------------------------------------------+--------------------------------------------|
| Soft Nano-Hexapod | Changes the low frequency gain | Changes the high frequency gain | Changes $\omega_0$ and high frequency gain |
| Stiff Nano-Hexapod | Changes the location of the modes and low frequency gain | Changes the location of the modes and high frequency gain | Changes the dynamics above $\omega_0$ |
#+end_important
* Variation of the Sample Resonance Frequency
<<sec:variability_sample_freq>>
** Introduction :ignore:
** Identification :ignore:
We initialize all the stages with the default parameters.
#+begin_src matlab :exports none :noweb yes
<<init-sim>>
<<init-identification>>
#+end_src
We identify the dynamics for the following sample resonance frequency.
#+begin_src matlab
mass_w = [50, 100, 500]; % [Hz]
mass = 10; % [Kg]
#+end_src
#+begin_src matlab :exports none
nano_hexapod = initializeNanoHexapod('actuator', 'lorentz');
Gmf_vc_iff = {zeros(length(mass_w))};
Gmf_vc_dvf = {zeros(length(mass_w))};
Gmf_vc_err = {zeros(length(mass_w))};
for i = 1:length(mass_w)
initializeSample('mass', mass, 'freq', mass_w(i)*ones(6,1));
%% Run the linearization
G = linearize(mdl, io);
G.InputName = {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'};
G.OutputName = {'Dnlm1', 'Dnlm2', 'Dnlm3', 'Dnlm4', 'Dnlm5', 'Dnlm6', ...
'Fnlm1', 'Fnlm2', 'Fnlm3', 'Fnlm4', 'Fnlm5', 'Fnlm6', ...
'Ex', 'Ey', 'Ez', 'Erx', 'Ery', 'Erz'};
Gmf_vc_iff(i) = {minreal(G({'Fnlm1', 'Fnlm2', 'Fnlm3', 'Fnlm4', 'Fnlm5', 'Fnlm6'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))};
Gmf_vc_dvf(i) = {minreal(G({'Dnlm1', 'Dnlm2', 'Dnlm3', 'Dnlm4', 'Dnlm5', 'Dnlm6'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))};
Jinvt = tf(inv(nano_hexapod.J)');
Jinvt.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
Jinvt.OutputName = {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'};
Gmf_vc_err(i) = {-minreal(G({'Ex', 'Ey', 'Ez', 'Erx', 'Ery', 'Erz'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))*Jinvt};
end
#+end_src
#+begin_src matlab :exports none
nano_hexapod = initializeNanoHexapod('actuator', 'piezo');
Gmf_pz_iff = {zeros(length(mass_w))};
Gmf_pz_dvf = {zeros(length(mass_w))};
Gmf_pz_err = {zeros(length(mass_w))};
for i = 1:length(mass_w)
initializeSample('mass', mass, 'freq', mass_w(i)*ones(6,1));
%% Run the linearization
G = linearize(mdl, io);
G.InputName = {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'};
G.OutputName = {'Dnlm1', 'Dnlm2', 'Dnlm3', 'Dnlm4', 'Dnlm5', 'Dnlm6', ...
'Fnlm1', 'Fnlm2', 'Fnlm3', 'Fnlm4', 'Fnlm5', 'Fnlm6', ...
'Ex', 'Ey', 'Ez', 'Erx', 'Ery', 'Erz'};
Gmf_pz_iff(i) = {minreal(G({'Fnlm1', 'Fnlm2', 'Fnlm3', 'Fnlm4', 'Fnlm5', 'Fnlm6'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))};
Gmf_pz_dvf(i) = {minreal(G({'Dnlm1', 'Dnlm2', 'Dnlm3', 'Dnlm4', 'Dnlm5', 'Dnlm6'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))};
Jinvt = tf(inv(nano_hexapod.J)');
Jinvt.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
Jinvt.OutputName = {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'};
Gmf_pz_err(i) = {-minreal(G({'Ex', 'Ey', 'Ez', 'Erx', 'Ery', 'Erz'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))*Jinvt};
end
#+end_src
#+begin_src matlab :exports none
save('./mat/dynamics_variability_mass_freq.mat', 'mass_w', ...
'Gmf_vc_iff', 'Gmf_vc_dvf', 'Gmf_vc_err', ...
'Gmf_pz_iff', 'Gmf_pz_dvf', 'Gmf_pz_err');
#+end_src
** Plots :ignore:
#+begin_src matlab :exports none
load('./mat/dynamics_variability_mass_freq.mat');
#+end_src
The following transfer functions are shown:
- Figure [[fig:dynamics_variability_iff_sample_w]]: From actuator forces to force sensors in each nano-hexapod's leg
- Figure [[fig:dynamics_variability_dvf_sample_w]]: From actuator forces to relative displacement of each nano-hexapod's leg
- Figure [[fig:dynamics_variability_err_sample_w]]: From forces applied in the task space by the nano-hexapod to displacement of the sample in the X direction
#+begin_src matlab :exports none
freqs = logspace(-1, 3, 1000);
figure;
ax1 = subplot(2, 2, 1);
hold on;
for i = 1:length(Gmf_vc_iff)
plot(freqs, abs(squeeze(freqresp(Gmf_vc_iff{i}('Fnlm1', 'Fnl1'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [N/N]'); set(gca, 'XTickLabel',[]);
title('Soft Nano-Hexapod');
ax2 = subplot(2, 2, 3);
hold on;
for i = 1:length(Gmf_vc_iff)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gmf_vc_iff{i}('Fnlm1', 'Fnl1'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$\\omega_m = %.0f$ [Hz]', mass_w(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
freqs = logspace(0, 3, 1000);
ax1 = subplot(2, 2, 2);
hold on;
for i = 1:length(Gmf_pz_iff)
plot(freqs, abs(squeeze(freqresp(Gmf_pz_iff{i}('Fnlm1', 'Fnl1'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [N/N]'); set(gca, 'XTickLabel',[]);
title('Stiff Nano-Hexapod');
ax2 = subplot(2, 2, 4);
hold on;
for i = 1:length(Gmf_pz_iff)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gmf_pz_iff{i}('Fnlm1', 'Fnl1'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$\\omega_m = %.0f$ [Hz]', mass_w(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
#+end_src
#+HEADER: :tangle no :exports results :results none :noweb yes
#+begin_src matlab :var filepath="figs/dynamics_variability_iff_sample_w.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png")
<<plt-matlab>>
#+end_src
#+name: fig:dynamics_variability_iff_sample_w
#+caption: Variability of the dynamics from actuator force to force sensor with the Sample Mass ([[./figs/dynamics_variability_iff_sample_w.png][png]], [[./figs/dynamics_variability_iff_sample_w.pdf][pdf]])
[[file:figs/dynamics_variability_iff_sample_w.png]]
#+begin_src matlab :exports none
freqs = logspace(-1, 3, 1000);
figure;
ax1 = subplot(2, 2, 1);
hold on;
for i = 1:length(Gmf_vc_dvf)
plot(freqs, abs(squeeze(freqresp(Gmf_vc_dvf{i}('Dnlm1', 'Fnl1'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]);
title('Soft Nano-Hexapod');
ax2 = subplot(2, 2, 3);
hold on;
for i = 1:length(Gmf_vc_dvf)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gmf_vc_dvf{i}('Dnlm1', 'Fnl1'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$\\omega_m = %.0f$ [Hz]', mass_w(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
freqs = logspace(0, 3, 1000);
ax1 = subplot(2, 2, 2);
hold on;
for i = 1:length(Gmf_pz_dvf)
plot(freqs, abs(squeeze(freqresp(Gmf_pz_dvf{i}('Dnlm1', 'Fnl1'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]);
title('Stiff Nano-Hexapod');
ax2 = subplot(2, 2, 4);
hold on;
for i = 1:length(Gmf_pz_dvf)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gmf_pz_dvf{i}('Dnlm1', 'Fnl1'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$\\omega_m = %.0f$ [Hz]', mass_w(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
#+end_src
#+HEADER: :tangle no :exports results :results none :noweb yes
#+begin_src matlab :var filepath="figs/dynamics_variability_dvf_sample_w.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png")
<<plt-matlab>>
#+end_src
#+name: fig:dynamics_variability_dvf_sample_w
#+caption: Variability of the dynamics from actuator force to relative motion sensor with the Sample Mass ([[./figs/dynamics_variability_dvf_sample_w.png][png]], [[./figs/dynamics_variability_dvf_sample_w.pdf][pdf]])
[[file:figs/dynamics_variability_dvf_sample_w.png]]
#+begin_src matlab :exports none
freqs = logspace(-1, 3, 1000);
figure;
ax1 = subplot(2, 2, 1);
hold on;
for i = 1:length(Gmf_vc_err)
plot(freqs, abs(squeeze(freqresp(Gmf_vc_err{i}('Erx', 'Mx'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [rad/(Nm)]'); set(gca, 'XTickLabel',[]);
title('Soft Nano-Hexapod');
ax2 = subplot(2, 2, 3);
hold on;
for i = 1:length(Gmf_vc_err)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gmf_vc_err{i}('Erx', 'Mx'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$\\omega_m = %.0f$ [Hz]', mass_w(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
freqs = logspace(0, 3, 1000);
ax1 = subplot(2, 2, 2);
hold on;
for i = 1:length(Gmf_pz_err)
plot(freqs, abs(squeeze(freqresp(Gmf_pz_err{i}('Erx', 'Mx'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [rad/(Nm)]'); set(gca, 'XTickLabel',[]);
title('Stiff Nano-Hexapod');
ax2 = subplot(2, 2, 4);
hold on;
for i = 1:length(Gmf_pz_err)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gmf_pz_err{i}('Erx', 'Mx'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$\\omega_m = %.0f$ [Hz]', mass_w(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
#+end_src
#+HEADER: :tangle no :exports results :results none :noweb yes
#+begin_src matlab :var filepath="figs/dynamics_variability_err_sample_w.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png")
<<plt-matlab>>
#+end_src
#+name: fig:dynamics_variability_err_sample_w
#+caption: Variability of the dynamics from a torque applied on the sample by the nano-hexapod in the X direction to the rotation of the sample around the X axis ([[./figs/dynamics_variability_err_sample_w.png][png]], [[./figs/dynamics_variability_err_sample_w.pdf][pdf]])
[[file:figs/dynamics_variability_err_sample_w.png]]
** Conclusion :ignore:
#+begin_important
Let's note $\omega_m$ the frequency of the resonance of the Payload.
| | $\frac{\tau_{mi}}{\tau_m}$ | $\frac{d\mathcal{L}_i}{\tau_i}$ | $\frac{\mathcal{X}_i}{\mathcal{F}_i}$ |
|--------------------+------------------------------+---------------------------------+---------------------------------------------------------|
| Soft Nano-Hexapod | No visible effect | Small effect around $\omega_m$ | Two c.c. zeros at $\omega_m$ followed by two c.c. poles |
| Stiff Nano-Hexapod | Slightly change the dynamics | Slightly change the dynamics | Greatly affect the dynamics above the first resonance |
#+end_important
* Variation of the Spindle Angle
<<sec:variability_spindle_angle>>
** Introduction :ignore:
** Identification
#+begin_src matlab :exports none :noweb yes
<<init-sim>>
<<init-identification>>
#+end_src
We identify the dynamics for the following Tilt stage angles.
#+begin_src matlab
initializeSample('mass', 50);
Rz_amplitudes = [0, pi/4, pi/2, pi]; % [rad]
#+end_src
#+begin_src matlab :exports none
nano_hexapod = initializeNanoHexapod('actuator', 'lorentz');
Grz_vc_iff = {zeros(length(Rz_amplitudes))};
Grz_vc_dvf = {zeros(length(Rz_amplitudes))};
Grz_vc_err = {zeros(length(Rz_amplitudes))};
for i = 1:length(Rz_amplitudes)
initializeReferences('Rz_type', 'constant', 'Rz_amplitude', Rz_amplitudes(i))
%% Run the linearization
G = linearize(mdl, io, 1e-3);
G.InputName = {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'};
G.OutputName = {'Dnlm1', 'Dnlm2', 'Dnlm3', 'Dnlm4', 'Dnlm5', 'Dnlm6', ...
'Fnlm1', 'Fnlm2', 'Fnlm3', 'Fnlm4', 'Fnlm5', 'Fnlm6', ...
'Ex', 'Ey', 'Ez', 'Erx', 'Ery', 'Erz'};
Grz_vc_iff(i) = {minreal(G({'Fnlm1', 'Fnlm2', 'Fnlm3', 'Fnlm4', 'Fnlm5', 'Fnlm6'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))};
Grz_vc_dvf(i) = {minreal(G({'Dnlm1', 'Dnlm2', 'Dnlm3', 'Dnlm4', 'Dnlm5', 'Dnlm6'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))};
Jinvt = tf(inv(nano_hexapod.J)');
Jinvt.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
Jinvt.OutputName = {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'};
Grz_vc_err(i) = {-minreal(G({'Ex', 'Ey', 'Ez', 'Erx', 'Ery', 'Erz'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))*Jinvt};
end
#+end_src
#+begin_src matlab :exports none
nano_hexapod = initializeNanoHexapod('actuator', 'piezo', 'Foffset', true);
Grz_pz_iff = {zeros(length(Rz_amplitudes))};
Grz_pz_dvf = {zeros(length(Rz_amplitudes))};
Grz_pz_err = {zeros(length(Rz_amplitudes))};
for i = 1:length(Rz_amplitudes)
initializeReferences('Rz_type', 'constant', 'Rz_amplitude', Rz_amplitudes(i))
%% Run the linearization
G = linearize(mdl, io, 1e-3);
G.InputName = {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'};
G.OutputName = {'Dnlm1', 'Dnlm2', 'Dnlm3', 'Dnlm4', 'Dnlm5', 'Dnlm6', ...
'Fnlm1', 'Fnlm2', 'Fnlm3', 'Fnlm4', 'Fnlm5', 'Fnlm6', ...
'Ex', 'Ey', 'Ez', 'Erx', 'Ery', 'Erz'};
Grz_pz_iff(i) = {minreal(G({'Fnlm1', 'Fnlm2', 'Fnlm3', 'Fnlm4', 'Fnlm5', 'Fnlm6'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))};
Grz_pz_dvf(i) = {minreal(G({'Dnlm1', 'Dnlm2', 'Dnlm3', 'Dnlm4', 'Dnlm5', 'Dnlm6'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))};
Jinvt = tf(inv(nano_hexapod.J)');
Jinvt.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
Jinvt.OutputName = {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'};
Grz_pz_err(i) = {-minreal(G({'Ex', 'Ey', 'Ez', 'Erx', 'Ery', 'Erz'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))*Jinvt};
end
#+end_src
#+begin_src matlab :exports none
save('./mat/dynamics_variability_Rz.mat', 'Rz_amplitudes', ...
'Grz_vc_iff', 'Grz_vc_dvf', 'Grz_vc_err', ...
'Grz_pz_iff', 'Grz_pz_dvf', 'Grz_pz_err');
#+end_src
** Plots :ignore:
#+begin_src matlab :exports none
load('./mat/dynamics_variability_Rz.mat');
#+end_src
The following transfer functions are shown:
- Figure [[fig:dynamics_variability_iff_spindle_angle]]: From actuator forces to force sensors in each nano-hexapod's leg
- Figure [[fig:dynamics_variability_err_spindle_angle]]: From forces applied in the task space by the nano-hexapod to displacement of the sample in the X direction
#+begin_src matlab :exports none
freqs = logspace(-1, 2, 1000);
figure;
ax1 = subplot(2, 2, 1);
hold on;
for i = 1:length(Grz_vc_iff)
plot(freqs, abs(squeeze(freqresp(Grz_vc_iff{i}('Fnlm1', 'Fnl1'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [N/N]'); set(gca, 'XTickLabel',[]);
title('Soft Nano-Hexapod');
ax2 = subplot(2, 2, 3);
hold on;
for i = 1:length(Grz_vc_iff)
plot(freqs, 180/pi*angle(squeeze(freqresp(Grz_vc_iff{i}('Fnlm1', 'Fnl1'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$R_z = %.0f$ [deg]', Rz_amplitudes(i)*180/pi));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
freqs = logspace(0, 3, 1000);
ax1 = subplot(2, 2, 2);
hold on;
for i = 1:length(Grz_pz_iff)
plot(freqs, abs(squeeze(freqresp(Grz_pz_iff{i}('Fnlm1', 'Fnl1'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [N/N]'); set(gca, 'XTickLabel',[]);
title('Stiff Nano-Hexapod');
ax2 = subplot(2, 2, 4);
hold on;
for i = 1:length(Grz_pz_iff)
plot(freqs, 180/pi*angle(squeeze(freqresp(Grz_pz_iff{i}('Fnlm1', 'Fnl1'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$R_z = %.0f$ [deg]', Rz_amplitudes(i)*180/pi));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
#+end_src
#+HEADER: :tangle no :exports results :results none :noweb yes
#+begin_src matlab :var filepath="figs/dynamics_variability_iff_spindle_angle.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png")
<<plt-matlab>>
#+end_src
#+name: fig:dynamics_variability_iff_spindle_angle
#+caption: Variability of the dynamics from the actuator force to the force sensor with the Spindle Angle ([[./figs/dynamics_variability_iff_spindle_angle.png][png]], [[./figs/dynamics_variability_iff_spindle_angle.pdf][pdf]])
[[file:figs/dynamics_variability_iff_spindle_angle.png]]
#+begin_src matlab :exports none
freqs = logspace(-1, 3, 1000);
figure;
ax1 = subplot(2, 2, 1);
hold on;
for i = 1:length(Grz_vc_err)
plot(freqs, abs(squeeze(freqresp(Grz_vc_err{i}('Erx', 'Mx'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]);
title('Soft Nano-Hexapod');
ax2 = subplot(2, 2, 3);
hold on;
for i = 1:length(Grz_vc_err)
plot(freqs, 180/pi*angle(squeeze(freqresp(Grz_vc_err{i}('Erx', 'Mx'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$R_y = %.0f$ [deg]', Rz_amplitudes(i)*180/pi));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
freqs = logspace(0, 3, 1000);
ax1 = subplot(2, 2, 2);
hold on;
for i = 1:length(Grz_pz_err)
plot(freqs, abs(squeeze(freqresp(Grz_pz_err{i}('Erx', 'Mx'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]);
title('Stiff Nano-Hexapod');
ax2 = subplot(2, 2, 4);
hold on;
for i = 1:length(Grz_pz_err)
plot(freqs, 180/pi*angle(squeeze(freqresp(Grz_pz_err{i}('Erx', 'Mx'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$R_y = %.0f$ [deg]', Rz_amplitudes(i)*180/pi));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
#+end_src
#+HEADER: :tangle no :exports results :results none :noweb yes
#+begin_src matlab :var filepath="figs/dynamics_variability_err_spindle_angle.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png")
<<plt-matlab>>
#+end_src
#+name: fig:dynamics_variability_err_spindle_angle
#+caption: Variability of the dynamics from actuator force to absolute velocity with the Spindle Angle ([[./figs/dynamics_variability_err_spindle_angle.png][png]], [[./figs/dynamics_variability_err_spindle_angle.pdf][pdf]])
[[file:figs/dynamics_variability_err_spindle_angle.png]]
** Conclusion :ignore:
#+begin_important
The Spindle angle has no visible effect for the soft nano-hexapod.
It has little effect on the dynamics when a stiff nano-hexapod is used.
This is seem between 50Hz and 100Hz.
This is probably due to the fact that the micro-station compliance is not uniform in the X and Y directions.
#+end_important
* Variation of the Spindle Rotation Speed
<<sec:variability_rotation_speed>>
** Introduction :ignore:
** Initialization of gravity compensation forces
We initialize all the stages such that their joints are blocked and we record the total forces/torques applied in each of these joints.
#+begin_src matlab :exports none :noweb yes
<<init-gravity-comp>>
initializeLoggingConfiguration('log', 'all');
#+end_src
We set a payload mass of 10Kg.
#+begin_src matlab
initializeSample('type', 'init', 'mass', 10);
nano_hexapod = initializeNanoHexapod( 'type', 'init');
#+end_src
Finally, we simulate the system and same the forces/torques applied in each joint.
#+begin_src matlab :exports none
load('mat/conf_simulink.mat');
set_param(conf_simulink, 'StopTime', '0.1');
sim('nass_model');
#+end_src
#+begin_src matlab :exports none :results value replace
max(max(simout.Em.En.Data))
#+end_src
#+begin_src matlab :exports none
save('mat/Foffset.mat', 'Fgm', 'Ftym', 'Fym', 'Fzm', 'Fhm', 'Fnm', 'Fsm');
#+end_src
** Identification
We initialize the stages with forces/torques compensating the gravity forces.
#+begin_src matlab :exports none :noweb yes
<<init-sim-gravity-comp>>
initializeSample('mass', 10, 'Foffset', true);
#+end_src
We identify the dynamics for the following Spindle rotation periods.
#+begin_src matlab
Rz_periods = [60, 6, 2, 1]; % [s]
#+end_src
#+begin_src matlab :exports none
nano_hexapod = initializeNanoHexapod('actuator', 'lorentz', 'Foffset', true);
Gwz_vc_iff = {zeros(length(Rz_periods))};
Gwz_vc_dvf = {zeros(length(Rz_periods))};
Gwz_vc_err = {zeros(length(Rz_periods))};
for i = 1:length(Rz_periods)
initializeReferences('Rz_type', 'rotating', ...
'Rz_period', Rz_periods(i), ... % Rotation period [s]
'Rz_amplitude', -0.1*(2*pi/Rz_periods(i))); % Angle offset [rad]
load('mat/nass_references.mat', 'Rz'); % We load the reference for the Spindle
[~, i_end] = min(abs(Rz.signals.values)); % Obtain the indice where the spindle angle is zero
t_sim = Rz.time(i_end); % Simulation time before identification [s]
%% Run the linearization
G = linearize(mdl, io, t_sim);
G.InputName = {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'};
G.OutputName = {'Dnlm1', 'Dnlm2', 'Dnlm3', 'Dnlm4', 'Dnlm5', 'Dnlm6', ...
'Fnlm1', 'Fnlm2', 'Fnlm3', 'Fnlm4', 'Fnlm5', 'Fnlm6', ...
'Ex', 'Ey', 'Ez', 'Erx', 'Ery', 'Erz'};
Gwz_vc_iff(i) = {minreal(G({'Fnlm1', 'Fnlm2', 'Fnlm3', 'Fnlm4', 'Fnlm5', 'Fnlm6'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))};
Gwz_vc_dvf(i) = {minreal(G({'Dnlm1', 'Dnlm2', 'Dnlm3', 'Dnlm4', 'Dnlm5', 'Dnlm6'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))};
Jinvt = tf(inv(nano_hexapod.J)');
Jinvt.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
Jinvt.OutputName = {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'};
Gwz_vc_err(i) = {-minreal(G({'Ex', 'Ey', 'Ez', 'Erx', 'Ery', 'Erz'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))*Jinvt};
end
#+end_src
#+begin_src matlab :exports none
nano_hexapod = initializeNanoHexapod('actuator', 'piezo', 'Foffset', true);
Gwz_pz_iff = {zeros(length(Rz_periods))};
Gwz_pz_dvf = {zeros(length(Rz_periods))};
Gwz_pz_err = {zeros(length(Rz_periods))};
for i = 1:length(Rz_periods)
initializeReferences('Rz_type', 'rotating', ...
'Rz_period', Rz_periods(i), ... % Rotation period [s]
'Rz_amplitude', -0.1*(2*pi/Rz_periods(i))); % Angle offset [rad]
load('mat/nass_references.mat', 'Rz'); % We load the reference for the Spindle
[~, i_end] = min(abs(Rz.signals.values)); % Obtain the indice where the spindle angle is zero
t_sim = Rz.time(i_end); % Simulation time before identification [s]
%% Run the linearization
G = linearize(mdl, io, t_sim);
G.InputName = {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'};
G.OutputName = {'Dnlm1', 'Dnlm2', 'Dnlm3', 'Dnlm4', 'Dnlm5', 'Dnlm6', ...
'Fnlm1', 'Fnlm2', 'Fnlm3', 'Fnlm4', 'Fnlm5', 'Fnlm6', ...
'Ex', 'Ey', 'Ez', 'Erx', 'Ery', 'Erz'};
Gwz_pz_iff(i) = {minreal(G({'Fnlm1', 'Fnlm2', 'Fnlm3', 'Fnlm4', 'Fnlm5', 'Fnlm6'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))};
Gwz_pz_dvf(i) = {minreal(G({'Dnlm1', 'Dnlm2', 'Dnlm3', 'Dnlm4', 'Dnlm5', 'Dnlm6'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))};
Jinvt = tf(inv(nano_hexapod.J)');
Jinvt.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
Jinvt.OutputName = {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'};
Gwz_pz_err(i) = {-minreal(G({'Ex', 'Ey', 'Ez', 'Erx', 'Ery', 'Erz'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))*Jinvt};
end
#+end_src
#+begin_src matlab :exports none
save('./mat/dynamics_variability_Wz.mat', 'Rz_periods', ...
'Gwz_vc_iff', 'Gwz_vc_dvf', 'Gwz_vc_err', ...
'Gwz_pz_iff', 'Gwz_pz_dvf', 'Gwz_pz_err');
#+end_src
** Plots
#+begin_src matlab :exports none
load('./mat/dynamics_variability_Wz.mat', 'Rz_periods', ...
'Gwz_vc_iff', 'Gwz_vc_dvf', 'Gwz_vc_err', ...
'Gwz_pz_iff', 'Gwz_pz_dvf', 'Gwz_pz_err');
#+end_src
The following transfer functions are shown:
- Figure [[fig:dynamics_variability_iff_spindle_speed]]: From actuator forces to force sensors in each nano-hexapod's leg
- Figure [[fig:dynamics_variability_dvf_spindle_speed]]: From actuator forces to relative displacement of each nano-hexapod's leg
- Figure [[fig:dynamics_variability_err_spindle_speed]]: From forces applied in the task space by the nano-hexapod to displacement of the sample in the X direction
- Figure [[fig:dynamics_variability_err_spindle_speed_coupling]]: From forces applied in the task space in the X direction by the nano-hexapod to displacement of the sample in the Y direction (coupling)
#+begin_src matlab :exports none
freqs = logspace(-1, 3, 1000);
figure;
ax1 = subplot(2, 2, 1);
hold on;
for i = 1:length(Gwz_vc_iff)
plot(freqs, abs(squeeze(freqresp(Gwz_vc_iff{i}('Fnlm1', 'Fnl1'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [N/N]'); set(gca, 'XTickLabel',[]);
title('Soft Nano-Hexapod');
ax2 = subplot(2, 2, 3);
hold on;
for i = 1:length(Gwz_vc_iff)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gwz_vc_iff{i}('Fnlm1', 'Fnl1'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$\\omega_z = %.0f$ [rpm]', 60/Rz_periods(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
freqs = logspace(0, 3, 1000);
ax1 = subplot(2, 2, 2);
hold on;
for i = 1:length(Gwz_pz_iff)
plot(freqs, abs(squeeze(freqresp(Gwz_pz_iff{i}('Fnlm1', 'Fnl1'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [N/N]'); set(gca, 'XTickLabel',[]);
title('Stiff Nano-Hexapod');
ax2 = subplot(2, 2, 4);
hold on;
for i = 1:length(Gwz_pz_iff)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gwz_pz_iff{i}('Fnlm1', 'Fnl1'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$\\omega_z = %.0f$ [rpm]', 60/Rz_periods(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
#+end_src
#+HEADER: :tangle no :exports results :results none :noweb yes
#+begin_src matlab :var filepath="figs/dynamics_variability_iff_spindle_speed.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png")
<<plt-matlab>>
#+end_src
#+name: fig:dynamics_variability_iff_spindle_speed
#+caption: Variability of the dynamics from the actuator force to the force sensor with the Spindle rotation speed ([[./figs/dynamics_variability_iff_spindle_speed.png][png]], [[./figs/dynamics_variability_iff_spindle_speed.pdf][pdf]])
[[file:figs/dynamics_variability_iff_spindle_speed.png]]
#+begin_src matlab :exports none
freqs = logspace(-1, 3, 1000);
figure;
ax1 = subplot(2, 2, 1);
hold on;
for i = 1:length(Gwz_vc_dvf)
plot(freqs, abs(squeeze(freqresp(Gwz_vc_dvf{i}('Dnlm1', 'Fnl1'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]);
title('Soft Nano-Hexapod');
ax2 = subplot(2, 2, 3);
hold on;
for i = 1:length(Gwz_vc_dvf)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gwz_vc_dvf{i}('Dnlm1', 'Fnl1'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$\\omega_z = %.0f$ [rpm]', 60/Rz_periods(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
freqs = logspace(0, 3, 1000);
ax1 = subplot(2, 2, 2);
hold on;
for i = 1:length(Gwz_pz_dvf)
plot(freqs, abs(squeeze(freqresp(Gwz_pz_dvf{i}('Dnlm1', 'Fnl1'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]);
title('Stiff Nano-Hexapod');
ax2 = subplot(2, 2, 4);
hold on;
for i = 1:length(Gwz_pz_dvf)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gwz_pz_dvf{i}('Dnlm1', 'Fnl1'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$\\omega_z = %.0f$ [rpm]', 60/Rz_periods(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
#+end_src
#+HEADER: :tangle no :exports results :results none :noweb yes
#+begin_src matlab :var filepath="figs/dynamics_variability_dvf_spindle_speed.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png")
<<plt-matlab>>
#+end_src
#+name: fig:dynamics_variability_dvf_spindle_speed
#+caption: Variability of the dynamics from the actuator force to the relative motion sensor with the Spindle rotation speed ([[./figs/dynamics_variability_dvf_spindle_speed.png][png]], [[./figs/dynamics_variability_dvf_spindle_speed.pdf][pdf]])
[[file:figs/dynamics_variability_dvf_spindle_speed.png]]
#+begin_src matlab :exports none
freqs = logspace(-1, 3, 1000);
figure;
ax1 = subplot(2, 2, 1);
hold on;
for i = 1:length(Gwz_vc_err)
plot(freqs, abs(squeeze(freqresp(Gwz_vc_err{i}('Ex', 'Fx'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]);
title('Soft Nano-Hexapod');
ax2 = subplot(2, 2, 3);
hold on;
for i = 1:length(Gwz_vc_err)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gwz_vc_err{i}('Ex', 'Fx'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$\\omega_z = %.0f$ [rpm]', 60/Rz_periods(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
freqs = logspace(0, 3, 1000);
ax1 = subplot(2, 2, 2);
hold on;
for i = 1:length(Gwz_pz_err)
plot(freqs, abs(squeeze(freqresp(Gwz_pz_err{i}('Ex', 'Fx'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]);
title('Stiff Nano-Hexapod');
ax2 = subplot(2, 2, 4);
hold on;
for i = 1:length(Gwz_pz_err)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gwz_pz_err{i}('Ex', 'Fx'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$\\omega_z = %.0f$ [rpm]', 60/Rz_periods(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
#+end_src
#+HEADER: :tangle no :exports results :results none :noweb yes
#+begin_src matlab :var filepath="figs/dynamics_variability_err_spindle_speed.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png")
<<plt-matlab>>
#+end_src
#+name: fig:dynamics_variability_err_spindle_speed
#+caption: Variability of the dynamics from the actuator force in the task force to the position error of the sample ([[./figs/dynamics_variability_err_spindle_speed.png][png]], [[./figs/dynamics_variability_err_spindle_speed.pdf][pdf]])
[[file:figs/dynamics_variability_err_spindle_speed.png]]
#+begin_src matlab :exports none
freqs = logspace(-1, 3, 1000);
figure;
ax1 = subplot(1, 2, 1);
hold on;
plot(freqs, abs(squeeze(freqresp(Gwz_vc_err{1}('Ey', 'Fy'), freqs, 'Hz'))), 'k-', 'DisplayName', '$\frac{E_y}{F_y}$');
for i = 1:length(Gwz_vc_err)
plot(freqs, abs(squeeze(freqresp(Gwz_vc_err{i}('Ex', 'Fy'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$\\frac{E_x}{F_y}, \\omega_z = %.0f$ [rpm]', 60/Rz_periods(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
xlabel('Frequency [Hz]'); ylabel('Amplitude [m/N]');
legend('location', 'southwest');
title('Soft Nano-Hexapod');
xlim([freqs(1), freqs(end)]);
freqs = logspace(0, 3, 1000);
ax2 = subplot(1, 2, 2);
hold on;
plot(freqs, abs(squeeze(freqresp(Gwz_pz_err{1}('Ey', 'Fy'), freqs, 'Hz'))), 'k-', 'DisplayName', '$\frac{E_y}{F_y}$');
for i = 1:length(Gwz_pz_err)
plot(freqs, abs(squeeze(freqresp(Gwz_pz_err{i}('Ex', 'Fy'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$\\frac{E_x}{F_y}, \\omega_z = %.0f$ [rpm]', 60/Rz_periods(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
xlabel('Frequency [Hz]'); ylabel('Amplitude [m/N]');
legend('location', 'southwest');
title('Stiff Nano-Hexapod');
xlim([freqs(1), freqs(end)]);
#+end_src
#+HEADER: :tangle no :exports results :results none :noweb yes
#+begin_src matlab :var filepath="figs/dynamics_variability_err_spindle_speed_coupling.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png")
<<plt-matlab>>
#+end_src
#+name: fig:dynamics_variability_err_spindle_speed_coupling
#+caption: Variability of the coupling from the actuator force in the task force to the position error of the sample ([[./figs/dynamics_variability_err_spindle_speed_coupling.png][png]], [[./figs/dynamics_variability_err_spindle_speed_coupling.pdf][pdf]])
[[file:figs/dynamics_variability_err_spindle_speed_coupling.png]]
** Conclusion :ignore:
#+begin_important
For the stiff nano-hexapod, the rotation speed of the Spindle does not affect the (main) dynamics.
It only affects the coupling due to Coriolis forces.
For the soft nano-hexapod, it greatly affects the obtained dynamics around the main resonance which corresponds to the payload vibrating on top of the nano-hexapod.
This effect is similar to the one described in rotating machinery, the c.c. poles is separated into two sets of c.c. poles, one going to decreasing frequencies while the other going to positive frequencies.
This effect is due to centrifugal forces that can be modeled as negative stiffness.
At some point, one of the pair of c.c. pole becomes unstable.
Also, the coupling from forces applied in the X direction to induced displacement in the Y direction becomes very high when the rotating speed is increased.
#+end_important
* Variation of the Tilt Angle
<<sec:variability_tilt_angle>>
** Introduction :ignore:
** Identification :ignore:
We initialize all the stages with the default parameters.
#+begin_src matlab :exports none :noweb yes
<<init-sim>>
<<init-identification>>
#+end_src
We identify the dynamics for the following Tilt stage angles.
#+begin_src matlab
initializeSample('mass', 50);
Ry_amplitudes = [-3*pi/180 0 3*pi/180]; % [rad]
#+end_src
#+begin_src matlab :exports none
nano_hexapod = initializeNanoHexapod('actuator', 'lorentz');
Gry_vc_iff = {zeros(length(Ry_amplitudes))};
Gry_vc_dvf = {zeros(length(Ry_amplitudes))};
Gry_vc_err = {zeros(length(Ry_amplitudes))};
for i = 1:length(Ry_amplitudes)
initializeReferences('Ry_type', 'constant', 'Ry_amplitude', Ry_amplitudes(i))
%% Run the linearization
G = linearize(mdl, io, 1e-3);
G.InputName = {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'};
G.OutputName = {'Dnlm1', 'Dnlm2', 'Dnlm3', 'Dnlm4', 'Dnlm5', 'Dnlm6', ...
'Fnlm1', 'Fnlm2', 'Fnlm3', 'Fnlm4', 'Fnlm5', 'Fnlm6', ...
'Ex', 'Ey', 'Ez', 'Erx', 'Ery', 'Erz'};
Gry_vc_iff(i) = {minreal(G({'Fnlm1', 'Fnlm2', 'Fnlm3', 'Fnlm4', 'Fnlm5', 'Fnlm6'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))};
Gry_vc_dvf(i) = {minreal(G({'Dnlm1', 'Dnlm2', 'Dnlm3', 'Dnlm4', 'Dnlm5', 'Dnlm6'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))};
Jinvt = tf(inv(nano_hexapod.J)');
Jinvt.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
Jinvt.OutputName = {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'};
Gry_vc_err(i) = {-minreal(G({'Ex', 'Ey', 'Ez', 'Erx', 'Ery', 'Erz'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))*Jinvt};
end
#+end_src
#+begin_src matlab :exports none
nano_hexapod = initializeNanoHexapod('actuator', 'piezo', 'Foffset', true);
Gry_pz_iff = {zeros(length(Ry_amplitudes))};
Gry_pz_dvf = {zeros(length(Ry_amplitudes))};
Gry_pz_err = {zeros(length(Ry_amplitudes))};
for i = 1:length(Ry_amplitudes)
initializeReferences('Ry_type', 'constant', 'Ry_amplitude', Ry_amplitudes(i))
%% Run the linearization
G = linearize(mdl, io, 1e-3);
G.InputName = {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'};
G.OutputName = {'Dnlm1', 'Dnlm2', 'Dnlm3', 'Dnlm4', 'Dnlm5', 'Dnlm6', ...
'Fnlm1', 'Fnlm2', 'Fnlm3', 'Fnlm4', 'Fnlm5', 'Fnlm6', ...
'Ex', 'Ey', 'Ez', 'Erx', 'Ery', 'Erz'};
Gry_pz_iff(i) = {minreal(G({'Fnlm1', 'Fnlm2', 'Fnlm3', 'Fnlm4', 'Fnlm5', 'Fnlm6'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))};
Gry_pz_dvf(i) = {minreal(G({'Dnlm1', 'Dnlm2', 'Dnlm3', 'Dnlm4', 'Dnlm5', 'Dnlm6'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))};
Jinvt = tf(inv(nano_hexapod.J)');
Jinvt.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
Jinvt.OutputName = {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'};
Gry_pz_err(i) = {-minreal(G({'Ex', 'Ey', 'Ez', 'Erx', 'Ery', 'Erz'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))*Jinvt};
end
#+end_src
#+begin_src matlab :exports none
save('./mat/dynamics_variability_Ry.mat', 'Ry_amplitudes', ...
'Gry_vc_iff', 'Gry_vc_dvf', 'Gry_vc_err', ...
'Gry_pz_iff', 'Gry_pz_dvf', 'Gry_pz_err');
#+end_src
** Plots :ignore:
#+begin_src matlab :exports none
load('./mat/dynamics_variability_Ry.mat');
#+end_src
The following transfer functions are shown:
- Figure [[fig:dynamics_variability_iff_tilt_angle]]: From actuator forces to force sensors in each nano-hexapod's leg
- Figure [[fig:dynamics_variability_err_tilt_angle]]: From forces applied in the task space by the nano-hexapod to displacement of the sample in the X direction
#+begin_src matlab :exports none
freqs = logspace(-1, 2, 1000);
figure;
ax1 = subplot(2, 2, 1);
hold on;
for i = 1:length(Gry_vc_iff)
plot(freqs, abs(squeeze(freqresp(Gry_vc_iff{i}('Fnlm1', 'Fnl1'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [N/N]'); set(gca, 'XTickLabel',[]);
title('Soft Nano-Hexapod');
ax2 = subplot(2, 2, 3);
hold on;
for i = 1:length(Gry_vc_iff)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gry_vc_iff{i}('Fnlm1', 'Fnl1'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$R_y = %.0f$ [deg]', Ry_amplitudes(i)*180/pi));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
freqs = logspace(0, 3, 1000);
ax1 = subplot(2, 2, 2);
hold on;
for i = 1:length(Gry_pz_iff)
plot(freqs, abs(squeeze(freqresp(Gry_pz_iff{i}('Fnlm1', 'Fnl1'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [N/N]'); set(gca, 'XTickLabel',[]);
title('Stiff Nano-Hexapod');
ax2 = subplot(2, 2, 4);
hold on;
for i = 1:length(Gry_pz_iff)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gry_pz_iff{i}('Fnlm1', 'Fnl1'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$R_y = %.0f$ [deg]', Ry_amplitudes(i)*180/pi));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
#+end_src
#+HEADER: :tangle no :exports results :results none :noweb yes
#+begin_src matlab :var filepath="figs/dynamics_variability_iff_tilt_angle.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png")
<<plt-matlab>>
#+end_src
#+name: fig:dynamics_variability_iff_tilt_angle
#+caption: Variability of the dynamics from the actuator force to the force sensor with the Tilt stage Angle ([[./figs/dynamics_variability_iff_tilt_angle.png][png]], [[./figs/dynamics_variability_iff_tilt_angle.pdf][pdf]])
[[file:figs/dynamics_variability_iff_tilt_angle.png]]
#+begin_src matlab :exports none
freqs = logspace(-1, 3, 1000);
figure;
ax1 = subplot(2, 2, 1);
hold on;
for i = 1:length(Gry_vc_err)
plot(freqs, abs(squeeze(freqresp(Gry_vc_err{i}('Erx', 'Mx'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]);
title('Soft Nano-Hexapod');
ax2 = subplot(2, 2, 3);
hold on;
for i = 1:length(Gry_vc_err)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gry_vc_err{i}('Erx', 'Mx'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$R_y = %.0f$ [deg]', Ry_amplitudes(i)*180/pi));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
freqs = logspace(0, 3, 1000);
ax1 = subplot(2, 2, 2);
hold on;
for i = 1:length(Gry_pz_err)
plot(freqs, abs(squeeze(freqresp(Gry_pz_err{i}('Erx', 'Mx'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]);
title('Stiff Nano-Hexapod');
ax2 = subplot(2, 2, 4);
hold on;
for i = 1:length(Gry_pz_err)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gry_pz_err{i}('Erx', 'Mx'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$R_y = %.0f$ [deg]', Ry_amplitudes(i)*180/pi));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
#+end_src
#+HEADER: :tangle no :exports results :results none :noweb yes
#+begin_src matlab :var filepath="figs/dynamics_variability_err_tilt_angle.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png")
<<plt-matlab>>
#+end_src
#+name: fig:dynamics_variability_err_tilt_angle
#+caption: Variability of the dynamics from the actuator force in the task space to the displacement of the sample ([[./figs/dynamics_variability_err_tilt_angle.png][png]], [[./figs/dynamics_variability_err_tilt_angle.pdf][pdf]])
[[file:figs/dynamics_variability_err_tilt_angle.png]]
** Conclusion :ignore:
#+begin_important
The tilt angle has no visible effect on the dynamics.
#+end_important
* Variation of the micro-hexapod pose
<<sec:micro_hexapod_pose>>
** Introduction :ignore:
** Identification :ignore:
We initialize all the stages with the default parameters.
#+begin_src matlab :exports none :noweb yes
<<init-sim>>
<<init-identification>>
initializeSample('mass', 1);
#+end_src
We identify the dynamics for the following translations of the micro-hexapod in the X direction.
#+begin_src matlab
Tx_amplitudes = [0, 5e-3, 10e-3]; % [m]
#+end_src
#+begin_src matlab :exports none
nano_hexapod = initializeNanoHexapod('actuator', 'lorentz');
Gry_vc_iff = {zeros(length(Tx_amplitudes))};
Gry_vc_dvf = {zeros(length(Tx_amplitudes))};
Gry_vc_err = {zeros(length(Tx_amplitudes))};
for i = 1:length(Tx_amplitudes)
initializeMicroHexapod('AP', [Tx_amplitudes(i) 0 0]);
initializeReferences('Dh_type', 'constant', 'Dh_pos', [Tx_amplitudes(i) 0 0 0 0 0])
%% Run the linearization
G = linearize(mdl, io, 1e-3);
G.InputName = {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'};
G.OutputName = {'Dnlm1', 'Dnlm2', 'Dnlm3', 'Dnlm4', 'Dnlm5', 'Dnlm6', ...
'Fnlm1', 'Fnlm2', 'Fnlm3', 'Fnlm4', 'Fnlm5', 'Fnlm6', ...
'Ex', 'Ey', 'Ez', 'Erx', 'Ery', 'Erz'};
Gtx_vc_iff(i) = {minreal(G({'Fnlm1', 'Fnlm2', 'Fnlm3', 'Fnlm4', 'Fnlm5', 'Fnlm6'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))};
Gtx_vc_dvf(i) = {minreal(G({'Dnlm1', 'Dnlm2', 'Dnlm3', 'Dnlm4', 'Dnlm5', 'Dnlm6'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))};
Jinvt = tf(inv(nano_hexapod.J)');
Jinvt.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
Jinvt.OutputName = {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'};
Gtx_vc_err(i) = {-minreal(G({'Ex', 'Ey', 'Ez', 'Erx', 'Ery', 'Erz'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))*Jinvt};
end
#+end_src
#+begin_src matlab :exports none
nano_hexapod = initializeNanoHexapod('actuator', 'piezo');
Gtx_pz_iff = {zeros(length(Tx_amplitudes))};
Gtx_pz_dvf = {zeros(length(Tx_amplitudes))};
Gtx_pz_err = {zeros(length(Tx_amplitudes))};
for i = 1:length(Tx_amplitudes)
initializeMicroHexapod('AP', [Tx_amplitudes(i) 0 0]);
initializeReferences('Dh_type', 'constant', 'Dh_pos', [Tx_amplitudes(i) 0 0 0 0 0])
%% Run the linearization
G = linearize(mdl, io, 1e-3);
G.InputName = {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'};
G.OutputName = {'Dnlm1', 'Dnlm2', 'Dnlm3', 'Dnlm4', 'Dnlm5', 'Dnlm6', ...
'Fnlm1', 'Fnlm2', 'Fnlm3', 'Fnlm4', 'Fnlm5', 'Fnlm6', ...
'Ex', 'Ey', 'Ez', 'Erx', 'Ery', 'Erz'};
Gtx_pz_iff(i) = {minreal(G({'Fnlm1', 'Fnlm2', 'Fnlm3', 'Fnlm4', 'Fnlm5', 'Fnlm6'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))};
Gtx_pz_dvf(i) = {minreal(G({'Dnlm1', 'Dnlm2', 'Dnlm3', 'Dnlm4', 'Dnlm5', 'Dnlm6'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))};
Jinvt = tf(inv(nano_hexapod.J)');
Jinvt.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};
Jinvt.OutputName = {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'};
Gtx_pz_err(i) = {-minreal(G({'Ex', 'Ey', 'Ez', 'Erx', 'Ery', 'Erz'}, {'Fnl1', 'Fnl2', 'Fnl3', 'Fnl4', 'Fnl5', 'Fnl6'}))*Jinvt};
end
#+end_src
#+begin_src matlab :exports none
save('./mat/dynamics_variability_Tx.mat', 'Tx_amplitudes', ...
'Gtx_vc_iff', 'Gtx_vc_dvf', 'Gtx_vc_err', ...
'Gtx_pz_iff', 'Gtx_pz_dvf', 'Gtx_pz_err');
#+end_src
** Plots :ignore:
#+begin_src matlab :exports none
load('./mat/dynamics_variability_Tx.mat');
#+end_src
#+begin_src matlab :exports none
freqs = logspace(-1, 2, 1000);
figure;
ax1 = subplot(2, 2, 1);
hold on;
for i = 1:length(Gtx_vc_iff)
plot(freqs, abs(squeeze(freqresp(Gtx_vc_iff{i}('Fnlm1', 'Fnl1'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [N/N]'); set(gca, 'XTickLabel',[]);
title('Soft Nano-Hexapod');
ax2 = subplot(2, 2, 3);
hold on;
for i = 1:length(Gtx_vc_iff)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gtx_vc_iff{i}('Fnlm1', 'Fnl1'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$T_x = %.0f$ [m]', 1e3*Tx_amplitudes(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
freqs = logspace(0, 3, 1000);
ax1 = subplot(2, 2, 2);
hold on;
for i = 1:length(Gtx_pz_iff)
plot(freqs, abs(squeeze(freqresp(Gtx_pz_iff{i}('Fnlm1', 'Fnl1'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [N/N]'); set(gca, 'XTickLabel',[]);
title('Stiff Nano-Hexapod');
ax2 = subplot(2, 2, 4);
hold on;
for i = 1:length(Gtx_pz_iff)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gtx_pz_iff{i}('Fnlm1', 'Fnl1'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$T_x = %.0f$ [m]', 1e3*Tx_amplitudes(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
#+end_src
#+HEADER: :tangle no :exports results :results none :noweb yes
#+begin_src matlab :var filepath="figs/dynamics_variability_iff_micro_hexapod_x.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png")
<<plt-matlab>>
#+end_src
#+name: fig:dynamics_variability_iff_micro_hexapod_x
#+caption: Variability of the dynamics from the actuator force to the force sensor with the Tilt stage Angle ([[./figs/dynamics_variability_iff_micro_hexapod_x.png][png]], [[./figs/dynamics_variability_iff_micro_hexapod_x.pdf][pdf]])
[[file:figs/dynamics_variability_iff_micro_hexapod_x.png]]
#+begin_src matlab :exports none
freqs = logspace(-1, 3, 1000);
figure;
ax1 = subplot(2, 2, 1);
hold on;
for i = 1:length(Gtx_vc_err)
plot(freqs, abs(squeeze(freqresp(Gtx_vc_err{i}('Erx', 'Mx'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]);
title('Soft Nano-Hexapod');
ax2 = subplot(2, 2, 3);
hold on;
for i = 1:length(Gtx_vc_err)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gtx_vc_err{i}('Erx', 'Mx'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$T_x = %.0f$ [m]', 1e3*Tx_amplitudes(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
freqs = logspace(0, 3, 1000);
ax1 = subplot(2, 2, 2);
hold on;
for i = 1:length(Gtx_pz_err)
plot(freqs, abs(squeeze(freqresp(Gtx_pz_err{i}('Erx', 'Mx'), freqs, 'Hz'))));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]);
title('Stiff Nano-Hexapod');
ax2 = subplot(2, 2, 4);
hold on;
for i = 1:length(Gtx_pz_err)
plot(freqs, 180/pi*angle(squeeze(freqresp(Gtx_pz_err{i}('Erx', 'Mx'), freqs, 'Hz'))), ...
'DisplayName', sprintf('$T_x = %.0f$ [m]', 1e3*Tx_amplitudes(i)));
end
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
ylabel('Phase [deg]'); xlabel('Frequency [Hz]');
ylim([-180, 180]);
yticks([-180, -90, 0, 90, 180]);
legend('location', 'northeast');
linkaxes([ax1,ax2],'x');
xlim([freqs(1), freqs(end)]);
#+end_src
#+HEADER: :tangle no :exports results :results none :noweb yes
#+begin_src matlab :var filepath="figs/dynamics_variability_err_micro_hexapod_x.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png")
<<plt-matlab>>
#+end_src
#+name: fig:dynamics_variability_err_micro_hexapod_x
#+caption: Variability of the dynamics from the actuator force in the task space to the displacement of the sample ([[./figs/dynamics_variability_err_micro_hexapod_x.png][png]], [[./figs/dynamics_variability_err_micro_hexapod_x.pdf][pdf]])
[[file:figs/dynamics_variability_err_micro_hexapod_x.png]]
** Conclusion :ignore:
#+begin_important
The pose of the micro-hexapod has negligible effect on the dynamics.
#+end_important
* Conclusion
<<sec:conclusion>>
#+begin_important
From all the experimental condition studied, the only ones that have significant effect on the dynamics are:
- the *sample mass*
- the *resonance frequency of the sample*
- the *rotation speed* of the spindle
| | Soft | Stiff |
|------------------+-------------------------------------------------+-------------------------|
| Sample Mass | Localized effect on the resonance of the sample | Effect on all the modes |
| Sample Resonance | Localized effect at the resonance of the sample | Effect on all the modes |
| Rotation Speed | Greatly influences the dynamics and coupling | No effect |
#+end_important
* Useful Blocks :noexport:
** Initialize Simulation
#+name: init-sim
#+begin_src matlab
initializeGround();
initializeGranite();
initializeTy();
initializeRy();
initializeRz();
initializeMicroHexapod();
initializeAxisc();
initializeMirror();
initializeReferences();
initializeDisturbances();
initializeController();
initializeSimscapeConfiguration('gravity', true);
initializeLoggingConfiguration('log', 'none');
#+end_src
** Initialize Simulation with Gravity Compensation
#+name: init-sim-gravity-comp
#+begin_src matlab
initializeGround();
initializeGranite('Foffset', true);
initializeTy('Foffset', true);
initializeRy('Foffset', true);
initializeRz('Foffset', true);
initializeMicroHexapod('Foffset', true);
initializeAxisc();
initializeMirror();
initializeReferences();
initializeDisturbances();
initializeController();
initializeSimscapeConfiguration('gravity', true);
initializeLoggingConfiguration('log', 'none');
#+end_src
** Initialize Simulation with Gravity Compensation
#+name: init-gravity-comp
#+begin_src matlab
initializeGround();
initializeGranite('type', 'init');
initializeTy('type', 'init');
initializeRy('type', 'init');
initializeRz('type', 'init');
initializeMicroHexapod('type', 'init');
initializeAxisc();
initializeMirror();
initializeReferences();
initializeDisturbances();
initializeController();
initializeSimscapeConfiguration('gravity', true);
initializeLoggingConfiguration('log', 'none');
#+end_src
** Initialize Identification
#+name: init-identification
#+begin_src matlab
%% Name of the Simulink File
mdl = 'nass_model';
%% Input/Output definition
clear io; io_i = 1;
io(io_i) = linio([mdl, '/Controller'], 1, 'openinput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Micro-Station'], 3, 'openoutput', [], 'Dnlm'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Micro-Station'], 3, 'openoutput', [], 'Fnlm'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/Tracking Error'], 1, 'output', [], 'En'); io_i = io_i + 1;
#+end_src