Compare commits

..

6 Commits

39 changed files with 4899 additions and 911 deletions

18
figs/inkscape/convert_svg.sh Executable file
View File

@@ -0,0 +1,18 @@
#!/bin/bash
# Directory containing SVG files
INPUT_DIR="."
# Loop through all SVG files in the directory
for svg_file in "$INPUT_DIR"/*.svg; do
# Check if there are SVG files in the directory
if [ -f "$svg_file" ]; then
# Output PDF file name
pdf_file="../${svg_file%.svg}.pdf"
png_file="../${svg_file%.svg}"
# Convert SVG to PDF using Inkscape
inkscape "$svg_file" --export-filename="$pdf_file" && \
pdftocairo -png -singlefile -cropbox "$pdf_file" "$png_file"
fi
done

File diff suppressed because it is too large Load Diff

After

Width:  |  Height:  |  Size: 180 KiB

View File

Before

Width:  |  Height:  |  Size: 20 MiB

After

Width:  |  Height:  |  Size: 20 MiB

View File

Before

Width:  |  Height:  |  Size: 76 KiB

After

Width:  |  Height:  |  Size: 76 KiB

Binary file not shown.

Binary file not shown.

After

Width:  |  Height:  |  Size: 27 KiB

File diff suppressed because it is too large Load Diff

Binary file not shown.

After

Width:  |  Height:  |  Size: 70 KiB

Binary file not shown.

Binary file not shown.

After

Width:  |  Height:  |  Size: 55 KiB

Binary file not shown.

Binary file not shown.

After

Width:  |  Height:  |  Size: 55 KiB

Binary file not shown.

Binary file not shown.

After

Width:  |  Height:  |  Size: 58 KiB

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

View File

@@ -1,102 +1,61 @@
function [cntrs,tp] = h5scan(pth,smp,ds,sn,varargin) % function [cntrs,tp] = h5scan(pth,smp,ds,sn,varargin)
function [cntrs,tp] = h5scan(ds,sn)
if ~isstr(ds), ds = sprintf('%.4d',ds); end;
i = cellfun(@(x) isa(x,'detector'),varargin); f = sprintf('%s.h5',ds);
if any(i), det = varargin{i}; varargin = varargin(~i); else, det = []; end; h = h5info(f,sprintf('/%d.1/measurement',sn));
if ~isstr(ds), ds = sprintf('%.4d',ds); end; fid = H5F.open(f);
for i = 1:length(h.Links)
f = sprintf('%s/%s/%s_%s/%s_%s.h5',pth,smp,smp,ds,smp,ds);
h = h5info(f,sprintf('/%d.1/measurement',sn));
fid = H5F.open(f);
for i = 1:length(h.Links),
nm = h.Links(i).Name; nm = h.Links(i).Name;
try, try
id = H5D.open(fid,h.Links(i).Value{1}); id = H5D.open(fid,h.Links(i).Value{1});
cntrs.(nm) = H5D.read(id); cntrs.(nm) = H5D.read(id);
H5D.close(id); H5D.close(id);
if ~isempty(det) & strcmp(nm,det.name), cntrs.(nm) = integrate(det,double(cntrs.(nm))); end; if ~isempty(det) & strcmp(nm,det.name), cntrs.(nm) = integrate(det,double(cntrs.(nm))); end;
catch, end
warning('solving problem with %s\n',nm);
cntrs.(nm) = vrtlds(sprintf('%s/%s/%s_%s/scan%.4d/',pth,smp,smp,ds,sn),nm,det);
end;
[~,tp.(nm)] = fileparts(h.Links(i).Value{1}); [~,tp.(nm)] = fileparts(h.Links(i).Value{1});
end; end
try, try
h = h5info(f,sprintf('/%d.2/measurement',sn)); h = h5info(f,sprintf('/%d.2/measurement',sn));
catch, catch
h = []; h = [];
end; end
if ~isempty(h), if ~isempty(h)
for i = 1:length(h.Links), for i = 1:length(h.Links)
nm = h.Links(i).Name; nm = h.Links(i).Name;
try, try
id = H5D.open(fid,h.Links(i).Value{1}); id = H5D.open(fid,h.Links(i).Value{1});
cntrs.part2.(nm) = H5D.read(id); cntrs.part2.(nm) = H5D.read(id);
H5D.close(id); H5D.close(id);
catch, end
warning('solving problem with %s\n',nm);
cntrs.part2.(nm) = vrtlds(sprintf('%s/%s/%s_%s/scan%.4d/',pth,smp,smp,ds,sn),nm,det);
end;
[~,tp.part2.(nm)] = fileparts(h.Links(i).Value{1}); [~,tp.part2.(nm)] = fileparts(h.Links(i).Value{1});
end; end
end; end
if length(varargin),
fn = sprintf('/%d.1/instrument/positioners/',sn);
h = h5info(f,fn);
[~,k,m] = intersect({h.Datasets.Name},varargin,'stable');
h.Datasets = h.Datasets(k);
for i = 1:length(h.Datasets),
id = H5D.open(fid,[fn h.Datasets(i).Name]);
cntrs.(h.Datasets(i).Name) = H5D.read(id);
H5D.close(id);
end;
end;
H5F.close(fid); H5F.close(fid);
%%%%%%%%%%%%%%%%%%%%%%%%%% %%%%%%%%%%%%%%%%%%%%%%%%%%
function A = vrtlds(f,nm,det) function A = vrtlds(f,nm,det)
%try,
n = 0; A = []; n = 0; A = [];
fn = sprintf('%s/%s_%.4d.h5',f,nm,n); fn = sprintf('%s/%s_%.4d.h5',f,nm,n);
while exist(fn) == 2,
while exist(fn) == 2
fid = H5F.open(fn); n = n+1; fid = H5F.open(fn); n = n+1;
id = H5D.open(fid,sprintf('/entry_0000/ESRF-ID31/%s/data',nm)); id = H5D.open(fid,sprintf('/entry_0000/ESRF-ID31/%s/data',nm));
if 2 < nargin & strcmp(nm,'p3') & ~isempty(det), if 2 < nargin & strcmp(nm,'p3') & ~isempty(det)
fprintf('integrating %s\n',fn); fprintf('integrating %s\n',fn);
if isempty(A), if isempty(A)
A = integrate(det,double(H5D.read(id)),1); A = integrate(det,double(H5D.read(id)),1);
else, else
tmp = integrate(det,double(H5D.read(id)),1); A.y = cat(2,A.y,tmp.y); A.y0 = cat(2,A.y0,tmp.y0); tmp = integrate(det,double(H5D.read(id)),1); A.y = cat(2,A.y,tmp.y); A.y0 = cat(2,A.y0,tmp.y0);
end; end
else, else
fprintf('loading %s\n',fn); fprintf('loading %s\n',fn);
A = cat(3,A,H5D.read(id)); A = cat(3,A,H5D.read(id));
end; end
H5D.close(id); H5F.close(fid); H5D.close(id); H5F.close(fid);
fn = sprintf('%s/%s_%.4d.h5',f,nm,n); fn = sprintf('%s/%s_%.4d.h5',f,nm,n);
end; end
%catch, end
% A = []; end
%end;
% fid = H5F.open...
% id = H5D.open...
% sid = H5D.get_space(id);
% [ndims,h5_dims]=H5S.get_simple_extent_dims(sid)
% Read a 2x3 hyperslab of data from a dataset, starting in the 4th row and 5th column of the example dataset.
% Create a property list identifier, then open the HDF5 file and the dataset /g1/g1.1/dset1.1.1.
% fid = H5F.open('example.h5');
% id = H5D.open(fid,'/g1/g1.1/dset1.1.1');
% dims = ([500 1679 1475];
% msid = H5S.create_simple(3,dims,[]);
% sid = H5D.get_space(id);
% offset = [n*500 0 0];
% block = dims; % d1: 500 or min(d1tot-n*500,500)
% H5S.select_hyperslab(sid,'H5S_SELECT_SET',offset,[],[],block);
% data = H5D.read(id,'H5ML_DEFAULT',msid,sid,'H5P_DEFAULT');
% H5D.close(id);
% H5F.close(fid);

View File

@@ -1,5 +1,3 @@
% Matlab Init :noexport:ignore:
%% test_id31_1_metrology.m %% test_id31_1_metrology.m
%% Clear Workspace and Close figures %% Clear Workspace and Close figures
@@ -34,51 +32,6 @@ specs_dz_rms = 15; % [nm RMS]
specs_dy_rms = 30; % [nm RMS] specs_dy_rms = 30; % [nm RMS]
specs_ry_rms = 0.25; % [urad RMS] specs_ry_rms = 0.25; % [urad RMS]
% Metrology Kinematics
% <<ssec:test_id31_metrology_kinematics>>
% The proposed short-stroke metrology system is schematized in Figure ref:fig:test_id31_metrology_kinematics.
% The point of interest is indicated by the blue frame $\{B\}$, which is located $H = 150\,mm$ above the nano-hexapod's top platform.
% The spheres have a diameter $d = 25.4\,mm$, and the indicated dimensions are $l_1 = 60\,mm$ and $l_2 = 16.2\,mm$.
% To compute the pose of the $\{B\}$ frame with respect to the granite (i.e. with respect to the fixed interferometer heads), the measured (small) displacements $[d_1,\ d_2,\ d_3,\ d_4,\ d_5]$ by the interferometers are first written as a function of the (small) linear and angular motion of the $\{B\}$ frame $[D_x,\ D_y,\ D_z,\ R_x,\ R_y]$ eqref:eq:test_id31_metrology_kinematics.
% \begin{equation}\label{eq:test_id31_metrology_kinematics}
% d_1 = D_y - l_2 R_x, \quad d_2 = D_y + l_1 R_x, \quad d_3 = -D_x - l_2 R_y, \quad d_4 = -D_x + l_1 R_y, \quad d_5 = -D_z
% \end{equation}
% #+attr_latex: :options [b]{0.48\linewidth}
% #+begin_minipage
% #+name: fig:test_id31_metrology_kinematics
% #+caption: Schematic of the measurement system. The measured distances are indicated by red arrows.
% #+attr_latex: :scale 1 :float nil
% [[file:figs/test_id31_metrology_kinematics.png]]
% #+end_minipage
% \hfill
% #+attr_latex: :options [b]{0.48\linewidth}
% #+begin_minipage
% #+name: fig:test_id31_align_top_sphere_comparators
% #+attr_latex: :width \linewidth :float nil
% #+caption: The top sphere is aligned with the rotation axis of the spindle using two probes.
% [[file:figs/test_id31_align_top_sphere_comparators.jpg]]
% #+end_minipage
% The five equations eqref:eq:test_id31_metrology_kinematics can be written in matrix form, and then inverted to have the pose of the $\{B\}$ frame as a linear combination of the measured five distances by the interferometers eqref:eq:test_id31_metrology_kinematics_inverse.
% \begin{equation}\label{eq:test_id31_metrology_kinematics_inverse}
% \begin{bmatrix}
% D_x \\ D_y \\ D_z \\ R_x \\ R_y
% \end{bmatrix} = {\underbrace{\begin{bmatrix}
% 0 & 1 & 0 & -l_2 & 0 \\
% 0 & 1 & 0 & l_1 & 0 \\
% -1 & 0 & 0 & 0 & -l_2 \\
% -1 & 0 & 0 & 0 & l_1 \\
% 0 & 0 & -1 & 0 & 0
% \end{bmatrix}}_{\bm{J_d}}}^{-1} \cdot \begin{bmatrix}
% d_1 \\ d_2 \\ d_3 \\ d_4 \\ d_5
% \end{bmatrix}
% \end{equation}
%% Geometrical parameters of the metrology system %% Geometrical parameters of the metrology system
H = 150e-3; H = 150e-3;
l1 = (150-48-42)*1e-3; l1 = (150-48-42)*1e-3;
@@ -91,26 +44,11 @@ Hm = [ 0 1 0 -l2 0;
-1 0 0 0 l1; -1 0 0 0 l1;
0 0 -1 0 0]; 0 0 -1 0 0];
% Fine Alignment of reference spheres using interferometers
% <<ssec:test_id31_metrology_sphere_fine_alignment>>
% Thanks to the first alignment of the two reference spheres with the spindle axis (Section ref:ssec:test_id31_metrology_sphere_rought_alignment) and to the fine adjustment of the interferometer orientations (Section ref:ssec:test_id31_metrology_alignment), the spindle can perform complete rotations while still having interference for all five interferometers.
% Therefore, this metrology can be used to better align the axis defined by the centers of the two spheres with the spindle axis.
% The alignment process requires few iterations.
% First, the spindle is scanned, and alignment errors are recorded.
% From the errors, the motion of the micro-hexapod to better align the spheres with the spindle axis is computed and the micro-hexapod is positioned accordingly.
% Then, the spindle is scanned again, and new alignment errors are recorded.
% This iterative process is first performed for angular errors (Figure ref:fig:test_id31_metrology_align_rx_ry) and then for lateral errors (Figure ref:fig:test_id31_metrology_align_dx_dy).
% The remaining errors after alignment are in the order of $\pm5\,\mu\text{rad}$ in $R_x$ and $R_y$ orientations, $\pm 1\,\mu m$ in $D_x$ and $D_y$ directions, and less than $0.1\,\mu m$ vertically.
%% Angular alignment %% Angular alignment
% Load Data % Load Data
data_it0 = h5scan(data_dir, 'alignment', 'h1rx_h1ry', 1); data_it0 = h5scan('alignment_h1rx_h1ry', 1);
data_it1 = h5scan(data_dir, 'alignment', 'h1rx_h1ry_0002', 3); data_it1 = h5scan('alignment_h1rx_h1ry_0002', 3);
data_it2 = h5scan(data_dir, 'alignment', 'h1rx_h1ry_0002', 5); data_it2 = h5scan('alignment_h1rx_h1ry_0002', 5);
% Offset wrong points % Offset wrong points
i_it0 = find(abs(data_it0.Rx_int_filtered(2:end)-data_it0.Rx_int_filtered(1:end-1))>1e-5); i_it0 = find(abs(data_it0.Rx_int_filtered(2:end)-data_it0.Rx_int_filtered(1:end-1))>1e-5);
@@ -143,8 +81,8 @@ ylim([-100, 800]);
%% Eccentricity alignment %% Eccentricity alignment
% Load Data % Load Data
data_it0 = h5scan(data_dir, 'alignment', 'h1rx_h1ry_0002', 5); data_it0 = h5scan('alignment_h1rx_h1ry_0002', 5);
data_it1 = h5scan(data_dir, 'alignment', 'h1dx_h1dy', 1); data_it1 = h5scan('alignment_h1dx_h1dy', 1);
% Offset wrong points % Offset wrong points
i_it0 = find(abs(data_it0.Dy_int_filtered(2:end)-data_it0.Dy_int_filtered(1:end-1))>1e-5); i_it0 = find(abs(data_it0.Dy_int_filtered(2:end)-data_it0.Dy_int_filtered(1:end-1))>1e-5);
@@ -168,21 +106,11 @@ legend('location', 'northeast', 'FontSize', 8, 'NumColumns', 1);
xlim([-1, 21]); xlim([-1, 21]);
ylim([-8, 14]); ylim([-8, 14]);
% Estimated measurement volume
% <<ssec:test_id31_metrology_acceptance>>
% Because the interferometers point to spheres and not flat surfaces, the lateral acceptance is limited.
% To estimate the metrology acceptance, the micro-hexapod was used to perform three accurate scans of $\pm 1\,mm$, respectively along the $x$, $y$ and $z$ axes.
% During these scans, the 5 interferometers are recorded individually, and the ranges in which each interferometer had enough coupling efficiency to be able to measure the displacement were estimated.
% Results are summarized in Table ref:tab:test_id31_metrology_acceptance.
% The obtained lateral acceptance for pure displacements in any direction is estimated to be around $+/-0.5\,mm$, which is enough for the current application as it is well above the micro-station errors to be actively corrected by the NASS.
%% Estimated acceptance of the metrology %% Estimated acceptance of the metrology
% This is estimated by moving the spheres using the micro-hexapod % This is estimated by moving the spheres using the micro-hexapod
% Dx % Dx
data_dx = h5scan(data_dir, 'metrology_acceptance_new_align', 'dx', 1); data_dx = h5scan('metrology_acceptance_new_align_dx', 1);
dx_acceptance = zeros(5,1); dx_acceptance = zeros(5,1);
@@ -198,7 +126,7 @@ for i = [1:size(dx_acceptance, 1)]
end end
% Dy % Dy
data_dy = h5scan(data_dir, 'metrology_acceptance_new_align', 'dy', 1); data_dy = h5scan('metrology_acceptance_new_align_dy', 1);
dy_acceptance = zeros(5,1); dy_acceptance = zeros(5,1);
@@ -214,7 +142,7 @@ for i = [1:size(dy_acceptance, 1)]
end end
% Dz % Dz
data_dz = h5scan(data_dir, 'metrology_acceptance_new_align', 'dz', 1); data_dz = h5scan('metrology_acceptance_new_align_dz', 1);
dz_acceptance = zeros(5,1); dz_acceptance = zeros(5,1);
@@ -229,30 +157,6 @@ for i = [1:size(dz_acceptance, 1)]
end end
end end
% Estimated measurement errors
% <<ssec:test_id31_metrology_errors>>
% When using the NASS, the accuracy of the sample positioning is determined by the accuracy of the external metrology.
% However, the validation of the nano-hexapod, the associated instrumentation, and the control architecture is independent of the accuracy of the metrology system.
% Only the bandwidth and noise characteristics of the external metrology are important.
% However, some elements that affect the accuracy of the metrology system are discussed here.
% First, the "metrology kinematics" (discussed in Section ref:ssec:test_id31_metrology_kinematics) is only approximate (i.e. valid for small displacements).
% This can be easily seen when performing lateral $[D_x,\,D_y]$ scans using the micro-hexapod while recording the vertical interferometer (Figure ref:fig:test_id31_xy_map_sphere).
% As the top interferometer points to a sphere and not to a plane, lateral motion of the sphere is seen as a vertical motion by the top interferometer.
% Then, the reference spheres have some deviations relative to an ideal sphere [fn:test_id31_6].
% These sphere are originally intended for use with capacitive sensors that integrate shape errors over large surfaces.
% When using interferometers, the size of the "light spot" on the sphere surface is a circle with a diameter approximately equal to $50\,\mu m$, and therefore the measurement is more sensitive to shape errors with small features.
% As the light from the interferometer travels through air (as opposed to being in vacuum), the measured distance is sensitive to any variation in the refractive index of the air.
% Therefore, any variation in air temperature, pressure or humidity will induce measurement errors.
% For instance, for a measurement length of $40\,mm$, a temperature variation of $0.1\,{}^oC$ (which is typical for the ID31 experimental hutch) induces errors in the distance measurement of $\approx 4\,nm$.
% Interferometers are also affected by noise [[cite:&watchi18_review_compac_inter]].
% The effect of noise on the translation and rotation measurements is estimated in Figure ref:fig:test_id31_interf_noise.
%% Interferometer noise estimation %% Interferometer noise estimation
data = load("test_id31_interf_noise.mat"); data = load("test_id31_interf_noise.mat");
@@ -282,7 +186,7 @@ leg = legend('location', 'northeast', 'FontSize', 8, 'NumColumns', 1);
leg.ItemTokenSize(1) = 15; leg.ItemTokenSize(1) = 15;
%% X-Y scan with the micro-hexapod, and record of the vertical interferometer %% X-Y scan with the micro-hexapod, and record of the vertical interferometer
data = h5scan(data_dir, 'metrology_acceptance', 'after_int_align_meshXY', 1); data = h5scan('metrology_acceptance_after_int_align_meshXY', 1);
x = 1e3*detrend(data.h1tx, 0); % [um] x = 1e3*detrend(data.h1tx, 0); % [um]
y = 1e3*detrend(data.h1ty, 0); % [um] y = 1e3*detrend(data.h1ty, 0); % [um]

View File

@@ -1,5 +1,3 @@
% Matlab Init :noexport:ignore:
%% test_id31_2_open_loop_plant.m %% test_id31_2_open_loop_plant.m
%% Clear Workspace and Close figures %% Clear Workspace and Close figures
@@ -37,21 +35,6 @@ specs_dz_rms = 15; % [nm RMS]
specs_dy_rms = 30; % [nm RMS] specs_dy_rms = 30; % [nm RMS]
specs_ry_rms = 0.25; % [urad RMS] specs_ry_rms = 0.25; % [urad RMS]
% Open-Loop Plant Identification
% <<ssec:test_id31_open_loop_plant_first_id>>
% The dynamics of the plant is first identified for a fixed spindle angle (at $0\,\text{deg}$) and without any payload.
% The model dynamics is also identified under the same conditions.
% A comparison between the model and the measured dynamics is presented in Figure ref:fig:test_id31_first_id.
% A good match can be observed for the diagonal dynamics (except the high frequency modes which are not modeled).
% However, the coupling of the transfer function from command signals $\bm{u}$ to the estimated strut motion from the external metrology $\bm{\epsilon\mathcal{L}}$ is larger than expected (Figure ref:fig:test_id31_first_id_int).
% The experimental time delay estimated from the FRF (Figure ref:fig:test_id31_first_id_int) is larger than expected.
% After investigation, it was found that the additional delay was due to a digital processing unit[fn:test_id31_3] that was used to get the interferometers' signals in the Speedgoat.
% This issue was later solved.
%% Identify the plant dynamics using the Simscape model %% Identify the plant dynamics using the Simscape model
% Initialize each Simscape model elements % Initialize each Simscape model elements
@@ -214,24 +197,11 @@ ylim([-90, 180])
linkaxes([ax1,ax2],'x'); linkaxes([ax1,ax2],'x');
xlim([1, 1e3]); xlim([1, 1e3]);
% Better Angular Alignment
% <<ssec:test_id31_open_loop_plant_rz_alignment>>
% One possible explanation of the increased coupling observed in Figure ref:fig:test_id31_first_id_int is the poor alignment between the external metrology axes (i.e. the interferometer supports) and the nano-hexapod axes.
% To estimate this alignment, a decentralized low-bandwidth feedback controller based on the nano-hexapod encoders was implemented.
% This allowed to perform two straight movements of the nano-hexapod along its $x$ and $y$ axes.
% During these two movements, external metrology measurements were recorded and the results are shown in Figure ref:fig:test_id31_Rz_align_error_and_correct.
% It was found that there was a misalignment of 2.7 degrees (rotation along the vertical axis) between the interferometer axes and nano-hexapod axes.
% This was corrected by adding an offset to the spindle angle.
% After alignment, the same movement was performed using the nano-hexapod while recording the signal of the external metrology.
% Results shown in Figure ref:fig:test_id31_Rz_align_correct are indeed indicating much better alignment.
%% Load Data %% Load Data
data_1_dx = h5scan(data_dir, 'align_int_enc_Rz', 'tx_first_scan', 2); data_1_dx = h5scan('align_int_enc_Rz_tx_first_scan', 2);
data_1_dy = h5scan(data_dir, 'align_int_enc_Rz', 'tx_first_scan', 3); data_1_dy = h5scan('align_int_enc_Rz_tx_first_scan', 3);
data_2_dx = h5scan(data_dir, 'align_int_enc_Rz', 'verif-after-correct-offset', 1); data_2_dx = h5scan('align_int_enc_Rz_verif-after-correct-offset', 1);
data_2_dy = h5scan(data_dir, 'align_int_enc_Rz', 'verif-after-correct-offset', 2); data_2_dy = h5scan('align_int_enc_Rz_verif-after-correct-offset', 2);
% Estimation of Rz misalignment % Estimation of Rz misalignment
p1 = polyfit(data_1_dx.Dx_int_filtered, data_1_dx.Dy_int_filtered, 1); p1 = polyfit(data_1_dx.Dx_int_filtered, data_1_dx.Dy_int_filtered, 1);
@@ -277,33 +247,6 @@ xticks([-10:5:10]); yticks([-10:5:10]);
leg = legend('location', 'southeast', 'FontSize', 8, 'NumColumns', 1); leg = legend('location', 'southeast', 'FontSize', 8, 'NumColumns', 1);
leg.ItemTokenSize(1) = 15; leg.ItemTokenSize(1) = 15;
% #+name: fig:test_id31_Rz_align_error_and_correct
% #+caption: Measurement of the Nano-Hexapod axes in the frame of the external metrology. Before alignment (\subref{fig:test_id31_Rz_align_error}) and after alignment (\subref{fig:test_id31_Rz_align_correct}).
% #+attr_latex: :options [htbp]
% #+begin_figure
% #+attr_latex: :caption \subcaption{\label{fig:test_id31_Rz_align_error}Before alignment}
% #+attr_latex: :options {0.49\textwidth}
% #+begin_subfigure
% #+attr_latex: :scale 1
% [[file:figs/test_id31_Rz_align_error.png]]
% #+end_subfigure
% #+attr_latex: :caption \subcaption{\label{fig:test_id31_Rz_align_correct}After alignment}
% #+attr_latex: :options {0.49\textwidth}
% #+begin_subfigure
% #+attr_latex: :scale 1
% [[file:figs/test_id31_Rz_align_correct.png]]
% #+end_subfigure
% #+end_figure
% The dynamics of the plant was identified again after fine alignment and compared with the model dynamics in Figure ref:fig:test_id31_first_id_int_better_rz_align.
% Compared to the initial identification shown in Figure ref:fig:test_id31_first_id_int, the obtained coupling was decreased and was close to the coupling obtained with the multi-body model.
% At low frequency (below $10\,\text{Hz}$), all off-diagonal elements have an amplitude $\approx 100$ times lower than the diagonal elements, indicating that a low bandwidth feedback controller can be implemented in a decentralized manner (i.e. $6$ SISO controllers).
% Between $650\,\text{Hz}$ and $1000\,\text{Hz}$, several modes can be observed, which are due to flexible modes of the top platform and the modes of the two spheres adjustment mechanism.
% The flexible modes of the top platform can be passively damped, whereas the modes of the two reference spheres should not be present in the final application.
%% Identification of the plant after Rz alignment %% Identification of the plant after Rz alignment
data_align = load('2023-08-17_17-37_ol_plant_m0_Wz0_new_Rz_align.mat'); data_align = load('2023-08-17_17-37_ol_plant_m0_Wz0_new_Rz_align.mat');
@@ -349,47 +292,6 @@ xlim([1, 1e3]); ylim([2e-9, 2e-4]);
leg = legend('location', 'southeast', 'FontSize', 8, 'NumColumns', 2); leg = legend('location', 'southeast', 'FontSize', 8, 'NumColumns', 2);
leg.ItemTokenSize(1) = 15; leg.ItemTokenSize(1) = 15;
% Effect of Payload Mass
% <<ssec:test_id31_open_loop_plant_mass>>
% To determine how the system dynamics changes with the payload, open-loop identification was performed for four payload conditions shown in Figure ref:fig:test_id31_picture_masses.
% The obtained direct terms are compared with the model dynamics in Figure ref:fig:test_id31_comp_simscape_diag_masses.
% It was found that the model well predicts the measured dynamics under all payload conditions.
% Therefore, the model can be used for model-based control is necessary.
% It is interesting to note that the anti-resonances in the force sensor plant now appear as minimum-phase, as the model predicts (Figure ref:fig:test_id31_comp_simscape_iff_diag_masses).
% #+name: fig:test_id31_picture_masses
% #+caption: The four tested payload conditions. (\subref{fig:test_id31_picture_mass_m0}) without payload. (\subref{fig:test_id31_picture_mass_m1}) with $13\,\text{kg}$ payload. (\subref{fig:test_id31_picture_mass_m2}) with $26\,\text{kg}$ payload. (\subref{fig:test_id31_picture_mass_m3}) with $39\,\text{kg}$ payload.
% #+attr_latex: :options [htbp]
% #+begin_figure
% #+attr_latex: :caption \subcaption{\label{fig:test_id31_picture_mass_m0}$m=0\,\text{kg}$}
% #+attr_latex: :options {0.24\textwidth}
% #+begin_subfigure
% #+attr_latex: :width 0.99\linewidth
% [[file:figs/test_id31_picture_mass_m0.jpg]]
% #+end_subfigure
% #+attr_latex: :caption \subcaption{\label{fig:test_id31_picture_mass_m1}$m=13\,\text{kg}$}
% #+attr_latex: :options {0.24\textwidth}
% #+begin_subfigure
% #+attr_latex: :width 0.99\linewidth
% [[file:figs/test_id31_picture_mass_m1.jpg]]
% #+end_subfigure
% #+attr_latex: :caption \subcaption{\label{fig:test_id31_picture_mass_m2}$m=26\,\text{kg}$}
% #+attr_latex: :options {0.24\textwidth}
% #+begin_subfigure
% #+attr_latex: :width 0.99\linewidth
% [[file:figs/test_id31_picture_mass_m2.jpg]]
% #+end_subfigure
% #+attr_latex: :caption \subcaption{\label{fig:test_id31_picture_mass_m3}$m=39\,\text{kg}$}
% #+attr_latex: :options {0.24\textwidth}
% #+begin_subfigure
% #+attr_latex: :width 0.99\linewidth
% [[file:figs/test_id31_picture_mass_m3.jpg]]
% #+end_subfigure
% #+end_figure
%% Identify the model dynamics for all payload conditions %% Identify the model dynamics for all payload conditions
% Initialize each Simscape model elements % Initialize each Simscape model elements
initializeGround(); initializeGround();
@@ -667,18 +569,6 @@ linkaxes([ax1,ax2],'x');
xlim([10, 5e2]); xlim([10, 5e2]);
xticks([10, 20, 50, 100, 200, 500]) xticks([10, 20, 50, 100, 200, 500])
% Effect of Spindle Rotation
% <<ssec:test_id31_open_loop_plant_rotation>>
% To verify that all the kinematics in Figure ref:fig:test_id31_block_schematic_plant are correct and to check whether the system dynamics is affected by Spindle rotation of not, three identification experiments were performed: no spindle rotation, spindle rotation at $36\,\text{deg}/s$ and at $180\,\text{deg}/s$.
% The obtained dynamics from command signal $u$ to estimated strut error $\epsilon\mathcal{L}$ are displayed in Figure ref:fig:test_id31_effect_rotation.
% Both direct terms (Figure ref:fig:test_id31_effect_rotation_direct) and coupling terms (Figure ref:fig:test_id31_effect_rotation_coupling) are unaffected by the rotation.
% The same can be observed for the dynamics from command signal to encoders and to force sensors.
% This confirms that spindle's rotation has no significant effect on plant dynamics.
% This also indicates that the metrology kinematics is correct and is working in real time.
%% Identify the model dynamics with Spindle rotation %% Identify the model dynamics with Spindle rotation
initializeSample('type', '0'); initializeSample('type', '0');
initializeReferences(... initializeReferences(...

View File

@@ -1,5 +1,3 @@
% Matlab Init :noexport:ignore:
%% test_id31_3_iff.m %% test_id31_3_iff.m
%% Clear Workspace and Close figures %% Clear Workspace and Close figures
@@ -37,18 +35,6 @@ specs_dz_rms = 15; % [nm RMS]
specs_dy_rms = 30; % [nm RMS] specs_dy_rms = 30; % [nm RMS]
specs_ry_rms = 0.25; % [urad RMS] specs_ry_rms = 0.25; % [urad RMS]
% IFF Plant
% <<ssec:test_id31_iff_plant>>
% As the multi-body model is used to evaluate the stability of the IFF controller and to optimize the achievable damping, it is first checked whether this model accurately represents the system dynamics.
% In the previous section (Figure ref:fig:test_id31_comp_simscape_iff_diag_masses), it was shown that the model well captures the dynamics from each actuator to its collocated force sensor, and that for all considered payloads.
% Nevertheless, it is also important to well model the coupling in the system.
% To verify that, instead of comparing the 36 elements of the $6 \times 6$ frequency response matrix from $\bm{u}$ to $\bm{V_s}$, only 6 elements are compared in Figure ref:fig:test_id31_comp_simscape_Vs.
% Similar results were obtained for all other 30 elements and for the different payload conditions.
% This confirms that the multi-body model can be used to tune the IFF controller.
% Load identified FRF for IFF Plant and Multi-Body Model % Load identified FRF for IFF Plant and Multi-Body Model
load('test_id31_identified_open_loop_plants.mat', 'G_iff_m0_Wz0', 'G_iff_m1_Wz0', 'G_iff_m2_Wz0', 'G_iff_m3_Wz0', 'f'); load('test_id31_identified_open_loop_plants.mat', 'G_iff_m0_Wz0', 'G_iff_m1_Wz0', 'G_iff_m2_Wz0', 'G_iff_m3_Wz0', 'f');
load('test_id31_simscape_open_loop_plants.mat', 'Gm_m0_Wz0', 'Gm_m1_Wz0', 'Gm_m2_Wz0', 'Gm_m3_Wz0'); load('test_id31_simscape_open_loop_plants.mat', 'Gm_m0_Wz0', 'Gm_m1_Wz0', 'Gm_m2_Wz0', 'Gm_m3_Wz0');
@@ -122,21 +108,6 @@ xticks([10, 20, 50, 100, 200])
linkaxes([ax1,ax2,ax3,ax4,ax5,ax6],'xy'); linkaxes([ax1,ax2,ax3,ax4,ax5,ax6],'xy');
xlim([10, 5e2]); ylim([1e-2, 5e1]); xlim([10, 5e2]); ylim([1e-2, 5e1]);
% IFF Controller
% <<ssec:test_id31_iff_controller>>
% A decentralized IFF controller was designed to add damping to the suspension modes of the nano-hexapod for all considered payloads.
% The frequency of the suspension modes are ranging from $\approx 30\,\text{Hz}$ to $\approx 250\,\text{Hz}$ (Figure ref:fig:test_id31_comp_simscape_iff_diag_masses), and therefore, the IFF controller should provide integral action in this frequency range.
% A second-order high-pass filter (cut-off frequency of $10\,\text{Hz}$) was added to limit the low frequency gain eqref:eq:test_id31_Kiff.
% \begin{equation}\label{eq:test_id31_Kiff}
% K_{\text{IFF}} = g_0 \cdot \underbrace{\frac{1}{s}}_{\text{int}} \cdot \underbrace{\frac{s^2/\omega_z^2}{s^2/\omega_z^2 + 2\xi_z s /\omega_z + 1}}_{\text{2nd order LPF}},\quad \left(g_0 = -100,\ \omega_z = 2\pi10\,\text{rad/s},\ \xi_z = 0.7\right)
% \end{equation}
% The bode plot of the decentralized IFF controller is shown in Figure ref:fig:test_id31_Kiff_bode_plot and the "decentralized loop-gains" for all considered payload masses are shown in Figure ref:fig:test_id31_Kiff_loop_gain.
% It can be seen that the loop-gain is larger than $1$ around the suspension modes, which indicates that some damping should be added to the suspension modes.
%% IFF Controller Design %% IFF Controller Design
% Second order high pass filter % Second order high pass filter
wz = 2*pi*10; wz = 2*pi*10;
@@ -219,34 +190,6 @@ ylim([-180, 180])
linkaxes([ax1,ax2],'x'); linkaxes([ax1,ax2],'x');
xlim([1, 1e3]); xlim([1, 1e3]);
% #+name: fig:test_id31_Kiff
% #+caption: Bode plot of the decentralized IFF controller (\subref{fig:test_id31_Kiff_bode_plot}). The decentralized controller $K_{\text{IFF}}$ multiplied by the identified dynamics from $u_1$ to $V_{s1}$ for all payloads are shown in (\subref{fig:test_id31_Kiff_loop_gain})
% #+attr_latex: :options [htbp]
% #+begin_figure
% #+attr_latex: :caption \subcaption{\label{fig:test_id31_Kiff_bode_plot}Bode plot of $K_{\text{IFF}}$}
% #+attr_latex: :options {0.49\textwidth}
% #+begin_subfigure
% #+attr_latex: :width 0.95\linewidth
% [[file:figs/test_id31_Kiff_bode_plot.png]]
% #+end_subfigure
% #+attr_latex: :caption \subcaption{\label{fig:test_id31_Kiff_loop_gain}Decentralized Loop gains}
% #+attr_latex: :options {0.49\textwidth}
% #+begin_subfigure
% #+attr_latex: :width 0.95\linewidth
% [[file:figs/test_id31_Kiff_loop_gain.png]]
% #+end_subfigure
% #+end_figure
% To estimate the added damping, a root-locus plot was computed using the multi-body model (Figure ref:fig:test_id31_iff_root_locus).
% It can be seen that for all considered payloads, the poles are bounded to the "left-half plane" indicating that the decentralized IFF is robust.
% The closed-loop poles for the chosen gain value are represented by black crosses.
% It can be seen that while damping can be added for all payloads (as compared to the open-loop case), the optimal value of the gain is different for each payload.
% For low payload masses, a higher IFF controller gain can lead to better damping.
% However, in this study, it was chosen to implement a "fixed" (i.e. non-adaptive) decentralized IFF controller.
%% Root Locus for IFF %% Root Locus for IFF
gains = logspace(-2, 2, 100); gains = logspace(-2, 2, 100);
Gm_iff_m0 = Gm_m0_Wz0({'Vs1', 'Vs2', 'Vs3', 'Vs4', 'Vs5', 'Vs6'}, {'u1', 'u2', 'u3', 'u4', 'u5', 'u6'}); Gm_iff_m0 = Gm_m0_Wz0({'Vs1', 'Vs2', 'Vs3', 'Vs4', 'Vs5', 'Vs6'}, {'u1', 'u2', 'u3', 'u4', 'u5', 'u6'});
@@ -357,17 +300,6 @@ xlim([-200, 0]); ylim([0, 500]);
set(gca, 'XTickLabel',[]); set(gca, 'YTickLabel',[]); set(gca, 'XTickLabel',[]); set(gca, 'YTickLabel',[]);
xlabel('Real part'); ylabel('Imaginary part'); xlabel('Real part'); ylabel('Imaginary part');
% Damped Plant
% <<ssec:test_id31_iff_perf>>
% As the model accurately represents the system dynamics, it can be used to estimate the damped plant, i.e. the transfer functions from $\bm{u}^\prime$ to $\bm{\mathcal{L}}$.
% The obtained damped plants are compared to the open-loop plants in Figure ref:fig:test_id31_comp_ol_iff_plant_model.
% The peak amplitudes corresponding to the suspension modes were approximately reduced by a factor $10$ for all considered payloads, indicating the effectiveness of the decentralized IFF control strategy.
% To experimentally validate the Decentralized IFF controller, it was implemented and the damped plants (i.e. the transfer function from $\bm{u}^\prime$ to $\bm{\epsilon\mathcal{L}}$) were identified for all payload conditions.
% The obtained frequency response functions are compared with the model in Figure ref:fig:test_id31_hac_plant_effect_mass verifying the good correlation between the predicted damped plant using the multi-body model and the experimental results.
%% Estimate damped plant from Multi-Body model %% Estimate damped plant from Multi-Body model
Gm_hac_m0_Wz0 = feedback(Gm_m0_Wz0, Kiff, 'name', +1); Gm_hac_m0_Wz0 = feedback(Gm_m0_Wz0, Kiff, 'name', +1);
Gm_hac_m1_Wz0 = feedback(Gm_m1_Wz0, Kiff, 'name', +1); Gm_hac_m1_Wz0 = feedback(Gm_m1_Wz0, Kiff, 'name', +1);

View File

@@ -1,5 +1,3 @@
% Matlab Init :noexport:ignore:
%% test_id31_4_hac.m %% test_id31_4_hac.m
%% Clear Workspace and Close figures %% Clear Workspace and Close figures
@@ -37,13 +35,6 @@ specs_dz_rms = 15; % [nm RMS]
specs_dy_rms = 30; % [nm RMS] specs_dy_rms = 30; % [nm RMS]
specs_ry_rms = 0.25; % [urad RMS] specs_ry_rms = 0.25; % [urad RMS]
% Damped Plant
% <<ssec:test_id31_iff_hac_plant>>
% To verify whether the multi-body model accurately represents the measured damped dynamics, both the direct terms and coupling terms corresponding to the first actuator are compared in Figure ref:fig:test_id31_comp_simscape_hac.
% Considering the complexity of the system's dynamics, the model can be considered to represent the system's dynamics with good accuracy, and can therefore be used to tune the feedback controller and evaluate its performance.
% Load the estimated damped plant from the multi-body model % Load the estimated damped plant from the multi-body model
load('test_id31_simscape_damped_plants.mat', 'Gm_hac_m0_Wz0', 'Gm_hac_m1_Wz0', 'Gm_hac_m2_Wz0', 'Gm_hac_m3_Wz0'); load('test_id31_simscape_damped_plants.mat', 'Gm_hac_m0_Wz0', 'Gm_hac_m1_Wz0', 'Gm_hac_m2_Wz0', 'Gm_hac_m3_Wz0');
% Load the measured damped plants % Load the measured damped plants
@@ -120,19 +111,6 @@ leg.ItemTokenSize(1) = 15;
linkaxes([ax1,ax2,ax3,ax4,ax5,ax6],'xy'); linkaxes([ax1,ax2,ax3,ax4,ax5,ax6],'xy');
xlim([10, 5e2]); ylim([1e-7, 4e-5]); xlim([10, 5e2]); ylim([1e-7, 4e-5]);
% #+name: fig:test_id31_comp_simscape_hac
% #+caption: Comparison of the measured (in blue) and modeled (in red) frequency transfer functions from the first control signal ($u_1^\prime$) of the damped plant to the estimated errors ($\epsilon_{\mathcal{L}_i}$) in the frame of the six struts by the external metrology
% #+RESULTS:
% [[file:figs/test_id31_comp_simscape_hac.png]]
% The challenge here is to tune a high authority controller such that it is robust to the change in dynamics due to different payloads being used.
% Without using the HAC-LAC strategy, it would be necessary to design a controller that provides good performance for all undamped dynamics (blue curves in Figure ref:fig:test_id31_comp_all_undamped_damped_plants), which is a very complex control problem.
% With the HAC-LAC strategy, the designed controller must be robust to all the damped dynamics (red curves in Figure ref:fig:test_id31_comp_all_undamped_damped_plants), which is easier from a control perspective.
% This is one of the key benefits of using the HAC-LAC strategy.
%% Comparison of all the undamped FRF and all the damped FRF %% Comparison of all the undamped FRF and all the damped FRF
figure; figure;
tiledlayout(3, 1, 'TileSpacing', 'compact', 'Padding', 'None'); tiledlayout(3, 1, 'TileSpacing', 'compact', 'Padding', 'None');
@@ -184,30 +162,6 @@ ylim([-270, 20])
linkaxes([ax1,ax2],'x'); linkaxes([ax1,ax2],'x');
xlim([1, 5e2]); xlim([1, 5e2]);
% Interaction Analysis
% <<sec:test_id31_hac_interaction_analysis>>
% The control strategy here is to apply a diagonal control in the frame of the struts; thus, it is important to determine the frequency at which the multivariable effects become significant, as this represents a critical limitation of the control approach.
% To conduct this interaction analysis, the acrfull:rga $\bm{\Lambda_G}$ is first computed using eqref:eq:test_id31_rga for the plant dynamics identified with the multiple payload masses.
% \begin{equation}\label{eq:test_id31_rga}
% \bm{\Lambda_G}(\omega) = \bm{G}(j\omega) \star \left(\bm{G}(j\omega)^{-1}\right)^{T}, \quad (\star \text{ means element wise multiplication})
% \end{equation}
% Then, acrshort:rga numbers are computed using eqref:eq:test_id31_rga_number and are use as a metric for interaction [[cite:&skogestad07_multiv_feedb_contr chapt. 3.4]].
% \begin{equation}\label{eq:test_id31_rga_number}
% \text{RGA number}(\omega) = \|\bm{\Lambda_G}(\omega) - \bm{I}\|_{\text{sum}}
% \end{equation}
% The obtained acrshort:rga numbers are compared in Figure ref:fig:test_id31_hac_rga_number.
% The results indicate that higher payload masses increase the coupling when implementing control in the strut reference frame (i.e., decentralized approach).
% This indicates that achieving high bandwidth feedback control is increasingly challenging as the payload mass increases.
% This behavior can be attributed to the fundamental approach of implementing control in the frame of the struts.
% Above the suspension modes of the nano-hexapod, the motion induced by the piezoelectric actuators is no longer dictated by kinematics but rather by the inertia of the different parts.
% This design choice, while beneficial for system simplicity, introduces inherent limitations in the system's ability to handle larger masses at high frequency.
%% Interaction Analysis - RGA Number %% Interaction Analysis - RGA Number
rga_m0 = zeros(1,size(G_hac_m0_Wz0,1)); rga_m0 = zeros(1,size(G_hac_m0_Wz0,1));
for i = 1:length(rga_m0) for i = 1:length(rga_m0)
@@ -236,29 +190,13 @@ plot(f, rga_m0, 'DisplayName', '$m = 0$ kg')
plot(f, rga_m1, 'DisplayName', '$m = 13$ kg') plot(f, rga_m1, 'DisplayName', '$m = 13$ kg')
plot(f, rga_m2, 'DisplayName', '$m = 26$ kg') plot(f, rga_m2, 'DisplayName', '$m = 26$ kg')
plot(f, rga_m3, 'DisplayName', '$m = 39$ kg') plot(f, rga_m3, 'DisplayName', '$m = 39$ kg')
hold off;
xlabel('Frequency [Hz]'); ylabel('RGA number'); xlabel('Frequency [Hz]'); ylabel('RGA number');
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin'); set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
xlim([1, 1e2]); ylim([0, 10]); xlim([1, 1e2]); ylim([0, 10]);
leg = legend('location', 'northwest', 'FontSize', 8, 'NumColumns', 2); leg = legend('location', 'northwest', 'FontSize', 8, 'NumColumns', 2);
leg.ItemTokenSize(1) = 15; leg.ItemTokenSize(1) = 15;
% Robust Controller Design
% <<ssec:test_id31_iff_hac_controller>>
% A diagonal controller was designed to be robust against changes in payload mass, which means that every damped plant shown in Figure ref:fig:test_id31_comp_all_undamped_damped_plants must be considered during the controller design.
% For this controller design, a crossover frequency of $5\,\text{Hz}$ was chosen to limit the multivariable effects, as explain in Section ref:sec:test_id31_hac_interaction_analysis.
% One integrator is added to increase the low-frequency gain, a lead is added around $5\,\text{Hz}$ to increase the stability margins and a first-order low-pass filter with a cut-off frequency of $30\,\text{Hz}$ is added to improve the robustness to dynamical uncertainty at high frequency.
% The controller transfer function is shown in eqref:eq:test_id31_robust_hac.
% \begin{equation}\label{eq:test_id31_robust_hac}
% K_{\text{HAC}}(s) = g_0 \cdot \underbrace{\frac{\omega_c}{s}}_{\text{int}} \cdot \underbrace{\frac{1}{\sqrt{\alpha}}\frac{1 + \frac{s}{\omega_c/\sqrt{\alpha}}}{1 + \frac{s}{\omega_c\sqrt{\alpha}}}}_{\text{lead}} \cdot \underbrace{\frac{1}{1 + \frac{s}{\omega_0}}}_{\text{LPF}}, \quad \left( \omega_c = 2\pi5\,\text{rad/s},\ \alpha = 2,\ \omega_0 = 2\pi30\,\text{rad/s} \right)
% \end{equation}
% The obtained "decentralized" loop-gains (i.e. the diagonal element of the controller times the diagonal terms of the plant) are shown in Figure ref:fig:test_id31_hac_loop_gain.
% The closed-loop stability was verified by computing the characteristic Loci (Figure ref:fig:test_id31_hac_characteristic_loci).
% However, small stability margins were observed for the highest mass, indicating that some multivariable effects are in play.
%% HAC Design %% HAC Design
% Wanted crossover % Wanted crossover
wc = 2*pi*5; % [rad/s] wc = 2*pi*5; % [rad/s]
@@ -292,10 +230,10 @@ tiledlayout(3, 1, 'TileSpacing', 'Compact', 'Padding', 'None');
ax1 = nexttile([2,1]); ax1 = nexttile([2,1]);
hold on; hold on;
plot(f(2:end), abs(G_hac_m0_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f(2:end), 'Hz'))), 'color', colors(1,:), 'DisplayName', '$0$ kg'); plot(f, abs(G_hac_m0_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f, 'Hz'))), 'color', colors(1,:), 'DisplayName', '$0$ kg');
plot(f(2:end), abs(G_hac_m1_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f(2:end), 'Hz'))), 'color', colors(2,:), 'DisplayName', '$13$ kg'); plot(f, abs(G_hac_m1_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f, 'Hz'))), 'color', colors(2,:), 'DisplayName', '$13$ kg');
plot(f(2:end), abs(G_hac_m2_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f(2:end), 'Hz'))), 'color', colors(3,:), 'DisplayName', '$26$ kg'); plot(f, abs(G_hac_m2_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f, 'Hz'))), 'color', colors(3,:), 'DisplayName', '$26$ kg');
plot(f(2:end), abs(G_hac_m3_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f(2:end), 'Hz'))), 'color', colors(4,:), 'DisplayName', '$39$ kg'); plot(f, abs(G_hac_m3_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f, 'Hz'))), 'color', colors(4,:), 'DisplayName', '$39$ kg');
xline(5, '--', 'linewidth', 1, 'color', [0,0,0,0.2], 'HandleVisibility', 'off') xline(5, '--', 'linewidth', 1, 'color', [0,0,0,0.2], 'HandleVisibility', 'off')
hold off; hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
@@ -306,10 +244,10 @@ leg.ItemTokenSize(1) = 15;
ax2 = nexttile; ax2 = nexttile;
hold on; hold on;
plot(f(2:end), 180/pi*angle(G_hac_m0_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f(2:end), 'Hz'))), 'color', colors(1,:)); plot(f, 180/pi*angle(G_hac_m0_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f, 'Hz'))), 'color', colors(1,:));
plot(f(2:end), 180/pi*angle(G_hac_m1_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f(2:end), 'Hz'))), 'color', colors(2,:)); plot(f, 180/pi*angle(G_hac_m1_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f, 'Hz'))), 'color', colors(2,:));
plot(f(2:end), 180/pi*angle(G_hac_m2_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f(2:end), 'Hz'))), 'color', colors(3,:)); plot(f, 180/pi*angle(G_hac_m2_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f, 'Hz'))), 'color', colors(3,:));
plot(f(2:end), 180/pi*angle(G_hac_m3_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f(2:end), 'Hz'))), 'color', colors(4,:)); plot(f, 180/pi*angle(G_hac_m3_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f, 'Hz'))), 'color', colors(4,:));
xline(5, '--', 'linewidth', 1, 'color', [0,0,0,0.2]) xline(5, '--', 'linewidth', 1, 'color', [0,0,0,0.2])
hold off; hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin'); set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
@@ -382,15 +320,6 @@ leg.ItemTokenSize(1) = 15;
axis square axis square
xlim([-1.5, 0.5]); ylim([-1, 1]); xlim([-1.5, 0.5]); ylim([-1, 1]);
% Performance estimation with simulation of Tomography scans
% <<ssec:test_id31_iff_hac_perf>>
% To estimate the performances that can be expected with this HAC-LAC architecture and the designed controller, simulations of tomography experiments were performed[fn:test_id31_4].
% The rotational velocity was set to $180\,\text{deg/s}$, and no payload was added on top of the nano-hexapod.
% An open-loop simulation and a closed-loop simulation were performed and compared in Figure ref:fig:test_id31_tomo_m0_30rpm_robust_hac_iff_sim.
% The obtained closed-loop positioning accuracy was found to comply with the requirements as it succeeded to keep the point of interest on the beam (Figure ref:fig:test_id31_tomo_m0_30rpm_robust_hac_iff_sim_yz).
%% Tomography experiment %% Tomography experiment
% Sample is not centered with the rotation axis % Sample is not centered with the rotation axis
% This is done by offsetfing the micro-hexapod by 0.9um % This is done by offsetfing the micro-hexapod by 0.9um
@@ -492,17 +421,6 @@ xlim([-300, 300]); ylim([-100, 100]);
leg = legend('location', 'northeast', 'FontSize', 8, 'NumColumns', 1); leg = legend('location', 'northeast', 'FontSize', 8, 'NumColumns', 1);
leg.ItemTokenSize(1) = 15; leg.ItemTokenSize(1) = 15;
% Robustness estimation with simulation of Tomography scans
% <<ssec:test_id31_iff_hac_robustness>>
% To verify the robustness against payload mass variations, four simulations of tomography experiments were performed with payloads as shown Figure ref:fig:test_id31_picture_masses (i.e. $0\,kg$, $13\,kg$, $26\,kg$ and $39\,kg$).
% The rotational velocity was set at $6\,\text{deg/s}$, which is the typical rotational velocity for heavy samples.
% The closed-loop systems were stable under all payload conditions, indicating good control robustness.
% However, the positioning errors worsen as the payload mass increases, especially in the lateral $D_y$ direction, as shown in Figure ref:fig:test_id31_hac_tomography_Wz36_simulation.
% However, it was decided that this controller should be tested experimentally and improved only if necessary.
%% Simulation of tomography experiments at 1RPM with all payloads %% Simulation of tomography experiments at 1RPM with all payloads
% Configuration % Configuration
open(mdl); open(mdl);

View File

@@ -1,5 +1,3 @@
% Matlab Init :noexport:ignore:
%% test_id31_5_experiments.m %% test_id31_5_experiments.m
%% Clear Workspace and Close figures %% Clear Workspace and Close figures
@@ -34,18 +32,6 @@ specs_dz_rms = 15; % [nm RMS]
specs_dy_rms = 30; % [nm RMS] specs_dy_rms = 30; % [nm RMS]
specs_ry_rms = 0.25; % [urad RMS] specs_ry_rms = 0.25; % [urad RMS]
% Slow Tomography scans
% First, tomography scans were performed with a rotational velocity of $6\,\text{deg/s}$ for all considered payload masses (shown in Figure ref:fig:test_id31_picture_masses).
% Each experimental sequence consisted of two complete spindle rotations: an initial open-loop rotation followed by a closed-loop rotation.
% The experimental results for the $26\,\text{kg}$ payload are presented in Figure ref:fig:test_id31_tomo_m2_1rpm_robust_hac_iff_fit.
% Due to the static deformation of the micro-station stages under payload loading, a significant eccentricity was observed between the point of interest and the spindle rotation axis.
% To establish a theoretical lower bound for open-loop errors, an ideal scenario was assumed, where the point of interest perfectly aligns with the spindle rotation axis.
% This idealized case was simulated by first calculating the eccentricity through circular fitting (represented by the dashed black circle in Figure ref:fig:test_id31_tomo_m2_1rpm_robust_hac_iff_fit), and then subtracting it from the measured data, as shown in Figure ref:fig:test_id31_tomo_m2_1rpm_robust_hac_iff_fit_removed.
% While this approach likely underestimates actual open-loop errors, as perfect alignment is practically unattainable, it enables a more balanced comparison with closed-loop performance.
%% Load Tomography scans with robust controller %% Load Tomography scans with robust controller
data_tomo_m0_Wz6 = load("2023-08-11_11-37_tomography_1rpm_m0.mat"); data_tomo_m0_Wz6 = load("2023-08-11_11-37_tomography_1rpm_m0.mat");
data_tomo_m0_Wz6.time = Ts*[0:length(data_tomo_m0_Wz6.Rz)-1]; data_tomo_m0_Wz6.time = Ts*[0:length(data_tomo_m0_Wz6.Rz)-1];
@@ -116,31 +102,6 @@ yticks([-0.4:0.2:0.6]);
leg = legend('location', 'northeast', 'FontSize', 8, 'NumColumns', 1); leg = legend('location', 'northeast', 'FontSize', 8, 'NumColumns', 1);
leg.ItemTokenSize(1) = 15; leg.ItemTokenSize(1) = 15;
% #+name: fig:test_id31_tomo_m2_1rpm_robust_hac_iff
% #+caption: Tomography experiment with a rotation velocity of $6\,\text{deg/s}$, and payload mass of 26kg. Errors in the $(x,y)$ plane are shown in (\subref{fig:test_id31_tomo_m2_1rpm_robust_hac_iff_fit}). The estimated eccentricity is represented by the black dashed circle. The errors with subtracted eccentricity are shown in (\subref{fig:test_id31_tomo_m2_1rpm_robust_hac_iff_fit_removed}).
% #+attr_latex: :options [htbp]
% #+begin_figure
% #+attr_latex: :caption \subcaption{\label{fig:test_id31_tomo_m2_1rpm_robust_hac_iff_fit}Errors in $(x,y)$ plane}
% #+attr_latex: :options {0.49\textwidth}
% #+begin_subfigure
% #+attr_latex: :scale 0.9
% [[file:figs/test_id31_tomo_m2_1rpm_robust_hac_iff_fit.png]]
% #+end_subfigure
% #+attr_latex: :caption \subcaption{\label{fig:test_id31_tomo_m2_1rpm_robust_hac_iff_fit_removed}Removed eccentricity}
% #+attr_latex: :options {0.49\textwidth}
% #+begin_subfigure
% #+attr_latex: :scale 0.9
% [[file:figs/test_id31_tomo_m2_1rpm_robust_hac_iff_fit_removed.png]]
% #+end_subfigure
% #+end_figure
% The residual motion (i.e. after compensating for eccentricity) in the $Y-Z$ is compared against the minimum beam size, as illustrated in Figure ref:fig:test_id31_tomo_Wz36_results.
% Results are indicating the NASS succeeds in keeping the sample's point of interest on the beam, except for the highest mass of $39\,\text{kg}$ for which the lateral motion is a bit too high.
% These experimental findings are consistent with the predictions from the tomography simulations presented in Section ref:ssec:test_id31_iff_hac_robustness.
%% Tomography experiment at 1rpm - Results in the YZ - All masses tested %% Tomography experiment at 1rpm - Results in the YZ - All masses tested
figure; figure;
tiledlayout(2, 2, 'TileSpacing', 'compact', 'Padding', 'None'); tiledlayout(2, 2, 'TileSpacing', 'compact', 'Padding', 'None');
@@ -205,14 +166,6 @@ xticks([-800:200:800]); yticks([-100:100:100]);
leg = legend('location', 'southeast', 'FontSize', 8, 'NumColumns', 1); leg = legend('location', 'southeast', 'FontSize', 8, 'NumColumns', 1);
leg.ItemTokenSize(1) = 15; leg.ItemTokenSize(1) = 15;
% #+name: fig:test_id31_tomo_Wz36_results
% #+caption: Measured errors in the $Y-Z$ plane during tomography experiments at $6\,\text{deg/s}$ for all considered payloads. In the open-loop case, the effect of eccentricity is removed from the data.
% #+RESULTS:
% [[file:figs/test_id31_tomo_Wz36_results.png]]
%% Estimate RMS of the errors while in closed-loop and open-loop - Tomography at 6deg/s %% Estimate RMS of the errors while in closed-loop and open-loop - Tomography at 6deg/s
% No mass % No mass
data_tomo_m0_Wz6.Dy_rms_cl = rms(detrend(data_tomo_m0_Wz6.Dy_int(i_m0+1e4:end), 0)); data_tomo_m0_Wz6.Dy_rms_cl = rms(detrend(data_tomo_m0_Wz6.Dy_int(i_m0+1e4:end), 0));
@@ -270,14 +223,6 @@ fun = @(theta)rms((data_tomo_m3_Wz6.Rx_int(1:i_m3) - (x0 + R*cos(data_tomo_m3_Wz
delta_theta = fminsearch(fun, 0); delta_theta = fminsearch(fun, 0);
data_tomo_m3_Wz6.Ry_rms_ol = rms(data_tomo_m3_Wz6.Ry_int(1:i_m3) - (y0 + R*sin(data_tomo_m3_Wz6.Rz(1:i_m3)+delta_theta))); data_tomo_m3_Wz6.Ry_rms_ol = rms(data_tomo_m3_Wz6.Ry_int(1:i_m3) - (y0 + R*sin(data_tomo_m3_Wz6.Rz(1:i_m3)+delta_theta)));
% Fast Tomography scans
% A tomography experiment was then performed with the highest rotational velocity of the Spindle: $180\,\text{deg/s}$[fn:test_id31_7].
% The trajectory of the point of interest during the fast tomography scan is shown in Figure ref:fig:test_id31_tomo_m0_30rpm_robust_hac_iff_exp.
% Although the experimental results closely mirror the simulation results (Figure ref:fig:test_id31_tomo_m0_30rpm_robust_hac_iff_sim), the actual performance was slightly lower than predicted.
% Nevertheless, even with this robust (i.e. conservative) HAC implementation, the system performance was already close to the specified requirements.
%% Experimental Results for Tomography at 180deg/s, no payload %% Experimental Results for Tomography at 180deg/s, no payload
data_tomo_m0_Wz180 = load('2023-08-17_15-26_tomography_30rpm_m0_robust.mat'); data_tomo_m0_Wz180 = load('2023-08-17_15-26_tomography_30rpm_m0_robust.mat');
@@ -334,27 +279,6 @@ xlim([-300, 300]); ylim([-100, 100]);
leg = legend('location', 'northeast', 'FontSize', 8, 'NumColumns', 1); leg = legend('location', 'northeast', 'FontSize', 8, 'NumColumns', 1);
leg.ItemTokenSize(1) = 15; leg.ItemTokenSize(1) = 15;
% #+name: fig:test_id31_tomo_m0_30rpm_robust_hac_iff_exp
% #+caption: Experimental results of tomography experiment at 180 deg/s without payload. The position error of the sample is shown in the XY (\subref{fig:test_id31_tomo_m0_30rpm_robust_hac_iff_exp_xy}) and YZ (\subref{fig:test_id31_tomo_m0_30rpm_robust_hac_iff_exp_yz}) planes.
% #+attr_latex: :options [htbp]
% #+begin_figure
% #+attr_latex: :caption \subcaption{\label{fig:test_id31_tomo_m0_30rpm_robust_hac_iff_exp_xy}XY plane}
% #+attr_latex: :options {0.49\textwidth}
% #+begin_subfigure
% #+attr_latex: :scale 0.9
% [[file:figs/test_id31_tomo_m0_30rpm_robust_hac_iff_exp_xy.png]]
% #+end_subfigure
% #+attr_latex: :caption \subcaption{\label{fig:test_id31_tomo_m0_30rpm_robust_hac_iff_exp_yz}YZ plane}
% #+attr_latex: :options {0.49\textwidth}
% #+begin_subfigure
% #+attr_latex: :scale 0.9
% [[file:figs/test_id31_tomo_m0_30rpm_robust_hac_iff_exp_yz.png]]
% #+end_subfigure
% #+end_figure
%% Estimate RMS of the errors while in closed-loop and open-loop - Tomography at 180deg/s %% Estimate RMS of the errors while in closed-loop and open-loop - Tomography at 180deg/s
% No mass % No mass
data_tomo_m0_Wz180.Dy_rms_cl = rms(detrend(data_tomo_m0_Wz180.Dy_int(i_m0+1e4:end), 0)); data_tomo_m0_Wz180.Dy_rms_cl = rms(detrend(data_tomo_m0_Wz180.Dy_int(i_m0+1e4:end), 0));
@@ -370,19 +294,6 @@ fun = @(theta)rms((data_tomo_m0_Wz180.Rx_int(1:i_m0) - (x0 + R*cos(data_tomo_m0_
delta_theta = fminsearch(fun, 0); delta_theta = fminsearch(fun, 0);
data_tomo_m0_Wz180.Ry_rms_ol = rms(data_tomo_m0_Wz180.Ry_int(1:i_m0) - (y0 + R*sin(data_tomo_m0_Wz180.Rz(1:i_m0)+delta_theta))); data_tomo_m0_Wz180.Ry_rms_ol = rms(data_tomo_m0_Wz180.Ry_int(1:i_m0) - (y0 + R*sin(data_tomo_m0_Wz180.Rz(1:i_m0)+delta_theta)));
% Cumulative Amplitude Spectra
% A comparative analysis was conducted using three tomography scans at $180,\text{deg/s}$ to evaluate the effectiveness of the HAC-LAC strategy in reducing positioning errors.
% The scans were performed under three conditions: open-loop, with decentralized IFF control, and with the complete HAC-LAC strategy.
% For these specific measurements, an enhanced high authority controller was optimized for low payload masses to meet the performance requirements.
% Figure ref:fig:test_id31_hac_cas_cl presents the cumulative amplitude spectra of the position errors for all three cases.
% The results reveal two distinct control contributions: the decentralized IFF effectively attenuates vibrations near the nano-hexapod suspension modes (an achievement not possible with HAC alone), while the high authority controller suppresses low-frequency vibrations primarily arising from Spindle guiding errors.
% Notably, the spectral patterns in Figure ref:fig:test_id31_hac_cas_cl closely resemble the cumulative amplitude spectra computed in the project's early stages.
% This experiment also illustrates that when needed, performance can be enhanced by designing controllers for specific experimental conditions rather than relying solely on robust controllers that can accommodate all payload ranges.
%% Jacobian to compute the motion in the X-Y-Z-Rx-Ry directions %% Jacobian to compute the motion in the X-Y-Z-Rx-Ry directions
J_int_to_X = [ 0 0 -0.787401574803149 -0.212598425196851 0; J_int_to_X = [ 0 0 -0.787401574803149 -0.212598425196851 0;
0.78740157480315 0.21259842519685 0 0 0; 0.78740157480315 0.21259842519685 0 0 0;
@@ -496,14 +407,6 @@ leg.ItemTokenSize(1) = 15;
xticks([1e0, 1e1, 1e2]); yticks([1e-9, 1e-8, 1e-7, 1e-6, 1e-5]); xticks([1e0, 1e1, 1e2]); yticks([1e-9, 1e-8, 1e-7, 1e-6, 1e-5]);
xlim([0.1, 5e2]); ylim([1e-10, 2e-5]); xlim([0.1, 5e2]); ylim([1e-10, 2e-5]);
% Reflectivity Scans
% <<ssec:test_id31_scans_reflectivity>>
% X-ray reflectivity measurements involve scanning thin structures, particularly solid/liquid interfaces, through the beam by varying the $R_y$ angle.
% In this experiment, a $R_y$ scan was executed at a rotational velocity of $100,\mu rad/s$, and the closed-loop positioning errors were monitored (Figure ref:fig:test_id31_reflectivity).
% The results confirmed that the NASS successfully maintained the point of interest within the specified beam parameters throughout the scanning process.
%% Load data for the reflectivity scan %% Load data for the reflectivity scan
data_ry = load("2023-08-18_15-24_first_reflectivity_m0.mat"); data_ry = load("2023-08-18_15-24_first_reflectivity_m0.mat");
data_ry.time = Ts*[0:length(data_ry.Ry_int)-1]; data_ry.time = Ts*[0:length(data_ry.Ry_int)-1];
@@ -564,18 +467,6 @@ xlim([0, 6.2]);
ylim([-310, 310]); ylim([-310, 310]);
xticks([0:2:6]); xticks([0:2:6]);
% Step by Step $D_z$ motion
% The vertical step motion was performed exclusively with the nano-hexapod.
% Testing was conducted across step sizes ranging from $10\,nm$ to $1\,\mu m$.
% Results are presented in Figure ref:fig:test_id31_dz_mim_steps.
% The system successfully resolved 10nm steps (red curve in Figure ref:fig:test_id31_dz_mim_10nm_steps) if a 50ms integration time is considered for the detectors, which is compatible with many experimental requirements.
% In step-by-step scanning procedures, the settling time is a critical parameter as it significantly affects the total experiment duration.
% The system achieved a response time of approximately $70\,ms$ to reach the target position (within $\pm 20\,nm$), as demonstrated by the $1\,\mu m$ step response in Figure ref:fig:test_id31_dz_mim_1000nm_steps.
% The settling duration typically decreases for smaller step sizes.
%% Load Dz steps data %% Load Dz steps data
data_dz_steps_10nm = load("2023-08-18_14-57_dz_mim_10_nm.mat"); data_dz_steps_10nm = load("2023-08-18_14-57_dz_mim_10_nm.mat");
data_dz_steps_10nm.time = Ts*[0:length(data_dz_steps_10nm.Dz_int)-1]; data_dz_steps_10nm.time = Ts*[0:length(data_dz_steps_10nm.Dz_int)-1];
@@ -635,14 +526,6 @@ ylim([-0.1, 1.6])
xticks([0, 70]) xticks([0, 70])
yticks([0, 1]) yticks([0, 1])
% Continuous $D_z$ motion: Dirty Layer Scans
% For these and subsequent experiments, the NASS performs "ramp scans" (constant velocity scans).
% To eliminate tracking errors, the feedback controller incorporates two integrators, compensating for the plant's lack of integral action at low frequencies.
% Initial testing at $10,\mu m/s$ demonstrated positioning errors well within specifications (indicated by dashed lines in Figure ref:fig:test_id31_dz_scan_10ums).
%% Dirty layer scans - 10um/s %% Dirty layer scans - 10um/s
data_dz_10ums = load("2023-08-18_15-33_dirty_layer_m0_small.mat"); data_dz_10ums = load("2023-08-18_15-33_dirty_layer_m0_small.mat");
data_dz_10ums.time = Ts*[0:length(data_dz_10ums.Dz_int)-1]; data_dz_10ums.time = Ts*[0:length(data_dz_10ums.Dz_int)-1];
@@ -719,37 +602,6 @@ ylabel('$R_y$ error [$\mu$rad]')
xlim([0, 2.2]); xlim([0, 2.2]);
ylim([-2, 2]); ylim([-2, 2]);
% #+name: fig:test_id31_dz_scan_10ums
% #+caption: $D_z$ scan at a velocity of $10\,\mu m/s$. $D_z$ setpoint, measured position and error are shown in (\subref{fig:test_id31_dz_scan_10ums_dz}). Errors in $D_y$ and $R_y$ are respectively shown in (\subref{fig:test_id31_dz_scan_10ums_dy}) and (\subref{fig:test_id31_dz_scan_10ums_ry})
% #+attr_latex: :options [htbp]
% #+begin_figure
% #+attr_latex: :caption \subcaption{\label{fig:test_id31_dz_scan_10ums_dy}$D_y$}
% #+attr_latex: :options {0.33\textwidth}
% #+begin_subfigure
% #+attr_latex: :scale 1
% [[file:figs/test_id31_dz_scan_10ums_dy.png]]
% #+end_subfigure
% #+attr_latex: :caption \subcaption{\label{fig:test_id31_dz_scan_10ums_dz}$D_z$}
% #+attr_latex: :options {0.33\textwidth}
% #+begin_subfigure
% #+attr_latex: :scale 1
% [[file:figs/test_id31_dz_scan_10ums_dz.png]]
% #+end_subfigure
% #+attr_latex: :caption \subcaption{\label{fig:test_id31_dz_scan_10ums_ry}$R_y$}
% #+attr_latex: :options {0.33\textwidth}
% #+begin_subfigure
% #+attr_latex: :scale 1
% [[file:figs/test_id31_dz_scan_10ums_ry.png]]
% #+end_subfigure
% #+end_figure
% A subsequent scan at $100,\mu m/s$ - the maximum velocity for high-precision $D_z$ scans[fn:test_id31_8] - maintains positioning errors within specifications during the constant velocity phase, with deviations occurring only during acceleration and deceleration phases (Figure ref:fig:test_id31_dz_scan_100ums).
% Since detectors typically operate only during the constant velocity phase, these transient deviations do not compromise the measurement quality.
% However, performance during acceleration phases could be enhanced through the implementation of feedforward control.
%% Dz scan at 100um/s - Lateral error %% Dz scan at 100um/s - Lateral error
figure; figure;
hold on; hold on;
@@ -799,18 +651,6 @@ ylabel('$R_y$ error [$\mu$rad]')
xlim([0, 2.2]); xlim([0, 2.2]);
ylim([-2, 2]) ylim([-2, 2])
% Slow scan
% Initial testing utilized a scanning velocity of $10,\mu m/s$, which is typical for these experiments.
% Figure ref:fig:test_id31_dy_10ums compares the positioning errors between open-loop (without NASS) and closed-loop operation.
% In the scanning direction, open-loop measurements reveal periodic errors (Figure ref:fig:test_id31_dy_10ums_dy) attributable to the $T_y$ stage's stepper motor.
% These micro-stepping errors, which are inherent to stepper motor operation, occur 200 times per motor rotation with approximately $1\,\text{mrad}$ angular error amplitude.
% Given the $T_y$ stage's lead screw pitch of $2\,mm$, these errors manifest as $10\,\mu m$ periodic oscillations with $\approx 300\,nm$ amplitude, which can indeed be seen in the open-loop measurements (Figure ref:fig:test_id31_dy_10ums_dy).
% In the vertical direction (Figure ref:fig:test_id31_dy_10ums_dz), open-loop errors likely stem from metrology measurement error because the top interferometer points at a spherical target surface (see Figure ref:fig:test_id31_xy_map_sphere).
% Under closed-loop control, positioning errors remain within specifications in all directions.
%% Slow Ty scan (10um/s) - OL %% Slow Ty scan (10um/s) - OL
data_ty_ol_10ums = load("2023-08-21_20-05_ty_scan_m1_open_loop_slow.mat"); data_ty_ol_10ums = load("2023-08-21_20-05_ty_scan_m1_open_loop_slow.mat");
data_ty_ol_10ums.time = Ts*[0:length(data_ty_ol_10ums.Dy_int)-1]; data_ty_ol_10ums.time = Ts*[0:length(data_ty_ol_10ums.Dy_int)-1];
@@ -868,19 +708,6 @@ ylim([-10, 10])
leg = legend('location', 'northwest', 'FontSize', 8, 'NumColumns', 1); leg = legend('location', 'northwest', 'FontSize', 8, 'NumColumns', 1);
leg.ItemTokenSize(1) = 15; leg.ItemTokenSize(1) = 15;
% Fast Scan
% The system performance was evaluated at an increased scanning velocity of $100\,\mu m/s$, and the results are presented in Figure ref:fig:test_id31_dy_100ums.
% At this velocity, the micro-stepping errors generate $10\,\text{Hz}$ vibrations, which are further amplified by micro-station resonances.
% These vibrations exceeded the NASS feedback controller bandwidth, resulting in limited attenuation under closed-loop control.
% This limitation exemplifies why stepper motors are suboptimal for "long-stroke/short-stroke" systems requiring precise scanning performance [[cite:&dehaeze22_fastj_uhv]].
% Two potential solutions exist for improving high-velocity scanning performance.
% First, the $T_y$ stage's stepper motor could be replaced by a three-phase torque motor.
% Alternatively, since closed-loop errors in $D_z$ and $R_y$ directions remain within specifications (Figures ref:fig:test_id31_dy_100ums_dz and ref:fig:test_id31_dy_100ums_ry), detector triggering could be based on measured $D_y$ position rather than time or $T_y$ setpoint, reducing sensitivity to $D_y$ vibrations.
% For applications requiring small $D_y$ scans, the nano-hexapod can be used exclusively, although with limited stroke capability.
%% Fast Ty scan (100um/s) - OL %% Fast Ty scan (100um/s) - OL
data_ty_ol_100ums = load("2023-08-21_20-05_ty_scan_m1_open_loop.mat"); data_ty_ol_100ums = load("2023-08-21_20-05_ty_scan_m1_open_loop.mat");
data_ty_ol_100ums.time = Ts*[0:length(data_ty_ol_100ums.Dy_int)-1]; data_ty_ol_100ums.time = Ts*[0:length(data_ty_ol_100ums.Dy_int)-1];
@@ -939,33 +766,6 @@ ylim([-10, 10])
leg = legend('location', 'northwest', 'FontSize', 8, 'NumColumns', 1); leg = legend('location', 'northwest', 'FontSize', 8, 'NumColumns', 1);
leg.ItemTokenSize(1) = 15; leg.ItemTokenSize(1) = 15;
% #+name: fig:test_id31_dy_100ums
% #+caption: Open-Loop (in blue) and Closed-loop (i.e. using the NASS, in red) during a $100\,\mu m/s$ scan with the $T_y$ stage. Errors in $D_y$ is shown in (\subref{fig:test_id31_dy_100ums_dy}).
% #+attr_latex: :options [htbp]
% #+begin_figure
% #+attr_latex: :caption \subcaption{\label{fig:test_id31_dy_100ums_dy} $D_y$}
% #+attr_latex: :options {0.33\textwidth}
% #+begin_subfigure
% #+attr_latex: :scale 1
% [[file:figs/test_id31_dy_100ums_dy.png]]
% #+end_subfigure
% #+attr_latex: :caption \subcaption{\label{fig:test_id31_dy_100ums_dz} $D_z$}
% #+attr_latex: :options {0.33\textwidth}
% #+begin_subfigure
% #+attr_latex: :scale 1
% [[file:figs/test_id31_dy_100ums_dz.png]]
% #+end_subfigure
% #+attr_latex: :caption \subcaption{\label{fig:test_id31_dy_100ums_ry} $R_y$}
% #+attr_latex: :options {0.33\textwidth}
% #+begin_subfigure
% #+attr_latex: :scale 1
% [[file:figs/test_id31_dy_100ums_ry.png]]
% #+end_subfigure
% #+end_figure
%% Compute errors for Dy scans %% Compute errors for Dy scans
i_ty_ol_10ums = data_ty_ol_10ums.Ty > data_ty_ol_10ums.Ty(1) & data_ty_ol_10ums.Ty < data_ty_ol_10ums.Ty(end); i_ty_ol_10ums = data_ty_ol_10ums.Ty > data_ty_ol_10ums.Ty(1) & data_ty_ol_10ums.Ty < data_ty_ol_10ums.Ty(end);
i_ty_cl_10ums = data_ty_cl_10ums.Ty > data_ty_cl_10ums.Ty(1) & data_ty_cl_10ums.Ty < data_ty_cl_10ums.Ty(end); i_ty_cl_10ums = data_ty_cl_10ums.Ty > data_ty_cl_10ums.Ty(1) & data_ty_cl_10ums.Ty < data_ty_cl_10ums.Ty(end);
@@ -989,15 +789,6 @@ data_ty_cl_100ums.Dy_rms = rms(detrend(data_ty_cl_100ums.e_dy(i_ty_cl_100ums), 0
data_ty_cl_100ums.Dz_rms = rms(detrend(data_ty_cl_100ums.e_dz(i_ty_cl_100ums), 0)); data_ty_cl_100ums.Dz_rms = rms(detrend(data_ty_cl_100ums.e_dz(i_ty_cl_100ums), 0));
data_ty_cl_100ums.Ry_rms = rms(detrend(data_ty_cl_100ums.e_ry(i_ty_cl_100ums), 0)); data_ty_cl_100ums.Ry_rms = rms(detrend(data_ty_cl_100ums.e_ry(i_ty_cl_100ums), 0));
% Diffraction Tomography
% <<ssec:test_id31_scans_diffraction_tomo>>
% In diffraction tomography experiments, the micro-station executes combined motions: continuous rotation around the $R_z$ axis while performing lateral scans along $D_y$.
% For this validation, the spindle maintained a constant rotational velocity of $6\,\text{deg/s}$ while the nano-hexapod executed the lateral scanning motion.
% To avoid high-frequency vibrations typically induced by the stepper motor, the $T_y$ stage was not utilized, which constrained the scanning range to approximately $\pm 100\,\mu m/s$.
% The system performance was evaluated at three lateral scanning velocities: $0.1\,mm/s$, $0.5\,mm/s$, and $1\,mm/s$. Figure ref:fig:test_id31_diffraction_tomo_setpoint presents both the $D_y$ position setpoints and the corresponding measured $D_y$ positions for all tested velocities.
%% 100um/s - Robust controller %% 100um/s - Robust controller
data_dt_100ums = load("2023-08-18_17-12_diffraction_tomo_m0.mat"); data_dt_100ums = load("2023-08-18_17-12_diffraction_tomo_m0.mat");
t = Ts*[0:length(data_dt_100ums.Dy_int)-1]; t = Ts*[0:length(data_dt_100ums.Dy_int)-1];
@@ -1038,20 +829,6 @@ xlabel('Time [s]');
ylabel('$D_y$ position [$\mu$m]') ylabel('$D_y$ position [$\mu$m]')
legend('location', 'southeast', 'FontSize', 8, 'NumColumns', 1); legend('location', 'southeast', 'FontSize', 8, 'NumColumns', 1);
% #+name: fig:test_id31_diffraction_tomo_setpoint
% #+caption: Dy motion for several configured velocities
% #+RESULTS:
% [[file:figs/test_id31_diffraction_tomo_setpoint.png]]
% The positioning errors measured along $D_y$, $D_z$, and $R_y$ directions are displayed in Figure ref:fig:test_id31_diffraction_tomo.
% The system maintained positioning errors within specifications for both $D_z$ and $R_y$ (Figures ref:fig:test_id31_diffraction_tomo_dz and ref:fig:test_id31_diffraction_tomo_ry).
% However, the lateral positioning errors exceeded specifications during the acceleration and deceleration phases (Figure ref:fig:test_id31_diffraction_tomo_dy).
% These large errors occurred only during $\approx 20\,ms$ intervals; thus, the issue could be addressed by implementing a corresponding delay in detector integration.
% Alternatively, a feedforward controller could improve the lateral positioning accuracy during these transient phases.
%% Diffraction Tomography - Dy errors for several configured velocities %% Diffraction Tomography - Dy errors for several configured velocities
figure; figure;
hold on; hold on;
@@ -1108,33 +885,6 @@ ylabel('$R_y$ position [$\mu$rad]')
leg = legend('location', 'southwest', 'FontSize', 8, 'NumColumns', 1); leg = legend('location', 'southwest', 'FontSize', 8, 'NumColumns', 1);
leg.ItemTokenSize(1) = 15; leg.ItemTokenSize(1) = 15;
% #+name: fig:test_id31_diffraction_tomo
% #+caption: Diffraction tomography scans (combined $R_z$ and $D_y$ motions) at several $D_y$ velocities ($R_z$ rotational velocity is $6\,\text{deg/s}$).
% #+attr_latex: :options [htbp]
% #+begin_figure
% #+attr_latex: :caption \subcaption{\label{fig:test_id31_diffraction_tomo_dy} $D_y$}
% #+attr_latex: :options {0.33\textwidth}
% #+begin_subfigure
% #+attr_latex: :scale 1
% [[file:figs/test_id31_diffraction_tomo_dy.png]]
% #+end_subfigure
% #+attr_latex: :caption \subcaption{\label{fig:test_id31_diffraction_tomo_dz} $D_z$}
% #+attr_latex: :options {0.33\textwidth}
% #+begin_subfigure
% #+attr_latex: :scale 1
% [[file:figs/test_id31_diffraction_tomo_dz.png]]
% #+end_subfigure
% #+attr_latex: :caption \subcaption{\label{fig:test_id31_diffraction_tomo_ry} $R_y$}
% #+attr_latex: :options {0.33\textwidth}
% #+begin_subfigure
% #+attr_latex: :scale 1
% [[file:figs/test_id31_diffraction_tomo_ry.png]]
% #+end_subfigure
% #+end_figure
%% Computation of errors during diffraction tomography experiments %% Computation of errors during diffraction tomography experiments
% Ignore acceleration and deceleration phases % Ignore acceleration and deceleration phases
acc_dt = 20e-3; % Acceleration phase to remove [s] acc_dt = 20e-3; % Acceleration phase to remove [s]
@@ -1184,29 +934,128 @@ data_dt_1000ums.Dy_rms_cl = rms(detrend(data_dt_1000ums.Dy_int(i_dt_1000ums)-dat
data_dt_1000ums.Dz_rms_cl = rms(detrend(data_dt_1000ums.Dz_int(i_dt_1000ums), 0)); data_dt_1000ums.Dz_rms_cl = rms(detrend(data_dt_1000ums.Dz_int(i_dt_1000ums), 0));
data_dt_1000ums.Ry_rms_cl = rms(detrend(data_dt_1000ums.Ry_int(i_dt_1000ums), 0)); data_dt_1000ums.Ry_rms_cl = rms(detrend(data_dt_1000ums.Ry_int(i_dt_1000ums), 0));
% Conclusion %% Complementary Filter Control - Experimental Validation
% :PROPERTIES: % Parameters to analyze results in the frequency domain
% :UNNUMBERED: t Ts = 1e-4; % Sampling Time [s]
% :END: Nfft = floor(2.0/Ts);
% <<ssec:test_id31_scans_conclusion>> win = hanning(Nfft);
Noverlap = floor(Nfft/2);
% A comprehensive series of experimental validations was conducted to evaluate the NASS performance over a wide range of typical scientific experiments. %% Closed-Loop performance identification (S and T transfer functions)
% The system demonstrated robust performance in most scenarios, with positioning errors generally remaining within specified tolerances (30 nm RMS in $D_y$, 15 nm RMS in $D_z$, and 250 nrad RMS in $R_y$). % Different parameters w0 in different directions
data = load("2023-08-21_14-09_m0_cf_inv_tustin.mat");
% For tomography experiments, the NASS successfully maintained good positioning accuracy at rotational velocities up to $180\,\text{deg/s}$ with light payloads, though performance degraded somewhat with heavier masses. [S_dy, f] = tfestimate(data.Dy.id_cl, data.Dy.e_dy, win, Noverlap, Nfft, 1/Ts);
% The HAC-LAC control architecture proved particularly effective, with the decentralized IFF providing damping of nano-hexapod suspension modes, while the high authority controller addressed low-frequency disturbances. [T_dy, ~] = tfestimate(data.Dy.id_cl, data.Dy.Dy_int, win, Noverlap, Nfft, 1/Ts);
% The vertical scanning capabilities were validated in both step-by-step and continuous motion modes. [S_dz, ~] = tfestimate(data.Dz.id_cl, data.Dz.e_dz, win, Noverlap, Nfft, 1/Ts);
% The system successfully resolved 10 nm steps with 50 ms detector integration time, while maintaining positioning accuracy during continuous scans at speeds up to $100\,\mu m/s$. [T_dz, ~] = tfestimate(data.Dz.id_cl, data.Dz.Dz_int, win, Noverlap, Nfft, 1/Ts);
% For lateral scanning, the system performed well at moderate speeds ($10\,\mu m/s$) but showed limitations at higher velocities ($100\,\mu m/s$) due to stepper motor-induced vibrations in the $T_y$ stage. [S_ry, ~] = tfestimate(data.Ry.id_cl, data.Ry.e_ry, win, Noverlap, Nfft, 1/Ts);
[T_ry, ~] = tfestimate(data.Ry.id_cl, data.Ry.Ry_int, win, Noverlap, Nfft, 1/Ts);
% The most challenging test case - diffraction tomography combining rotation and lateral scanning - demonstrated the system's ability to maintain vertical and angular stability while highlighting some limitations in lateral positioning during rapid accelerations. %% Obtained Closed-Loop transfer functions - Different Complementary filters for Dy and Dz
% These limitations could be addressed through feedforward control or alternative detector triggering strategies. figure;
hold on;
plot(f, abs(S_dy), '-', 'color', colors(1,:),'DisplayName', '$S_{D_y}$');
plot(f, abs(S_dz), '-', 'color', colors(2,:),'DisplayName', '$S_{D_z}$');
plot(f, abs(S_ry), '-', 'color', colors(3,:),'DisplayName', '$S_{R_y}$');
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
xlabel('Frequency [Hz]'); ylabel('Magnitude');
ylim([1e-3, 5]);
xlim([1, 1e3]);
leg = legend('location', 'southeast', 'FontSize', 8, 'NumColumns', 1);
leg.ItemTokenSize(1) = 18;
% Overall, the experimental results validate the effectiveness of the developed control architecture and demonstrate that the NASS meets most design specifications across a wide range of operating conditions (summarized in Table ref:tab:test_id31_experiments_results_summary). %% Effect of a change of complementary filter parameter alpha
% The identified limitations, primarily related to high-speed lateral scanning and heavy payload handling, provide clear directions for future improvements. % w0 = 10, alpha = 2
data_a2 = load("2023-08-21_17-56_m2_cf_10Hz_a2.mat");
[S_a2, ~] = tfestimate(data_a2.Dy.id_cl, data_a2.Dy.e_dy, win, Noverlap, Nfft, 1/Ts);
[T_a2, ~] = tfestimate(data_a2.Dy.id_cl, data_a2.Dy.Dy_int, win, Noverlap, Nfft, 1/Ts);
% Analytical formulas
w0 = 2*pi*10;
alpha = 2;
Hh_a2 = (s/w0)^2*((s/w0)+1+alpha)/(((s/w0)+1)*((s/w0)^2 + alpha*(s/w0) + 1));
Hl_a2 = ((1+alpha)*(s/w0)+1)/(((s/w0)+1)*((s/w0)^2 + alpha*(s/w0) + 1));
% w0 = 10, alpha = 0.5
data_a05 = load("2023-08-21_17-58_m2_cf_10Hz_a05.mat");
[S_a05, ~] = tfestimate(data_a05.Dz.id_cl, data_a05.Dz.e_dz, win, Noverlap, Nfft, 1/Ts);
[T_a05, ~] = tfestimate(data_a05.Dz.id_cl, data_a05.Dz.Dz_int, win, Noverlap, Nfft, 1/Ts);
% Analytical formulas
w0 = 2*pi*10;
alpha = 0.5;
Hh_a05 = (s/w0)^2*((s/w0)+1+alpha)/(((s/w0)+1)*((s/w0)^2 + alpha*(s/w0) + 1));
Hl_a05 = ((1+alpha)*(s/w0)+1)/(((s/w0)+1)*((s/w0)^2 + alpha*(s/w0) + 1));
%% Obtained Closed-Loop transfer functions - Effect of changing alpha
figure;
hold on;
plot(freqs, abs(squeeze(freqresp(Hh_a2, freqs, 'Hz'))), '--', 'color', colors(1,:),'DisplayName', '$\alpha = 2$, $H_H$, $H_L$');
plot(f, abs(S_a2), '-', 'color', [colors(1,:), 0.5], 'linewidth', 2.5,'DisplayName', '$\alpha = 2$, $S$, $T$');
plot(freqs, abs(squeeze(freqresp(Hh_a05, freqs, 'Hz'))), '--', 'color', colors(2,:),'DisplayName', '$\alpha = 0.5$, $H_H$, $H_L$');
plot(f, abs(S_a05), '-', 'color', [colors(2,:), 0.5], 'linewidth', 2.5,'DisplayName', '$\alpha = 0.5$, $S$, $T$');
plot(freqs, abs(squeeze(freqresp(Hl_a2, freqs, 'Hz'))), '--', 'color', colors(1,:), 'HandleVisibility', 'off');
plot(f, abs(T_a2), '-', 'color', [colors(1,:), 0.5], 'linewidth', 2.5, 'HandleVisibility', 'off');
plot(freqs, abs(squeeze(freqresp(Hl_a05, freqs, 'Hz'))), '--', 'color', colors(2,:), 'HandleVisibility', 'off');
plot(f, abs(T_a05), '-', 'color', [colors(2,:), 0.5], 'linewidth', 2.5, 'HandleVisibility', 'off');
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
xlabel('Frequency [Hz]'); ylabel('Magnitude');
xlim([1, 1e3]);
ylim([1e-3, 5]);
leg = legend('location', 'south', 'FontSize', 8, 'NumColumns', 2);
leg.ItemTokenSize(1) = 18;
%% Trying high bandwidth controllers - 60Hz
% Z direction
data = load("2023-08-21_14-19_m0_cf_inv_tustin_Dz_60Hz_a_20.mat");
[S_dz, ~] = tfestimate(data.Dz.id_cl, data.Dz.e_dz, win, Noverlap, Nfft, 1/Ts);
[T_dz, ~] = tfestimate(data.Dz.id_cl, data.Dz.Dz_int, win, Noverlap, Nfft, 1/Ts);
% Y direction
data = load("2023-08-21_14-20_m0_cf_inv_tustin_Dy_60Hz_a_20.mat");
[S_dy, ~] = tfestimate(data.Dy.id_cl, data.Dy.e_dy, win, Noverlap, Nfft, 1/Ts);
[T_dy, ~] = tfestimate(data.Dy.id_cl, data.Dy.Dy_int, win, Noverlap, Nfft, 1/Ts);
% Analytical formulas
w0 = 2*pi*60;
alpha = 2;
Hh_60Hz = (s/w0)^2*((s/w0)+1+alpha)/(((s/w0)+1)*((s/w0)^2 + alpha*(s/w0) + 1));
Hl_60Hz = ((1+alpha)*(s/w0)+1)/(((s/w0)+1)*((s/w0)^2 + alpha*(s/w0) + 1));
%% Bode plot of the Weighting filters and Obtained complementary filters
figure;
hold on;
plot(f, abs(S_dy), '-', 'color', colors(1,:), 'DisplayName', '$S$, $D_y$');
plot(f, abs(S_dz), '-', 'color', colors(2,:), 'DisplayName', '$S$, $D_z$');
plot(freqs, abs(squeeze(freqresp(Hh_60Hz, freqs, 'Hz'))), 'k--','DisplayName', '$H_H$');
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
xlabel('Frequency [Hz]'); ylabel('Magnitude');
xlim([1, 1e3]);
ylim([3e-4, 5]);
leg = legend('location', 'southeast', 'FontSize', 8, 'NumColumns', 1);
leg.ItemTokenSize(1) = 18;
%% Bode plot of the Weighting filters and Obtained complementary filters
figure;
hold on;
plot(f, abs(T_dy), '-', 'color', colors(1,:), 'DisplayName', '$T$, $D_y$');
plot(f, abs(T_dz), '-', 'color', colors(2,:), 'DisplayName', '$T$, $D_z$');
plot(freqs, abs(squeeze(freqresp(Hl_60Hz, freqs, 'Hz'))), 'k--','DisplayName', '$H_L$');
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
xlabel('Frequency [Hz]'); ylabel('Magnitude');
xlim([1, 1e3]);
ylim([3e-4, 5]);
leg = legend('location', 'southwest', 'FontSize', 8, 'NumColumns', 1);
leg.ItemTokenSize(1) = 18;
%% Summary of results %% Summary of results
% 1e9*data_tomo_m0_Wz6.Dy_rms_ol, 1e9*data_tomo_m0_Wz6.Dz_rms_ol, 1e6*data_tomo_m0_Wz6.Ry_rms_ol; % Tomo - OL - 6deg/s - 0kg % 1e9*data_tomo_m0_Wz6.Dy_rms_ol, 1e9*data_tomo_m0_Wz6.Dz_rms_ol, 1e6*data_tomo_m0_Wz6.Ry_rms_ol; % Tomo - OL - 6deg/s - 0kg

View File

@@ -22,7 +22,7 @@
#+BIND: org-latex-bib-compiler "biber" #+BIND: org-latex-bib-compiler "biber"
#+PROPERTY: header-args:matlab :session *MATLAB* #+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+ :exports none
#+PROPERTY: header-args:matlab+ :results none #+PROPERTY: header-args:matlab+ :results none
#+PROPERTY: header-args:matlab+ :eval no-export #+PROPERTY: header-args:matlab+ :eval no-export
@@ -685,9 +685,9 @@ The remaining errors after alignment are in the order of $\pm5\,\mu\text{rad}$ i
#+begin_src matlab #+begin_src matlab
%% Angular alignment %% Angular alignment
% Load Data % Load Data
data_it0 = h5scan(data_dir, 'alignment', 'h1rx_h1ry', 1); data_it0 = h5scan('alignment_h1rx_h1ry', 1);
data_it1 = h5scan(data_dir, 'alignment', 'h1rx_h1ry_0002', 3); data_it1 = h5scan('alignment_h1rx_h1ry_0002', 3);
data_it2 = h5scan(data_dir, 'alignment', 'h1rx_h1ry_0002', 5); data_it2 = h5scan('alignment_h1rx_h1ry_0002', 5);
% Offset wrong points % Offset wrong points
i_it0 = find(abs(data_it0.Rx_int_filtered(2:end)-data_it0.Rx_int_filtered(1:end-1))>1e-5); i_it0 = find(abs(data_it0.Rx_int_filtered(2:end)-data_it0.Rx_int_filtered(1:end-1))>1e-5);
@@ -728,8 +728,8 @@ exportFig('figs/test_id31_metrology_align_rx_ry.pdf', 'width', 'half', 'height',
#+begin_src matlab #+begin_src matlab
%% Eccentricity alignment %% Eccentricity alignment
% Load Data % Load Data
data_it0 = h5scan(data_dir, 'alignment', 'h1rx_h1ry_0002', 5); data_it0 = h5scan('alignment_h1rx_h1ry_0002', 5);
data_it1 = h5scan(data_dir, 'alignment', 'h1dx_h1dy', 1); data_it1 = h5scan('alignment_h1dx_h1dy', 1);
% Offset wrong points % Offset wrong points
i_it0 = find(abs(data_it0.Dy_int_filtered(2:end)-data_it0.Dy_int_filtered(1:end-1))>1e-5); i_it0 = find(abs(data_it0.Dy_int_filtered(2:end)-data_it0.Dy_int_filtered(1:end-1))>1e-5);
@@ -793,7 +793,7 @@ The obtained lateral acceptance for pure displacements in any direction is estim
% This is estimated by moving the spheres using the micro-hexapod % This is estimated by moving the spheres using the micro-hexapod
% Dx % Dx
data_dx = h5scan(data_dir, 'metrology_acceptance_new_align', 'dx', 1); data_dx = h5scan('metrology_acceptance_new_align_dx', 1);
dx_acceptance = zeros(5,1); dx_acceptance = zeros(5,1);
@@ -809,7 +809,7 @@ for i = [1:size(dx_acceptance, 1)]
end end
% Dy % Dy
data_dy = h5scan(data_dir, 'metrology_acceptance_new_align', 'dy', 1); data_dy = h5scan('metrology_acceptance_new_align_dy', 1);
dy_acceptance = zeros(5,1); dy_acceptance = zeros(5,1);
@@ -825,7 +825,7 @@ for i = [1:size(dy_acceptance, 1)]
end end
% Dz % Dz
data_dz = h5scan(data_dir, 'metrology_acceptance_new_align', 'dz', 1); data_dz = h5scan('metrology_acceptance_new_align_dz', 1);
dz_acceptance = zeros(5,1); dz_acceptance = zeros(5,1);
@@ -920,7 +920,7 @@ exportFig('figs/test_id31_interf_noise.pdf', 'width', 'half', 'height', 'normal'
#+begin_src matlab #+begin_src matlab
%% X-Y scan with the micro-hexapod, and record of the vertical interferometer %% X-Y scan with the micro-hexapod, and record of the vertical interferometer
data = h5scan(data_dir, 'metrology_acceptance', 'after_int_align_meshXY', 1); data = h5scan('metrology_acceptance_after_int_align_meshXY', 1);
x = 1e3*detrend(data.h1tx, 0); % [um] x = 1e3*detrend(data.h1tx, 0); % [um]
y = 1e3*detrend(data.h1ty, 0); % [um] y = 1e3*detrend(data.h1ty, 0); % [um]
@@ -1305,10 +1305,10 @@ Results shown in Figure ref:fig:test_id31_Rz_align_correct are indeed indicating
#+begin_src matlab #+begin_src matlab
%% Load Data %% Load Data
data_1_dx = h5scan(data_dir, 'align_int_enc_Rz', 'tx_first_scan', 2); data_1_dx = h5scan('align_int_enc_Rz_tx_first_scan', 2);
data_1_dy = h5scan(data_dir, 'align_int_enc_Rz', 'tx_first_scan', 3); data_1_dy = h5scan('align_int_enc_Rz_tx_first_scan', 3);
data_2_dx = h5scan(data_dir, 'align_int_enc_Rz', 'verif-after-correct-offset', 1); data_2_dx = h5scan('align_int_enc_Rz_verif-after-correct-offset', 1);
data_2_dy = h5scan(data_dir, 'align_int_enc_Rz', 'verif-after-correct-offset', 2); data_2_dy = h5scan('align_int_enc_Rz_verif-after-correct-offset', 2);
#+end_src #+end_src
#+begin_src matlab #+begin_src matlab
@@ -2981,7 +2981,7 @@ The control strategy here is to apply a diagonal control in the frame of the str
To conduct this interaction analysis, the acrfull:rga $\bm{\Lambda_G}$ is first computed using eqref:eq:test_id31_rga for the plant dynamics identified with the multiple payload masses. To conduct this interaction analysis, the acrfull:rga $\bm{\Lambda_G}$ is first computed using eqref:eq:test_id31_rga for the plant dynamics identified with the multiple payload masses.
\begin{equation}\label{eq:test_id31_rga} \begin{equation}\label{eq:test_id31_rga}
\bm{\Lambda_G}(\omega) = \bm{G}(j\omega) \star \left(\bm{G}(j\omega)^{-1}\right)^{T}, \quad (\star \text{ means element wise multiplication}) \bm{\Lambda_G}(\omega) = \bm{G}(j\omega) \star \left(\bm{G}(j\omega)^{-1}\right)^{\intercal}, \quad (\star \text{ means element wise multiplication})
\end{equation} \end{equation}
Then, acrshort:rga numbers are computed using eqref:eq:test_id31_rga_number and are use as a metric for interaction [[cite:&skogestad07_multiv_feedb_contr chapt. 3.4]]. Then, acrshort:rga numbers are computed using eqref:eq:test_id31_rga_number and are use as a metric for interaction [[cite:&skogestad07_multiv_feedb_contr chapt. 3.4]].
@@ -3104,10 +3104,10 @@ tiledlayout(3, 1, 'TileSpacing', 'Compact', 'Padding', 'None');
ax1 = nexttile([2,1]); ax1 = nexttile([2,1]);
hold on; hold on;
plot(f(2:end), abs(G_hac_m0_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f(2:end), 'Hz'))), 'color', colors(1,:), 'DisplayName', '$0$ kg'); plot(f, abs(G_hac_m0_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f, 'Hz'))), 'color', colors(1,:), 'DisplayName', '$0$ kg');
plot(f(2:end), abs(G_hac_m1_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f(2:end), 'Hz'))), 'color', colors(2,:), 'DisplayName', '$13$ kg'); plot(f, abs(G_hac_m1_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f, 'Hz'))), 'color', colors(2,:), 'DisplayName', '$13$ kg');
plot(f(2:end), abs(G_hac_m2_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f(2:end), 'Hz'))), 'color', colors(3,:), 'DisplayName', '$26$ kg'); plot(f, abs(G_hac_m2_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f, 'Hz'))), 'color', colors(3,:), 'DisplayName', '$26$ kg');
plot(f(2:end), abs(G_hac_m3_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f(2:end), 'Hz'))), 'color', colors(4,:), 'DisplayName', '$39$ kg'); plot(f, abs(G_hac_m3_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f, 'Hz'))), 'color', colors(4,:), 'DisplayName', '$39$ kg');
xline(5, '--', 'linewidth', 1, 'color', [0,0,0,0.2], 'HandleVisibility', 'off') xline(5, '--', 'linewidth', 1, 'color', [0,0,0,0.2], 'HandleVisibility', 'off')
hold off; hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
@@ -3118,10 +3118,10 @@ leg.ItemTokenSize(1) = 15;
ax2 = nexttile; ax2 = nexttile;
hold on; hold on;
plot(f(2:end), 180/pi*angle(G_hac_m0_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f(2:end), 'Hz'))), 'color', colors(1,:)); plot(f, 180/pi*angle(G_hac_m0_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f, 'Hz'))), 'color', colors(1,:));
plot(f(2:end), 180/pi*angle(G_hac_m1_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f(2:end), 'Hz'))), 'color', colors(2,:)); plot(f, 180/pi*angle(G_hac_m1_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f, 'Hz'))), 'color', colors(2,:));
plot(f(2:end), 180/pi*angle(G_hac_m2_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f(2:end), 'Hz'))), 'color', colors(3,:)); plot(f, 180/pi*angle(G_hac_m2_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f, 'Hz'))), 'color', colors(3,:));
plot(f(2:end), 180/pi*angle(G_hac_m3_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f(2:end), 'Hz'))), 'color', colors(4,:)); plot(f, 180/pi*angle(G_hac_m3_Wz0(:,1, 1).*squeeze(freqresp(Khac(1,1), f, 'Hz'))), 'color', colors(4,:));
xline(5, '--', 'linewidth', 1, 'color', [0,0,0,0.2]) xline(5, '--', 'linewidth', 1, 'color', [0,0,0,0.2])
hold off; hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin'); set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin');
@@ -3529,6 +3529,7 @@ Several scientific experiments were replicated, such as:
- Diffraction Tomography:continuous $R_z$ rotation using the Spindle and lateral $D_y$ scans performed at the same time using the translation stage (Section ref:ssec:test_id31_scans_diffraction_tomo) - Diffraction Tomography:continuous $R_z$ rotation using the Spindle and lateral $D_y$ scans performed at the same time using the translation stage (Section ref:ssec:test_id31_scans_diffraction_tomo)
Unless explicitly stated, all closed-loop experiments were performed using the robust (i.e. conservative) high authority controller designed in Section ref:ssec:test_id31_iff_hac_controller. Unless explicitly stated, all closed-loop experiments were performed using the robust (i.e. conservative) high authority controller designed in Section ref:ssec:test_id31_iff_hac_controller.
Higher performance controllers using complementary filters are investigated in Section ref:ssec:test_id31_cf_control.
For each experiment, the obtained performances are compared to the specifications for the most demanding case in which nano-focusing optics are used to focus the beam down to $200\,nm\times 100\,nm$. For each experiment, the obtained performances are compared to the specifications for the most demanding case in which nano-focusing optics are used to focus the beam down to $200\,nm\times 100\,nm$.
In this case, the goal is to keep the sample's point of interest in the beam, and therefore the $D_y$ and $D_z$ positioning errors should be less than $200\,nm$ and $100\,nm$ peak-to-peak, respectively. In this case, the goal is to keep the sample's point of interest in the beam, and therefore the $D_y$ and $D_z$ positioning errors should be less than $200\,nm$ and $100\,nm$ peak-to-peak, respectively.
@@ -3942,7 +3943,7 @@ data_tomo_m0_Wz180.Ry_rms_ol = rms(data_tomo_m0_Wz180.Ry_int(1:i_m0) - (y0 + R*s
A comparative analysis was conducted using three tomography scans at $180\,\text{deg/s}$ to evaluate the effectiveness of the HAC-LAC strategy in reducing positioning errors. A comparative analysis was conducted using three tomography scans at $180\,\text{deg/s}$ to evaluate the effectiveness of the HAC-LAC strategy in reducing positioning errors.
The scans were performed under three conditions: open-loop, with decentralized IFF control, and with the complete HAC-LAC strategy. The scans were performed under three conditions: open-loop, with decentralized IFF control, and with the complete HAC-LAC strategy.
For these specific measurements, an enhanced high authority controller was optimized for low payload masses to meet the performance requirements. For this specific measurement, an enhanced high authority controller (discussed in Section ref:ssec:test_id31_cf_control) was optimized for low payload masses to meet the performance requirements.
Figure ref:fig:test_id31_hac_cas_cl presents the cumulative amplitude spectra of the position errors for all three cases. Figure ref:fig:test_id31_hac_cas_cl presents the cumulative amplitude spectra of the position errors for all three cases.
The results reveal two distinct control contributions: the decentralized IFF effectively attenuates vibrations near the nano-hexapod suspension modes (an achievement not possible with HAC alone), while the high authority controller suppresses low-frequency vibrations primarily arising from Spindle guiding errors. The results reveal two distinct control contributions: the decentralized IFF effectively attenuates vibrations near the nano-hexapod suspension modes (an achievement not possible with HAC alone), while the high authority controller suppresses low-frequency vibrations primarily arising from Spindle guiding errors.
@@ -5041,6 +5042,236 @@ data_dt_1000ums.Dz_rms_cl = rms(detrend(data_dt_1000ums.Dz_int(i_dt_1000ums), 0)
data_dt_1000ums.Ry_rms_cl = rms(detrend(data_dt_1000ums.Ry_int(i_dt_1000ums), 0)); data_dt_1000ums.Ry_rms_cl = rms(detrend(data_dt_1000ums.Ry_int(i_dt_1000ums), 0));
#+end_src #+end_src
** Feedback control using Complementary Filters
<<ssec:test_id31_cf_control>>
# TODO - Add link to section
A control architecture utilizing complementary filters to shape the closed-loop transfer functions was proposed during the detail design phase.
Experimental validation of this architecture using the NASS is presented herein.
Given that performance requirements are specified in the Cartesian frame, decoupling of the plant within this frame was achieved using Jacobian matrices.
Consequently, the control space comprises the directions $D_x$, $D_y$, $D_z$, $R_x$, and $R_y$.
Control performance in each of these directions can be tuned independently.
A schematic of the proposed control architecture is illustrated in Figure\nbsp{}ref:fig:test_id31_cf_control.
#+name: fig:test_id31_cf_control
#+caption: Control architecture in the Cartesian frame. Only the controller corresponding to the $D_z$ direction is shown. $H_L$ and $H_H$ are complementary filters.
[[file:figs/test_id31_cf_control.png]]
# TODO - Add link to 2DoF model
Implementation of this control architecture necessitates a plant model, which must subsequently be inverted.
This plant model was derived from the multi-body model incorporating the previously detailed 2-DoF APA model, such that the model order stays relatively low.
Proposed analytical formulas for complementary filters having $40\,\text{dB/dec}$ were used during this experimental validation.
# TODO - Add link to the analytical formulas
An initial experimental validation was conducted under no-payload conditions, with control applied solely to the $D_y$, $D_z$, and $R_y$ directions.
Increased control bandwidth was achieved for the $D_z$ and $R_y$ directions through appropriate tuning of the parameter $\omega_0$.
The experimentally measured closed-loop sensitivity transfer functions corresponding to these three controlled directions are presented in Figure ref:fig:test_id31_cf_control_dy_dz_diff.
#+begin_src matlab
%% Complementary Filter Control - Experimental Validation
% Parameters to analyze results in the frequency domain
Ts = 1e-4; % Sampling Time [s]
Nfft = floor(2.0/Ts);
win = hanning(Nfft);
Noverlap = floor(Nfft/2);
%% Closed-Loop performance identification (S and T transfer functions)
% Different parameters w0 in different directions
data = load("2023-08-21_14-09_m0_cf_inv_tustin.mat");
[S_dy, f] = tfestimate(data.Dy.id_cl, data.Dy.e_dy, win, Noverlap, Nfft, 1/Ts);
[T_dy, ~] = tfestimate(data.Dy.id_cl, data.Dy.Dy_int, win, Noverlap, Nfft, 1/Ts);
[S_dz, ~] = tfestimate(data.Dz.id_cl, data.Dz.e_dz, win, Noverlap, Nfft, 1/Ts);
[T_dz, ~] = tfestimate(data.Dz.id_cl, data.Dz.Dz_int, win, Noverlap, Nfft, 1/Ts);
[S_ry, ~] = tfestimate(data.Ry.id_cl, data.Ry.e_ry, win, Noverlap, Nfft, 1/Ts);
[T_ry, ~] = tfestimate(data.Ry.id_cl, data.Ry.Ry_int, win, Noverlap, Nfft, 1/Ts);
#+end_src
#+begin_src matlab :exports none :results none
%% Obtained Closed-Loop transfer functions - Different Complementary filters for Dy and Dz
figure;
hold on;
plot(f, abs(S_dy), '-', 'color', colors(1,:),'DisplayName', '$S_{D_y}$');
plot(f, abs(S_dz), '-', 'color', colors(2,:),'DisplayName', '$S_{D_z}$');
plot(f, abs(S_ry), '-', 'color', colors(3,:),'DisplayName', '$S_{R_y}$');
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
xlabel('Frequency [Hz]'); ylabel('Magnitude');
ylim([1e-3, 5]);
xlim([1, 1e3]);
leg = legend('location', 'southeast', 'FontSize', 8, 'NumColumns', 1);
leg.ItemTokenSize(1) = 18;
#+end_src
#+begin_src matlab :tangle no :exports results :results file replace
exportFig('figs/test_id31_cf_control_dy_dz_diff.pdf', 'width', 'half', 'height', 'normal');
#+end_src
Another test was conducted with a $26\,\text{kg}$ payload.
For this configuration, complementary filters were implemented with $\omega_0 = 2\pi \cdot 10\,\text{rad/s}$, and parameter $\alpha$ was varied.
The resulting experimentally obtained closed-loop transfer functions are compared against the theoretical complementary filter responses in Figure\nbsp{}ref:fig:test_id31_cf_control_alpha.
As illustrated in the figure, a close correspondence between the measured closed-loop responses and the target complementary filter magnitude was observed.
It also shows that the parameter $\alpha$ provides a mechanism for managing the trade-off between low-frequency disturbance rejection performance and the potential amplification of disturbances within the crossover frequency region.
#+begin_src matlab
%% Effect of a change of complementary filter parameter alpha
% w0 = 10, alpha = 2
data_a2 = load("2023-08-21_17-56_m2_cf_10Hz_a2.mat");
[S_a2, ~] = tfestimate(data_a2.Dy.id_cl, data_a2.Dy.e_dy, win, Noverlap, Nfft, 1/Ts);
[T_a2, ~] = tfestimate(data_a2.Dy.id_cl, data_a2.Dy.Dy_int, win, Noverlap, Nfft, 1/Ts);
% Analytical formulas
w0 = 2*pi*10;
alpha = 2;
Hh_a2 = (s/w0)^2*((s/w0)+1+alpha)/(((s/w0)+1)*((s/w0)^2 + alpha*(s/w0) + 1));
Hl_a2 = ((1+alpha)*(s/w0)+1)/(((s/w0)+1)*((s/w0)^2 + alpha*(s/w0) + 1));
% w0 = 10, alpha = 0.5
data_a05 = load("2023-08-21_17-58_m2_cf_10Hz_a05.mat");
[S_a05, ~] = tfestimate(data_a05.Dz.id_cl, data_a05.Dz.e_dz, win, Noverlap, Nfft, 1/Ts);
[T_a05, ~] = tfestimate(data_a05.Dz.id_cl, data_a05.Dz.Dz_int, win, Noverlap, Nfft, 1/Ts);
% Analytical formulas
w0 = 2*pi*10;
alpha = 0.5;
Hh_a05 = (s/w0)^2*((s/w0)+1+alpha)/(((s/w0)+1)*((s/w0)^2 + alpha*(s/w0) + 1));
Hl_a05 = ((1+alpha)*(s/w0)+1)/(((s/w0)+1)*((s/w0)^2 + alpha*(s/w0) + 1));
#+end_src
#+begin_src matlab :exports none :results none
%% Obtained Closed-Loop transfer functions - Effect of changing alpha
figure;
hold on;
plot(freqs, abs(squeeze(freqresp(Hh_a2, freqs, 'Hz'))), '--', 'color', colors(1,:),'DisplayName', '$\alpha = 2$, $H_H$, $H_L$');
plot(f, abs(S_a2), '-', 'color', [colors(1,:), 0.5], 'linewidth', 2.5,'DisplayName', '$\alpha = 2$, $S$, $T$');
plot(freqs, abs(squeeze(freqresp(Hh_a05, freqs, 'Hz'))), '--', 'color', colors(2,:),'DisplayName', '$\alpha = 0.5$, $H_H$, $H_L$');
plot(f, abs(S_a05), '-', 'color', [colors(2,:), 0.5], 'linewidth', 2.5,'DisplayName', '$\alpha = 0.5$, $S$, $T$');
plot(freqs, abs(squeeze(freqresp(Hl_a2, freqs, 'Hz'))), '--', 'color', colors(1,:), 'HandleVisibility', 'off');
plot(f, abs(T_a2), '-', 'color', [colors(1,:), 0.5], 'linewidth', 2.5, 'HandleVisibility', 'off');
plot(freqs, abs(squeeze(freqresp(Hl_a05, freqs, 'Hz'))), '--', 'color', colors(2,:), 'HandleVisibility', 'off');
plot(f, abs(T_a05), '-', 'color', [colors(2,:), 0.5], 'linewidth', 2.5, 'HandleVisibility', 'off');
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
xlabel('Frequency [Hz]'); ylabel('Magnitude');
xlim([1, 1e3]);
ylim([1e-3, 5]);
leg = legend('location', 'south', 'FontSize', 8, 'NumColumns', 2);
leg.ItemTokenSize(1) = 18;
#+end_src
#+begin_src matlab :tangle no :exports results :results file replace
exportFig('figs/test_id31_cf_control_alpha.pdf', 'width', 'half', 'height', 'normal');
#+end_src
#+name: fig:test_id31_cf_control_results
#+caption: Measured closed-loop transfer functions. Different bandwidth can be specified for different directions using $\omega_0$ (\subref{fig:test_id31_cf_control_dy_dz_diff}). The shape can be adjusted using parameter $\alpha$ (\subref{fig:test_id31_cf_control_alpha}).
#+attr_latex: :options [htbp]
#+begin_figure
#+attr_latex: :caption \subcaption{\label{fig:test_id31_cf_control_dy_dz_diff}Chose of bandwidth using $\omega_0$, $m = 0\,\text{kg}$}
#+attr_latex: :options {0.49\textwidth}
#+begin_subfigure
#+attr_latex: :scale 0.9
[[file:figs/test_id31_cf_control_dy_dz_diff.png]]
#+end_subfigure
#+attr_latex: :caption \subcaption{\label{fig:test_id31_cf_control_alpha}Effect of a change of $\alpha$, $m = 26\,\text{kg}$}
#+attr_latex: :options {0.49\textwidth}
#+begin_subfigure
#+attr_latex: :scale 0.9
[[file:figs/test_id31_cf_control_alpha.png]]
#+end_subfigure
#+end_figure
Finally, $\omega_0$ was gradually increased to estimate the maximum bandwidth (i.e. the best low frequency disturbance rejection) that can be achieved with this architecture.
No payload was used for this test, and the parameter $\omega_0$ was increased for the controllers in the $D_y$ and $D_z$ directions.
A value $\omega_0 = 2\pi \cdot 60 \,\text{rad/s}$ could be achieved.
Measured closed-loop transfer functions are shown in Figure ref:fig:test_id31_high_bandwidth, indicating a reduction of disturbances in the considered direction of $1000$ at $1\,\text{Hz}$.
For higher values of $\omega_0$, the system became unstable in the vertical direction, probably because of the resonance at $250\,\text{Hz}$ that is not well captured with the multi-body model (Figure ref:fig:test_id31_hac_plant_effect_mass).
#+begin_src matlab
%% Trying high bandwidth controllers - 60Hz
% Z direction
data = load("2023-08-21_14-19_m0_cf_inv_tustin_Dz_60Hz_a_20.mat");
[S_dz, ~] = tfestimate(data.Dz.id_cl, data.Dz.e_dz, win, Noverlap, Nfft, 1/Ts);
[T_dz, ~] = tfestimate(data.Dz.id_cl, data.Dz.Dz_int, win, Noverlap, Nfft, 1/Ts);
% Y direction
data = load("2023-08-21_14-20_m0_cf_inv_tustin_Dy_60Hz_a_20.mat");
[S_dy, ~] = tfestimate(data.Dy.id_cl, data.Dy.e_dy, win, Noverlap, Nfft, 1/Ts);
[T_dy, ~] = tfestimate(data.Dy.id_cl, data.Dy.Dy_int, win, Noverlap, Nfft, 1/Ts);
% Analytical formulas
w0 = 2*pi*60;
alpha = 2;
Hh_60Hz = (s/w0)^2*((s/w0)+1+alpha)/(((s/w0)+1)*((s/w0)^2 + alpha*(s/w0) + 1));
Hl_60Hz = ((1+alpha)*(s/w0)+1)/(((s/w0)+1)*((s/w0)^2 + alpha*(s/w0) + 1));
#+end_src
#+begin_src matlab :exports none :results none
%% Bode plot of the Weighting filters and Obtained complementary filters
figure;
hold on;
plot(f, abs(S_dy), '-', 'color', colors(1,:), 'DisplayName', '$S$, $D_y$');
plot(f, abs(S_dz), '-', 'color', colors(2,:), 'DisplayName', '$S$, $D_z$');
plot(freqs, abs(squeeze(freqresp(Hh_60Hz, freqs, 'Hz'))), 'k--','DisplayName', '$H_H$');
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
xlabel('Frequency [Hz]'); ylabel('Magnitude');
xlim([1, 1e3]);
ylim([3e-4, 5]);
leg = legend('location', 'southeast', 'FontSize', 8, 'NumColumns', 1);
leg.ItemTokenSize(1) = 18;
#+end_src
#+begin_src matlab :tangle no :exports results :results file replace
yticks([1e-3, 1e-2, 1e-1, 1]);
exportFig('figs/test_id31_high_bandwidth_S.pdf', 'width', 'half', 'height', 'normal');
#+end_src
#+begin_src matlab :exports none :results none
%% Bode plot of the Weighting filters and Obtained complementary filters
figure;
hold on;
plot(f, abs(T_dy), '-', 'color', colors(1,:), 'DisplayName', '$T$, $D_y$');
plot(f, abs(T_dz), '-', 'color', colors(2,:), 'DisplayName', '$T$, $D_z$');
plot(freqs, abs(squeeze(freqresp(Hl_60Hz, freqs, 'Hz'))), 'k--','DisplayName', '$H_L$');
hold off;
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
xlabel('Frequency [Hz]'); ylabel('Magnitude');
xlim([1, 1e3]);
ylim([3e-4, 5]);
leg = legend('location', 'southwest', 'FontSize', 8, 'NumColumns', 1);
leg.ItemTokenSize(1) = 18;
#+end_src
#+begin_src matlab :tangle no :exports results :results file replace
yticks([1e-3, 1e-2, 1e-1, 1]);
exportFig('figs/test_id31_high_bandwidth_T.pdf', 'width', 'half', 'height', 'normal');
#+end_src
#+name: fig:test_id31_high_bandwidth
#+caption: Measured Closed-Loop Sensitivity (\subref{fig:test_id31_high_bandwidth_S}) and Complementary Sensitivity (\subref{fig:test_id31_high_bandwidth_T}) transfer functions for the highest test bandwidth $\omega_0 = 2\pi\cdot 60\,\text{rad/s}$.
#+attr_latex: :options [htbp]
#+begin_figure
#+attr_latex: :caption \subcaption{\label{fig:test_id31_high_bandwidth_S}Sensitivity}
#+attr_latex: :options {0.49\textwidth}
#+begin_subfigure
#+attr_latex: :scale 0.9
[[file:figs/test_id31_high_bandwidth_S.png]]
#+end_subfigure
#+attr_latex: :caption \subcaption{\label{fig:test_id31_high_bandwidth_T}Complementary Sensitivity}
#+attr_latex: :options {0.49\textwidth}
#+begin_subfigure
#+attr_latex: :scale 0.9
[[file:figs/test_id31_high_bandwidth_T.png]]
#+end_subfigure
#+end_figure
** Conclusion ** Conclusion
:PROPERTIES: :PROPERTIES:
:UNNUMBERED: t :UNNUMBERED: t
@@ -5208,108 +5439,67 @@ specs_ry_rms = 0.25; % [urad RMS]
:header-args:matlab+: :comments none :mkdirp yes :eval no :header-args:matlab+: :comments none :mkdirp yes :eval no
:END: :END:
#+begin_src matlab #+begin_src matlab
function [cntrs,tp] = h5scan(pth,smp,ds,sn,varargin) % function [cntrs,tp] = h5scan(pth,smp,ds,sn,varargin)
function [cntrs,tp] = h5scan(ds,sn)
if ~isstr(ds), ds = sprintf('%.4d',ds); end;
i = cellfun(@(x) isa(x,'detector'),varargin); f = sprintf('%s.h5',ds);
if any(i), det = varargin{i}; varargin = varargin(~i); else, det = []; end; h = h5info(f,sprintf('/%d.1/measurement',sn));
if ~isstr(ds), ds = sprintf('%.4d',ds); end; fid = H5F.open(f);
for i = 1:length(h.Links)
f = sprintf('%s/%s/%s_%s/%s_%s.h5',pth,smp,smp,ds,smp,ds);
h = h5info(f,sprintf('/%d.1/measurement',sn));
fid = H5F.open(f);
for i = 1:length(h.Links),
nm = h.Links(i).Name; nm = h.Links(i).Name;
try, try
id = H5D.open(fid,h.Links(i).Value{1}); id = H5D.open(fid,h.Links(i).Value{1});
cntrs.(nm) = H5D.read(id); cntrs.(nm) = H5D.read(id);
H5D.close(id); H5D.close(id);
if ~isempty(det) & strcmp(nm,det.name), cntrs.(nm) = integrate(det,double(cntrs.(nm))); end; if ~isempty(det) & strcmp(nm,det.name), cntrs.(nm) = integrate(det,double(cntrs.(nm))); end;
catch, end
warning('solving problem with %s\n',nm);
cntrs.(nm) = vrtlds(sprintf('%s/%s/%s_%s/scan%.4d/',pth,smp,smp,ds,sn),nm,det);
end;
[~,tp.(nm)] = fileparts(h.Links(i).Value{1}); [~,tp.(nm)] = fileparts(h.Links(i).Value{1});
end; end
try, try
h = h5info(f,sprintf('/%d.2/measurement',sn)); h = h5info(f,sprintf('/%d.2/measurement',sn));
catch, catch
h = []; h = [];
end; end
if ~isempty(h), if ~isempty(h)
for i = 1:length(h.Links), for i = 1:length(h.Links)
nm = h.Links(i).Name; nm = h.Links(i).Name;
try, try
id = H5D.open(fid,h.Links(i).Value{1}); id = H5D.open(fid,h.Links(i).Value{1});
cntrs.part2.(nm) = H5D.read(id); cntrs.part2.(nm) = H5D.read(id);
H5D.close(id); H5D.close(id);
catch, end
warning('solving problem with %s\n',nm);
cntrs.part2.(nm) = vrtlds(sprintf('%s/%s/%s_%s/scan%.4d/',pth,smp,smp,ds,sn),nm,det);
end;
[~,tp.part2.(nm)] = fileparts(h.Links(i).Value{1}); [~,tp.part2.(nm)] = fileparts(h.Links(i).Value{1});
end; end
end; end
if length(varargin),
fn = sprintf('/%d.1/instrument/positioners/',sn);
h = h5info(f,fn);
[~,k,m] = intersect({h.Datasets.Name},varargin,'stable');
h.Datasets = h.Datasets(k);
for i = 1:length(h.Datasets),
id = H5D.open(fid,[fn h.Datasets(i).Name]);
cntrs.(h.Datasets(i).Name) = H5D.read(id);
H5D.close(id);
end;
end;
H5F.close(fid); H5F.close(fid);
%%%%%%%%%%%%%%%%%%%%%%%%%% %%%%%%%%%%%%%%%%%%%%%%%%%%
function A = vrtlds(f,nm,det) function A = vrtlds(f,nm,det)
%try,
n = 0; A = []; n = 0; A = [];
fn = sprintf('%s/%s_%.4d.h5',f,nm,n); fn = sprintf('%s/%s_%.4d.h5',f,nm,n);
while exist(fn) == 2,
while exist(fn) == 2
fid = H5F.open(fn); n = n+1; fid = H5F.open(fn); n = n+1;
id = H5D.open(fid,sprintf('/entry_0000/ESRF-ID31/%s/data',nm)); id = H5D.open(fid,sprintf('/entry_0000/ESRF-ID31/%s/data',nm));
if 2 < nargin & strcmp(nm,'p3') & ~isempty(det), if 2 < nargin & strcmp(nm,'p3') & ~isempty(det)
fprintf('integrating %s\n',fn); fprintf('integrating %s\n',fn);
if isempty(A), if isempty(A)
A = integrate(det,double(H5D.read(id)),1); A = integrate(det,double(H5D.read(id)),1);
else, else
tmp = integrate(det,double(H5D.read(id)),1); A.y = cat(2,A.y,tmp.y); A.y0 = cat(2,A.y0,tmp.y0); tmp = integrate(det,double(H5D.read(id)),1); A.y = cat(2,A.y,tmp.y); A.y0 = cat(2,A.y0,tmp.y0);
end; end
else, else
fprintf('loading %s\n',fn); fprintf('loading %s\n',fn);
A = cat(3,A,H5D.read(id)); A = cat(3,A,H5D.read(id));
end; end
H5D.close(id); H5F.close(fid); H5D.close(id); H5F.close(fid);
fn = sprintf('%s/%s_%.4d.h5',f,nm,n); fn = sprintf('%s/%s_%.4d.h5',f,nm,n);
end; end
%catch, end
% A = []; end
%end;
% fid = H5F.open...
% id = H5D.open...
% sid = H5D.get_space(id);
% [ndims,h5_dims]=H5S.get_simple_extent_dims(sid)
% Read a 2x3 hyperslab of data from a dataset, starting in the 4th row and 5th column of the example dataset.
% Create a property list identifier, then open the HDF5 file and the dataset /g1/g1.1/dset1.1.1.
% fid = H5F.open('example.h5');
% id = H5D.open(fid,'/g1/g1.1/dset1.1.1');
% dims = ([500 1679 1475];
% msid = H5S.create_simple(3,dims,[]);
% sid = H5D.get_space(id);
% offset = [n*500 0 0];
% block = dims; % d1: 500 or min(d1tot-n*500,500)
% H5S.select_hyperslab(sid,'H5S_SELECT_SET',offset,[],[],block);
% data = H5D.read(id,'H5ML_DEFAULT',msid,sid,'H5P_DEFAULT');
% H5D.close(id);
% H5F.close(fid);
#+end_src #+end_src
*** =sphereFit= - Fit sphere from x,y,z points *** =sphereFit= - Fit sphere from x,y,z points

Binary file not shown.

View File

@@ -1,4 +1,4 @@
% Created 2025-02-20 Thu 10:55 % Created 2025-04-20 Sun 22:21
% Intended LaTeX compiler: pdflatex % Intended LaTeX compiler: pdflatex
\documentclass[a4paper, 10pt, DIV=12, parskip=full, bibliography=totoc]{scrreprt} \documentclass[a4paper, 10pt, DIV=12, parskip=full, bibliography=totoc]{scrreprt}
@@ -18,7 +18,7 @@
pdftitle={Experimental Validation on the ID31 Beamline}, pdftitle={Experimental Validation on the ID31 Beamline},
pdfkeywords={}, pdfkeywords={},
pdfsubject={}, pdfsubject={},
pdfcreator={Emacs 29.4 (Org mode 9.6)}, pdfcreator={Emacs 30.1 (Org mode 9.7.26)},
pdflang={English}} pdflang={English}}
\usepackage{biblatex} \usepackage{biblatex}
@@ -28,7 +28,6 @@
\tableofcontents \tableofcontents
\clearpage \clearpage
To proceed with the full validation of the Nano Active Stabilization System (NASS), the nano-hexapod was mounted on top of the micro-station on ID31, as illustrated in figure \ref{fig:test_id31_micro_station_nano_hexapod}. To proceed with the full validation of the Nano Active Stabilization System (NASS), the nano-hexapod was mounted on top of the micro-station on ID31, as illustrated in figure \ref{fig:test_id31_micro_station_nano_hexapod}.
This section presents a comprehensive experimental evaluation of the complete system's performance on the ID31 beamline, focusing on its ability to maintain precise sample positioning under various experimental conditions. This section presents a comprehensive experimental evaluation of the complete system's performance on the ID31 beamline, focusing on its ability to maintain precise sample positioning under various experimental conditions.
@@ -62,7 +61,6 @@ These include tomography scans at various speeds and with different payload mass
\end{subfigure} \end{subfigure}
\caption{\label{fig:test_id31_micro_station_nano_hexapod}Picture of the micro-station without the nano-hexapod (\subref{fig:test_id31_micro_station_cables}) and with the nano-hexapod (\subref{fig:test_id31_fixed_nano_hexapod})} \caption{\label{fig:test_id31_micro_station_nano_hexapod}Picture of the micro-station without the nano-hexapod (\subref{fig:test_id31_micro_station_cables}) and with the nano-hexapod (\subref{fig:test_id31_fixed_nano_hexapod})}
\end{figure} \end{figure}
\chapter{Short Stroke Metrology System} \chapter{Short Stroke Metrology System}
\label{sec:test_id31_metrology} \label{sec:test_id31_metrology}
The control of the nano-hexapod requires an external metrology system that measures the relative position of the nano-hexapod top platform with respect to the granite. The control of the nano-hexapod requires an external metrology system that measures the relative position of the nano-hexapod top platform with respect to the granite.
@@ -142,7 +140,6 @@ The five equations \eqref{eq:test_id31_metrology_kinematics} can be written in m
d_1 \\ d_2 \\ d_3 \\ d_4 \\ d_5 d_1 \\ d_2 \\ d_3 \\ d_4 \\ d_5
\end{bmatrix} \end{bmatrix}
\end{equation} \end{equation}
\section{Rough alignment of the reference spheres} \section{Rough alignment of the reference spheres}
\label{ssec:test_id31_metrology_sphere_rought_alignment} \label{ssec:test_id31_metrology_sphere_rought_alignment}
@@ -156,7 +153,6 @@ The probes are then fixed to the top (adjustable) cylinder, and the same alignme
With this setup, the alignment accuracy of both spheres with the spindle axis was expected to around \(10\,\mu m\). With this setup, the alignment accuracy of both spheres with the spindle axis was expected to around \(10\,\mu m\).
The accuracy was probably limited by the poor coaxiality between the cylinders and the spheres. The accuracy was probably limited by the poor coaxiality between the cylinders and the spheres.
However, this first alignment should be sufficient to position the two sphere within the acceptance range of the interferometers. However, this first alignment should be sufficient to position the two sphere within the acceptance range of the interferometers.
\section{Tip-Tilt adjustment of the interferometers} \section{Tip-Tilt adjustment of the interferometers}
\label{ssec:test_id31_metrology_alignment} \label{ssec:test_id31_metrology_alignment}
@@ -180,7 +176,6 @@ This allows them to be individually oriented so that they all point to the spher
This is achieved by maximizing the intensity of the reflected light of each interferometer. This is achieved by maximizing the intensity of the reflected light of each interferometer.
After the alignment procedure, the top interferometer should coincide with the spindle axis, and the lateral interferometers should all be in the horizontal plane and intersect the centers of the spheres. After the alignment procedure, the top interferometer should coincide with the spindle axis, and the lateral interferometers should all be in the horizontal plane and intersect the centers of the spheres.
\section{Fine Alignment of reference spheres using interferometers} \section{Fine Alignment of reference spheres using interferometers}
\label{ssec:test_id31_metrology_sphere_fine_alignment} \label{ssec:test_id31_metrology_sphere_fine_alignment}
@@ -210,8 +205,6 @@ The remaining errors after alignment are in the order of \(\pm5\,\mu\text{rad}\)
\end{subfigure} \end{subfigure}
\caption{\label{fig:test_id31_metrology_align}Measured angular (\subref{fig:test_id31_metrology_align_rx_ry}) and lateral (\subref{fig:test_id31_metrology_align_dx_dy}) errors during full spindle rotation. Between two rotations, the micro-hexapod is adjusted to better align the two spheres with the rotation axis.} \caption{\label{fig:test_id31_metrology_align}Measured angular (\subref{fig:test_id31_metrology_align_rx_ry}) and lateral (\subref{fig:test_id31_metrology_align_dx_dy}) errors during full spindle rotation. Between two rotations, the micro-hexapod is adjusted to better align the two spheres with the rotation axis.}
\end{figure} \end{figure}
\section{Estimated measurement volume} \section{Estimated measurement volume}
\label{ssec:test_id31_metrology_acceptance} \label{ssec:test_id31_metrology_acceptance}
@@ -236,8 +229,6 @@ The obtained lateral acceptance for pure displacements in any direction is estim
\bottomrule \bottomrule
\end{tabularx} \end{tabularx}
\end{table} \end{table}
\section{Estimated measurement errors} \section{Estimated measurement errors}
\label{ssec:test_id31_metrology_errors} \label{ssec:test_id31_metrology_errors}
@@ -276,7 +267,6 @@ The effect of noise on the translation and rotation measurements is estimated in
\end{subfigure} \end{subfigure}
\caption{\label{fig:test_id31_metrology_errors}Estimated measurement errors of the metrology. Cross-coupling between lateral motion and vertical measurement is shown in (\subref{fig:test_id31_xy_map_sphere}). The effect of interferometer noise on the measured translations and rotations is shown in (\subref{fig:test_id31_interf_noise}).} \caption{\label{fig:test_id31_metrology_errors}Estimated measurement errors of the metrology. Cross-coupling between lateral motion and vertical measurement is shown in (\subref{fig:test_id31_xy_map_sphere}). The effect of interferometer noise on the measured translations and rotations is shown in (\subref{fig:test_id31_interf_noise}).}
\end{figure} \end{figure}
\chapter{Open Loop Plant} \chapter{Open Loop Plant}
\label{sec:test_id31_open_loop_plant} \label{sec:test_id31_open_loop_plant}
The NASS plant is schematically illustrated in Figure \ref{fig:test_id31_block_schematic_plant}. The NASS plant is schematically illustrated in Figure \ref{fig:test_id31_block_schematic_plant}.
@@ -327,7 +317,6 @@ This issue was later solved.
\end{subfigure} \end{subfigure}
\caption{\label{fig:test_id31_first_id}Comparison between the measured dynamics and the multi-body model dynamics. Both for the external metrology (\subref{fig:test_id31_first_id_int}) and force sensors (\subref{fig:test_id31_first_id_iff}). Direct terms are displayed with solid lines while off-diagonal (i.e. coupling) terms are displayed with shaded lines.} \caption{\label{fig:test_id31_first_id}Comparison between the measured dynamics and the multi-body model dynamics. Both for the external metrology (\subref{fig:test_id31_first_id_int}) and force sensors (\subref{fig:test_id31_first_id_iff}). Direct terms are displayed with solid lines while off-diagonal (i.e. coupling) terms are displayed with shaded lines.}
\end{figure} \end{figure}
\section{Better Angular Alignment} \section{Better Angular Alignment}
\label{ssec:test_id31_open_loop_plant_rz_alignment} \label{ssec:test_id31_open_loop_plant_rz_alignment}
@@ -367,7 +356,6 @@ The flexible modes of the top platform can be passively damped, whereas the mode
\includegraphics[scale=1]{figs/test_id31_first_id_int_better_rz_align.png} \includegraphics[scale=1]{figs/test_id31_first_id_int_better_rz_align.png}
\caption{\label{fig:test_id31_first_id_int_better_rz_align}Decrease of the coupling with better Rz alignment} \caption{\label{fig:test_id31_first_id_int_better_rz_align}Decrease of the coupling with better Rz alignment}
\end{figure} \end{figure}
\section{Effect of Payload Mass} \section{Effect of Payload Mass}
\label{ssec:test_id31_open_loop_plant_mass} \label{ssec:test_id31_open_loop_plant_mass}
@@ -421,7 +409,6 @@ It is interesting to note that the anti-resonances in the force sensor plant now
\end{subfigure} \end{subfigure}
\caption{\label{fig:test_id31_comp_simscape_diag_masses}Comparison of the diagonal elements (i.e. ``direct'' terms) of the measured FRF matrix and the dynamics identified from the multi-body model. Both for the dynamics from \(u\) to \(\epsilon\mathcal{L}\) (\subref{fig:test_id31_comp_simscape_int_diag_masses}) and from \(u\) to \(V_s\) (\subref{fig:test_id31_comp_simscape_iff_diag_masses})} \caption{\label{fig:test_id31_comp_simscape_diag_masses}Comparison of the diagonal elements (i.e. ``direct'' terms) of the measured FRF matrix and the dynamics identified from the multi-body model. Both for the dynamics from \(u\) to \(\epsilon\mathcal{L}\) (\subref{fig:test_id31_comp_simscape_int_diag_masses}) and from \(u\) to \(V_s\) (\subref{fig:test_id31_comp_simscape_iff_diag_masses})}
\end{figure} \end{figure}
\section{Effect of Spindle Rotation} \section{Effect of Spindle Rotation}
\label{ssec:test_id31_open_loop_plant_rotation} \label{ssec:test_id31_open_loop_plant_rotation}
@@ -448,12 +435,10 @@ This also indicates that the metrology kinematics is correct and is working in r
\end{subfigure} \end{subfigure}
\caption{\label{fig:test_id31_effect_rotation}Effect of the spindle rotation on the plant dynamics from \(u\) to \(\epsilon\mathcal{L}\). Three rotational velocities are tested (\(0\,\text{deg}/s\), \(36\,\text{deg}/s\) and \(180\,\text{deg}/s\)). Both direct terms (\subref{fig:test_id31_effect_rotation_direct}) and coupling terms (\subref{fig:test_id31_effect_rotation_coupling}) are displayed.} \caption{\label{fig:test_id31_effect_rotation}Effect of the spindle rotation on the plant dynamics from \(u\) to \(\epsilon\mathcal{L}\). Three rotational velocities are tested (\(0\,\text{deg}/s\), \(36\,\text{deg}/s\) and \(180\,\text{deg}/s\)). Both direct terms (\subref{fig:test_id31_effect_rotation_direct}) and coupling terms (\subref{fig:test_id31_effect_rotation_coupling}) are displayed.}
\end{figure} \end{figure}
\section*{Conclusion} \section*{Conclusion}
The identified frequency response functions from command signals \(\bm{u}\) to the force sensors \(\bm{V}_s\) and to the estimated strut errors \(\bm{\epsilon\mathcal{L}}\) are well matching the dynamics of the developed multi-body model. The identified frequency response functions from command signals \(\bm{u}\) to the force sensors \(\bm{V}_s\) and to the estimated strut errors \(\bm{\epsilon\mathcal{L}}\) are well matching the dynamics of the developed multi-body model.
The effect of payload mass is shown to be well predicted by the model, which can be useful if robust model based control is to be used. The effect of payload mass is shown to be well predicted by the model, which can be useful if robust model based control is to be used.
The spindle rotation had no visible effect on the measured dynamics, indicating that controllers should be robust against spindle rotation. The spindle rotation had no visible effect on the measured dynamics, indicating that controllers should be robust against spindle rotation.
\chapter{Decentralized Integral Force Feedback} \chapter{Decentralized Integral Force Feedback}
\label{sec:test_id31_iff} \label{sec:test_id31_iff}
In this section, the low authority control part is first validated. In this section, the low authority control part is first validated.
@@ -490,7 +475,6 @@ This confirms that the multi-body model can be used to tune the IFF controller.
\includegraphics[scale=1]{figs/test_id31_comp_simscape_Vs.png} \includegraphics[scale=1]{figs/test_id31_comp_simscape_Vs.png}
\caption{\label{fig:test_id31_comp_simscape_Vs}Comparison of the measured (in blue) and modeled (in red) frequency transfer functions from the first control signal \(u_1\) to the six force sensor voltages \(V_{s1}\) to \(V_{s6}\)} \caption{\label{fig:test_id31_comp_simscape_Vs}Comparison of the measured (in blue) and modeled (in red) frequency transfer functions from the first control signal \(u_1\) to the six force sensor voltages \(V_{s1}\) to \(V_{s6}\)}
\end{figure} \end{figure}
\section{IFF Controller} \section{IFF Controller}
\label{ssec:test_id31_iff_controller} \label{ssec:test_id31_iff_controller}
@@ -555,7 +539,6 @@ However, in this study, it was chosen to implement a ``fixed'' (i.e. non-adaptiv
\end{subfigure} \end{subfigure}
\caption{\label{fig:test_id31_iff_root_locus}Root Locus plots for the designed decentralized IFF controller, computed using the multy-body model. Black crosses indicate the closed-loop poles for the choosen value of the gain.} \caption{\label{fig:test_id31_iff_root_locus}Root Locus plots for the designed decentralized IFF controller, computed using the multy-body model. Black crosses indicate the closed-loop poles for the choosen value of the gain.}
\end{figure} \end{figure}
\section{Damped Plant} \section{Damped Plant}
\label{ssec:test_id31_iff_perf} \label{ssec:test_id31_iff_perf}
@@ -581,14 +564,12 @@ The obtained frequency response functions are compared with the model in Figure
\end{subfigure} \end{subfigure}
\caption{\label{fig:test_id31_hac_plant_effect_mass_comp_model}Comparison of the open-loop plants and the damped plant with Decentralized IFF, estimated from the multi-body model (\subref{fig:test_id31_comp_ol_iff_plant_model}). Comparison of measured damped and modeled plants for all considered payloads (\subref{fig:test_id31_hac_plant_effect_mass}). Only ``direct'' terms (\(\epsilon\mathcal{L}_i/u_i^\prime\)) are displayed for simplificty} \caption{\label{fig:test_id31_hac_plant_effect_mass_comp_model}Comparison of the open-loop plants and the damped plant with Decentralized IFF, estimated from the multi-body model (\subref{fig:test_id31_comp_ol_iff_plant_model}). Comparison of measured damped and modeled plants for all considered payloads (\subref{fig:test_id31_hac_plant_effect_mass}). Only ``direct'' terms (\(\epsilon\mathcal{L}_i/u_i^\prime\)) are displayed for simplificty}
\end{figure} \end{figure}
\section*{Conclusion} \section*{Conclusion}
The implementation of a decentralized Integral Force Feedback controller was successfully demonstrated. The implementation of a decentralized Integral Force Feedback controller was successfully demonstrated.
Using the multi-body model, the controller was designed and optimized to ensure stability across all payload conditions while providing significant damping of suspension modes. Using the multi-body model, the controller was designed and optimized to ensure stability across all payload conditions while providing significant damping of suspension modes.
The experimental results validated the model predictions, showing a reduction in peak amplitudes by approximately a factor of 10 across the full payload range (0-39 kg). The experimental results validated the model predictions, showing a reduction in peak amplitudes by approximately a factor of 10 across the full payload range (0-39 kg).
Although higher gains could achieve better damping performance for lighter payloads, the chosen fixed-gain configuration represents a robust compromise that maintains stability and performance under all operating conditions. Although higher gains could achieve better damping performance for lighter payloads, the chosen fixed-gain configuration represents a robust compromise that maintains stability and performance under all operating conditions.
The good correlation between the modeled and measured damped plants confirms the effectiveness of using the multi-body model for both controller design and performance prediction. The good correlation between the modeled and measured damped plants confirms the effectiveness of using the multi-body model for both controller design and performance prediction.
\chapter{High Authority Control in the frame of the struts} \chapter{High Authority Control in the frame of the struts}
\label{sec:test_id31_hac} \label{sec:test_id31_hac}
In this section, a High-Authority-Controller is developed to actively stabilize the sample position. In this section, a High-Authority-Controller is developed to actively stabilize the sample position.
@@ -631,7 +612,6 @@ This is one of the key benefits of using the HAC-LAC strategy.
\includegraphics[scale=1]{figs/test_id31_comp_all_undamped_damped_plants.png} \includegraphics[scale=1]{figs/test_id31_comp_all_undamped_damped_plants.png}
\caption{\label{fig:test_id31_comp_all_undamped_damped_plants}Comparison of the (six) direct terms for all (four) payload conditions in the undamped case (in blue) and the damped case (i.e. with the decentralized IFF being implemented, in red).} \caption{\label{fig:test_id31_comp_all_undamped_damped_plants}Comparison of the (six) direct terms for all (four) payload conditions in the undamped case (in blue) and the damped case (i.e. with the decentralized IFF being implemented, in red).}
\end{figure} \end{figure}
\section{Interaction Analysis} \section{Interaction Analysis}
\label{sec:test_id31_hac_interaction_analysis} \label{sec:test_id31_hac_interaction_analysis}
@@ -639,7 +619,7 @@ The control strategy here is to apply a diagonal control in the frame of the str
To conduct this interaction analysis, the \acrfull{rga} \(\bm{\Lambda_G}\) is first computed using \eqref{eq:test_id31_rga} for the plant dynamics identified with the multiple payload masses. To conduct this interaction analysis, the \acrfull{rga} \(\bm{\Lambda_G}\) is first computed using \eqref{eq:test_id31_rga} for the plant dynamics identified with the multiple payload masses.
\begin{equation}\label{eq:test_id31_rga} \begin{equation}\label{eq:test_id31_rga}
\bm{\Lambda_G}(\omega) = \bm{G}(j\omega) \star \left(\bm{G}(j\omega)^{-1}\right)^{T}, \quad (\star \text{ means element wise multiplication}) \bm{\Lambda_G}(\omega) = \bm{G}(j\omega) \star \left(\bm{G}(j\omega)^{-1}\right)^{\intercal}, \quad (\star \text{ means element wise multiplication})
\end{equation} \end{equation}
Then, \acrshort{rga} numbers are computed using \eqref{eq:test_id31_rga_number} and are use as a metric for interaction \cite[chapt. 3.4]{skogestad07_multiv_feedb_contr}. Then, \acrshort{rga} numbers are computed using \eqref{eq:test_id31_rga_number} and are use as a metric for interaction \cite[chapt. 3.4]{skogestad07_multiv_feedb_contr}.
@@ -660,7 +640,6 @@ This design choice, while beneficial for system simplicity, introduces inherent
\includegraphics[scale=1]{figs/test_id31_hac_rga_number.png} \includegraphics[scale=1]{figs/test_id31_hac_rga_number.png}
\caption{\label{fig:test_id31_hac_rga_number}RGA-number for the damped plants - Comparison of all the payload conditions} \caption{\label{fig:test_id31_hac_rga_number}RGA-number for the damped plants - Comparison of all the payload conditions}
\end{figure} \end{figure}
\section{Robust Controller Design} \section{Robust Controller Design}
\label{ssec:test_id31_iff_hac_controller} \label{ssec:test_id31_iff_hac_controller}
@@ -692,7 +671,6 @@ However, small stability margins were observed for the highest mass, indicating
\end{subfigure} \end{subfigure}
\caption{\label{fig:test_id31_hac_loop_gain_loci}Robust High Authority Controller. ``Decentralized loop-gains'' are shown in (\subref{fig:test_id31_hac_loop_gain}) and characteristic loci are shown in (\subref{fig:test_id31_hac_characteristic_loci})} \caption{\label{fig:test_id31_hac_loop_gain_loci}Robust High Authority Controller. ``Decentralized loop-gains'' are shown in (\subref{fig:test_id31_hac_loop_gain}) and characteristic loci are shown in (\subref{fig:test_id31_hac_characteristic_loci})}
\end{figure} \end{figure}
\section{Performance estimation with simulation of Tomography scans} \section{Performance estimation with simulation of Tomography scans}
\label{ssec:test_id31_iff_hac_perf} \label{ssec:test_id31_iff_hac_perf}
@@ -716,7 +694,6 @@ The obtained closed-loop positioning accuracy was found to comply with the requi
\end{subfigure} \end{subfigure}
\caption{\label{fig:test_id31_tomo_m0_30rpm_robust_hac_iff_sim}Position error of the sample in the XY (\subref{fig:test_id31_tomo_m0_30rpm_robust_hac_iff_sim_xy}) and YZ (\subref{fig:test_id31_tomo_m0_30rpm_robust_hac_iff_sim_yz}) planes during a simulation of a tomography experiment at \(180\,\text{deg/s}\). No payload is placed on top of the nano-hexapod.} \caption{\label{fig:test_id31_tomo_m0_30rpm_robust_hac_iff_sim}Position error of the sample in the XY (\subref{fig:test_id31_tomo_m0_30rpm_robust_hac_iff_sim_xy}) and YZ (\subref{fig:test_id31_tomo_m0_30rpm_robust_hac_iff_sim_yz}) planes during a simulation of a tomography experiment at \(180\,\text{deg/s}\). No payload is placed on top of the nano-hexapod.}
\end{figure} \end{figure}
\section{Robustness estimation with simulation of Tomography scans} \section{Robustness estimation with simulation of Tomography scans}
\label{ssec:test_id31_iff_hac_robustness} \label{ssec:test_id31_iff_hac_robustness}
@@ -732,7 +709,6 @@ However, it was decided that this controller should be tested experimentally and
\includegraphics[scale=1]{figs/test_id31_hac_tomography_Wz36_simulation.png} \includegraphics[scale=1]{figs/test_id31_hac_tomography_Wz36_simulation.png}
\caption{\label{fig:test_id31_hac_tomography_Wz36_simulation}Positioning errors in the Y-Z plane during tomography experiments simulated using the multi-body model (in closed-loop)} \caption{\label{fig:test_id31_hac_tomography_Wz36_simulation}Positioning errors in the Y-Z plane during tomography experiments simulated using the multi-body model (in closed-loop)}
\end{figure} \end{figure}
\section*{Conclusion} \section*{Conclusion}
In this section, a High-Authority-Controller was developed to actively stabilize the sample position. In this section, a High-Authority-Controller was developed to actively stabilize the sample position.
The multi-body model was first validated by comparing it with the measured frequency responses of the damped plant, which showed good agreement for both direct terms and coupling terms. The multi-body model was first validated by comparing it with the measured frequency responses of the damped plant, which showed good agreement for both direct terms and coupling terms.
@@ -746,7 +722,6 @@ The closed-loop system remained stable under all tested payload conditions (0 to
With no payload at \(180\,\text{deg/s}\), the NASS successfully maintained the sample point of interest in the beam, which fulfilled the specifications. With no payload at \(180\,\text{deg/s}\), the NASS successfully maintained the sample point of interest in the beam, which fulfilled the specifications.
At \(6\,\text{deg/s}\), although the positioning errors increased with the payload mass (particularly in the lateral direction), the system remained stable. At \(6\,\text{deg/s}\), although the positioning errors increased with the payload mass (particularly in the lateral direction), the system remained stable.
These results demonstrate both the effectiveness and limitations of implementing control in the frame of the struts. These results demonstrate both the effectiveness and limitations of implementing control in the frame of the struts.
\chapter{Validation with Scientific experiments} \chapter{Validation with Scientific experiments}
\label{sec:test_id31_experiments} \label{sec:test_id31_experiments}
In this section, the goal is to evaluate the performance of the NASS and validate its use to perform typical scientific experiments. In this section, the goal is to evaluate the performance of the NASS and validate its use to perform typical scientific experiments.
@@ -763,6 +738,7 @@ Several scientific experiments were replicated, such as:
\end{itemize} \end{itemize}
Unless explicitly stated, all closed-loop experiments were performed using the robust (i.e. conservative) high authority controller designed in Section \ref{ssec:test_id31_iff_hac_controller}. Unless explicitly stated, all closed-loop experiments were performed using the robust (i.e. conservative) high authority controller designed in Section \ref{ssec:test_id31_iff_hac_controller}.
Higher performance controllers using complementary filters are investigated in Section \ref{ssec:test_id31_cf_control}.
For each experiment, the obtained performances are compared to the specifications for the most demanding case in which nano-focusing optics are used to focus the beam down to \(200\,nm\times 100\,nm\). For each experiment, the obtained performances are compared to the specifications for the most demanding case in which nano-focusing optics are used to focus the beam down to \(200\,nm\times 100\,nm\).
In this case, the goal is to keep the sample's point of interest in the beam, and therefore the \(D_y\) and \(D_z\) positioning errors should be less than \(200\,nm\) and \(100\,nm\) peak-to-peak, respectively. In this case, the goal is to keep the sample's point of interest in the beam, and therefore the \(D_y\) and \(D_z\) positioning errors should be less than \(200\,nm\) and \(100\,nm\) peak-to-peak, respectively.
@@ -785,7 +761,7 @@ RMS & 30nm & 15nm & \(250\,\text{nrad}\)\\
\end{table} \end{table}
\section{Tomography Scans} \section{Tomography Scans}
\label{ssec:test_id31_scans_tomography} \label{ssec:test_id31_scans_tomography}
\paragraph{Slow Tomography scans} \subsubsection{Slow Tomography scans}
First, tomography scans were performed with a rotational velocity of \(6\,\text{deg/s}\) for all considered payload masses (shown in Figure \ref{fig:test_id31_picture_masses}). First, tomography scans were performed with a rotational velocity of \(6\,\text{deg/s}\) for all considered payload masses (shown in Figure \ref{fig:test_id31_picture_masses}).
Each experimental sequence consisted of two complete spindle rotations: an initial open-loop rotation followed by a closed-loop rotation. Each experimental sequence consisted of two complete spindle rotations: an initial open-loop rotation followed by a closed-loop rotation.
@@ -821,8 +797,7 @@ These experimental findings are consistent with the predictions from the tomogra
\includegraphics[scale=1]{figs/test_id31_tomo_Wz36_results.png} \includegraphics[scale=1]{figs/test_id31_tomo_Wz36_results.png}
\caption{\label{fig:test_id31_tomo_Wz36_results}Measured errors in the \(Y-Z\) plane during tomography experiments at \(6\,\text{deg/s}\) for all considered payloads. In the open-loop case, the effect of eccentricity is removed from the data.} \caption{\label{fig:test_id31_tomo_Wz36_results}Measured errors in the \(Y-Z\) plane during tomography experiments at \(6\,\text{deg/s}\) for all considered payloads. In the open-loop case, the effect of eccentricity is removed from the data.}
\end{figure} \end{figure}
\subsubsection{Fast Tomography scans}
\paragraph{Fast Tomography scans}
A tomography experiment was then performed with the highest rotational velocity of the Spindle: \(180\,\text{deg/s}\)\footnote{The highest rotational velocity of \(360\,\text{deg/s}\) could not be tested due to an issue in the Spindle's controller.}. A tomography experiment was then performed with the highest rotational velocity of the Spindle: \(180\,\text{deg/s}\)\footnote{The highest rotational velocity of \(360\,\text{deg/s}\) could not be tested due to an issue in the Spindle's controller.}.
The trajectory of the point of interest during the fast tomography scan is shown in Figure \ref{fig:test_id31_tomo_m0_30rpm_robust_hac_iff_exp}. The trajectory of the point of interest during the fast tomography scan is shown in Figure \ref{fig:test_id31_tomo_m0_30rpm_robust_hac_iff_exp}.
@@ -844,12 +819,11 @@ Nevertheless, even with this robust (i.e. conservative) HAC implementation, the
\end{subfigure} \end{subfigure}
\caption{\label{fig:test_id31_tomo_m0_30rpm_robust_hac_iff_exp}Experimental results of tomography experiment at 180 deg/s without payload. The position error of the sample is shown in the XY (\subref{fig:test_id31_tomo_m0_30rpm_robust_hac_iff_exp_xy}) and YZ (\subref{fig:test_id31_tomo_m0_30rpm_robust_hac_iff_exp_yz}) planes.} \caption{\label{fig:test_id31_tomo_m0_30rpm_robust_hac_iff_exp}Experimental results of tomography experiment at 180 deg/s without payload. The position error of the sample is shown in the XY (\subref{fig:test_id31_tomo_m0_30rpm_robust_hac_iff_exp_xy}) and YZ (\subref{fig:test_id31_tomo_m0_30rpm_robust_hac_iff_exp_yz}) planes.}
\end{figure} \end{figure}
\subsubsection{Cumulative Amplitude Spectra}
\paragraph{Cumulative Amplitude Spectra}
A comparative analysis was conducted using three tomography scans at \(180\,\text{deg/s}\) to evaluate the effectiveness of the HAC-LAC strategy in reducing positioning errors. A comparative analysis was conducted using three tomography scans at \(180\,\text{deg/s}\) to evaluate the effectiveness of the HAC-LAC strategy in reducing positioning errors.
The scans were performed under three conditions: open-loop, with decentralized IFF control, and with the complete HAC-LAC strategy. The scans were performed under three conditions: open-loop, with decentralized IFF control, and with the complete HAC-LAC strategy.
For these specific measurements, an enhanced high authority controller was optimized for low payload masses to meet the performance requirements. For this specific measurement, an enhanced high authority controller (discussed in Section \ref{ssec:test_id31_cf_control}) was optimized for low payload masses to meet the performance requirements.
Figure \ref{fig:test_id31_hac_cas_cl} presents the cumulative amplitude spectra of the position errors for all three cases. Figure \ref{fig:test_id31_hac_cas_cl} presents the cumulative amplitude spectra of the position errors for all three cases.
The results reveal two distinct control contributions: the decentralized IFF effectively attenuates vibrations near the nano-hexapod suspension modes (an achievement not possible with HAC alone), while the high authority controller suppresses low-frequency vibrations primarily arising from Spindle guiding errors. The results reveal two distinct control contributions: the decentralized IFF effectively attenuates vibrations near the nano-hexapod suspension modes (an achievement not possible with HAC alone), while the high authority controller suppresses low-frequency vibrations primarily arising from Spindle guiding errors.
@@ -878,7 +852,6 @@ This experiment also illustrates that when needed, performance can be enhanced b
\end{subfigure} \end{subfigure}
\caption{\label{fig:test_id31_hac_cas_cl}Cumulative Amplitude Spectrum for tomography experiments at \(180\,\text{deg}/s\). Open-Loop case, IFF, and HAC-LAC are compared. Specifications are indicated by black dashed lines. The RMS values are indicated in the legend.} \caption{\label{fig:test_id31_hac_cas_cl}Cumulative Amplitude Spectrum for tomography experiments at \(180\,\text{deg}/s\). Open-Loop case, IFF, and HAC-LAC are compared. Specifications are indicated by black dashed lines. The RMS values are indicated in the legend.}
\end{figure} \end{figure}
\section{Reflectivity Scans} \section{Reflectivity Scans}
\label{ssec:test_id31_scans_reflectivity} \label{ssec:test_id31_scans_reflectivity}
@@ -907,12 +880,11 @@ The results confirmed that the NASS successfully maintained the point of interes
\end{subfigure} \end{subfigure}
\caption{\label{fig:test_id31_reflectivity}Reflectivity scan (\(R_y\)) with a rotational velocity of \(100\,\mu \text{rad}/s\).} \caption{\label{fig:test_id31_reflectivity}Reflectivity scan (\(R_y\)) with a rotational velocity of \(100\,\mu \text{rad}/s\).}
\end{figure} \end{figure}
\section{Dirty Layer Scans} \section{Dirty Layer Scans}
\label{ssec:test_id31_scans_dz} \label{ssec:test_id31_scans_dz}
In some cases, samples are composed of several atomic ``layers'' that are first aligned in the horizontal plane through \(R_x\) and \(R_y\) positioning, followed by vertical scanning with precise \(D_z\) motion. In some cases, samples are composed of several atomic ``layers'' that are first aligned in the horizontal plane through \(R_x\) and \(R_y\) positioning, followed by vertical scanning with precise \(D_z\) motion.
These vertical scans can be executed either continuously or in a step-by-step manner. These vertical scans can be executed either continuously or in a step-by-step manner.
\paragraph{Step by Step \(D_z\) motion} \subsubsection{Step by Step \(D_z\) motion}
The vertical step motion was performed exclusively with the nano-hexapod. The vertical step motion was performed exclusively with the nano-hexapod.
Testing was conducted across step sizes ranging from \(10\,nm\) to \(1\,\mu m\). Testing was conducted across step sizes ranging from \(10\,nm\) to \(1\,\mu m\).
@@ -944,8 +916,7 @@ The settling duration typically decreases for smaller step sizes.
\end{subfigure} \end{subfigure}
\caption{\label{fig:test_id31_dz_mim_steps}Vertical steps performed with the nano-hexapod. 10nm steps are shown in (\subref{fig:test_id31_dz_mim_10nm_steps}) with the low-pass filtered data corresponding to an integration time of \(50\,ms\). 100nm steps are shown in (\subref{fig:test_id31_dz_mim_100nm_steps}). The response time to reach a peak-to-peak error of \(\pm 20\,nm\) is \(\approx 70\,ms\) as shown in (\subref{fig:test_id31_dz_mim_1000nm_steps}) for a \(1\,\mu m\) step.} \caption{\label{fig:test_id31_dz_mim_steps}Vertical steps performed with the nano-hexapod. 10nm steps are shown in (\subref{fig:test_id31_dz_mim_10nm_steps}) with the low-pass filtered data corresponding to an integration time of \(50\,ms\). 100nm steps are shown in (\subref{fig:test_id31_dz_mim_100nm_steps}). The response time to reach a peak-to-peak error of \(\pm 20\,nm\) is \(\approx 70\,ms\) as shown in (\subref{fig:test_id31_dz_mim_1000nm_steps}) for a \(1\,\mu m\) step.}
\end{figure} \end{figure}
\subsubsection{Continuous \(D_z\) motion: Dirty Layer Scans}
\paragraph{Continuous \(D_z\) motion: Dirty Layer Scans}
For these and subsequent experiments, the NASS performs ``ramp scans'' (constant velocity scans). For these and subsequent experiments, the NASS performs ``ramp scans'' (constant velocity scans).
To eliminate tracking errors, the feedback controller incorporates two integrators, compensating for the plant's lack of integral action at low frequencies. To eliminate tracking errors, the feedback controller incorporates two integrators, compensating for the plant's lack of integral action at low frequencies.
@@ -999,14 +970,13 @@ However, performance during acceleration phases could be enhanced through the im
\end{subfigure} \end{subfigure}
\caption{\label{fig:test_id31_dz_scan_100ums}\(D_z\) scan at a velocity of \(100\,\mu m/s\). \(D_z\) setpoint, measured position and error are shown in (\subref{fig:test_id31_dz_scan_100ums_dz}). Errors in \(D_y\) and \(R_y\) are respectively shown in (\subref{fig:test_id31_dz_scan_100ums_dy}) and (\subref{fig:test_id31_dz_scan_100ums_ry})} \caption{\label{fig:test_id31_dz_scan_100ums}\(D_z\) scan at a velocity of \(100\,\mu m/s\). \(D_z\) setpoint, measured position and error are shown in (\subref{fig:test_id31_dz_scan_100ums_dz}). Errors in \(D_y\) and \(R_y\) are respectively shown in (\subref{fig:test_id31_dz_scan_100ums_dy}) and (\subref{fig:test_id31_dz_scan_100ums_ry})}
\end{figure} \end{figure}
\section{Lateral Scans} \section{Lateral Scans}
\label{ssec:test_id31_scans_dy} \label{ssec:test_id31_scans_dy}
Lateral scans are executed using the \(T_y\) stage. Lateral scans are executed using the \(T_y\) stage.
The stepper motor controller\footnote{The ``IcePAP'' \cite{janvier13_icepap} which is developed at the ESRF.} generates a setpoint that is transmitted to the Speedgoat. The stepper motor controller\footnote{The ``IcePAP'' \cite{janvier13_icepap} which is developed at the ESRF.} generates a setpoint that is transmitted to the Speedgoat.
Within the Speedgoat, the system computes the positioning error by comparing the measured \(D_y\) sample position against the received setpoint, and the Nano-Hexapod compensates for positioning errors introduced during \(T_y\) stage scanning. Within the Speedgoat, the system computes the positioning error by comparing the measured \(D_y\) sample position against the received setpoint, and the Nano-Hexapod compensates for positioning errors introduced during \(T_y\) stage scanning.
The scanning range is constrained \(\pm 100\,\mu m\) due to the limited acceptance of the metrology system. The scanning range is constrained \(\pm 100\,\mu m\) due to the limited acceptance of the metrology system.
\paragraph{Slow scan} \subsubsection{Slow scan}
Initial testing utilized a scanning velocity of \(10\,\mu m/s\), which is typical for these experiments. Initial testing utilized a scanning velocity of \(10\,\mu m/s\), which is typical for these experiments.
Figure \ref{fig:test_id31_dy_10ums} compares the positioning errors between open-loop (without NASS) and closed-loop operation. Figure \ref{fig:test_id31_dy_10ums} compares the positioning errors between open-loop (without NASS) and closed-loop operation.
@@ -1038,8 +1008,7 @@ Under closed-loop control, positioning errors remain within specifications in al
\end{subfigure} \end{subfigure}
\caption{\label{fig:test_id31_dy_10ums}Open-Loop (in blue) and Closed-loop (i.e. using the NASS, in red) during a \(10\,\mu m/s\) scan with the \(T_y\) stage. Errors in \(D_y\) is shown in (\subref{fig:test_id31_dy_10ums_dy}).} \caption{\label{fig:test_id31_dy_10ums}Open-Loop (in blue) and Closed-loop (i.e. using the NASS, in red) during a \(10\,\mu m/s\) scan with the \(T_y\) stage. Errors in \(D_y\) is shown in (\subref{fig:test_id31_dy_10ums_dy}).}
\end{figure} \end{figure}
\subsubsection{Fast Scan}
\paragraph{Fast Scan}
The system performance was evaluated at an increased scanning velocity of \(100\,\mu m/s\), and the results are presented in Figure \ref{fig:test_id31_dy_100ums}. The system performance was evaluated at an increased scanning velocity of \(100\,\mu m/s\), and the results are presented in Figure \ref{fig:test_id31_dy_100ums}.
At this velocity, the micro-stepping errors generate \(10\,\text{Hz}\) vibrations, which are further amplified by micro-station resonances. At this velocity, the micro-stepping errors generate \(10\,\text{Hz}\) vibrations, which are further amplified by micro-station resonances.
@@ -1072,7 +1041,6 @@ For applications requiring small \(D_y\) scans, the nano-hexapod can be used exc
\end{subfigure} \end{subfigure}
\caption{\label{fig:test_id31_dy_100ums}Open-Loop (in blue) and Closed-loop (i.e. using the NASS, in red) during a \(100\,\mu m/s\) scan with the \(T_y\) stage. Errors in \(D_y\) is shown in (\subref{fig:test_id31_dy_100ums_dy}).} \caption{\label{fig:test_id31_dy_100ums}Open-Loop (in blue) and Closed-loop (i.e. using the NASS, in red) during a \(100\,\mu m/s\) scan with the \(T_y\) stage. Errors in \(D_y\) is shown in (\subref{fig:test_id31_dy_100ums_dy}).}
\end{figure} \end{figure}
\section{Diffraction Tomography} \section{Diffraction Tomography}
\label{ssec:test_id31_scans_diffraction_tomo} \label{ssec:test_id31_scans_diffraction_tomo}
@@ -1114,7 +1082,74 @@ Alternatively, a feedforward controller could improve the lateral positioning ac
\end{subfigure} \end{subfigure}
\caption{\label{fig:test_id31_diffraction_tomo}Diffraction tomography scans (combined \(R_z\) and \(D_y\) motions) at several \(D_y\) velocities (\(R_z\) rotational velocity is \(6\,\text{deg/s}\)).} \caption{\label{fig:test_id31_diffraction_tomo}Diffraction tomography scans (combined \(R_z\) and \(D_y\) motions) at several \(D_y\) velocities (\(R_z\) rotational velocity is \(6\,\text{deg/s}\)).}
\end{figure} \end{figure}
\section{Feedback control using Complementary Filters}
\label{ssec:test_id31_cf_control}
A control architecture utilizing complementary filters to shape the closed-loop transfer functions was proposed during the detail design phase.
Experimental validation of this architecture using the NASS is presented herein.
Given that performance requirements are specified in the Cartesian frame, decoupling of the plant within this frame was achieved using Jacobian matrices.
Consequently, the control space comprises the directions \(D_x\), \(D_y\), \(D_z\), \(R_x\), and \(R_y\).
Control performance in each of these directions can be tuned independently.
A schematic of the proposed control architecture is illustrated in Figure~\ref{fig:test_id31_cf_control}.
\begin{figure}[htbp]
\centering
\includegraphics[scale=1]{figs/test_id31_cf_control.png}
\caption{\label{fig:test_id31_cf_control}Control architecture in the Cartesian frame. Only the controller corresponding to the \(D_z\) direction is shown. \(H_L\) and \(H_H\) are complementary filters.}
\end{figure}
Implementation of this control architecture necessitates a plant model, which must subsequently be inverted.
This plant model was derived from the multi-body model incorporating the previously detailed 2-DoF APA model, such that the model order stays relatively low.
Proposed analytical formulas for complementary filters having \(40\,\text{dB/dec}\) were used during this experimental validation.
An initial experimental validation was conducted under no-payload conditions, with control applied solely to the \(D_y\), \(D_z\), and \(R_y\) directions.
Increased control bandwidth was achieved for the \(D_z\) and \(R_y\) directions through appropriate tuning of the parameter \(\omega_0\).
The experimentally measured closed-loop sensitivity transfer functions corresponding to these three controlled directions are presented in Figure \ref{fig:test_id31_cf_control_dy_dz_diff}.
Another test was conducted with a \(26\,\text{kg}\) payload.
For this configuration, complementary filters were implemented with \(\omega_0 = 2\pi \cdot 10\,\text{rad/s}\), and parameter \(\alpha\) was varied.
The resulting experimentally obtained closed-loop transfer functions are compared against the theoretical complementary filter responses in Figure~\ref{fig:test_id31_cf_control_alpha}.
As illustrated in the figure, a close correspondence between the measured closed-loop responses and the target complementary filter magnitude was observed.
It also shows that the parameter \(\alpha\) provides a mechanism for managing the trade-off between low-frequency disturbance rejection performance and the potential amplification of disturbances within the crossover frequency region.
\begin{figure}[htbp]
\begin{subfigure}{0.49\textwidth}
\begin{center}
\includegraphics[scale=1,scale=0.9]{figs/test_id31_cf_control_dy_dz_diff.png}
\end{center}
\subcaption{\label{fig:test_id31_cf_control_dy_dz_diff}Chose of bandwidth using $\omega_0$, $m = 0\,\text{kg}$}
\end{subfigure}
\begin{subfigure}{0.49\textwidth}
\begin{center}
\includegraphics[scale=1,scale=0.9]{figs/test_id31_cf_control_alpha.png}
\end{center}
\subcaption{\label{fig:test_id31_cf_control_alpha}Effect of a change of $\alpha$, $m = 26\,\text{kg}$}
\end{subfigure}
\caption{\label{fig:test_id31_cf_control_results}Measured closed-loop transfer functions. Different bandwidth can be specified for different directions using \(\omega_0\) (\subref{fig:test_id31_cf_control_dy_dz_diff}). The shape can be adjusted using parameter \(\alpha\) (\subref{fig:test_id31_cf_control_alpha}).}
\end{figure}
Finally, \(\omega_0\) was gradually increased to estimate the maximum bandwidth (i.e. the best low frequency disturbance rejection) that can be achieved with this architecture.
No payload was used for this test, and the parameter \(\omega_0\) was increased for the controllers in the \(D_y\) and \(D_z\) directions.
A value \(\omega_0 = 2\pi \cdot 60 \,\text{rad/s}\) could be achieved.
Measured closed-loop transfer functions are shown in Figure \ref{fig:test_id31_high_bandwidth}, indicating a reduction of disturbances in the considered direction of \(1000\) at \(1\,\text{Hz}\).
For higher values of \(\omega_0\), the system became unstable in the vertical direction, probably because of the resonance at \(250\,\text{Hz}\) that is not well captured with the multi-body model (Figure \ref{fig:test_id31_hac_plant_effect_mass}).
\begin{figure}[htbp]
\begin{subfigure}{0.49\textwidth}
\begin{center}
\includegraphics[scale=1,scale=0.9]{figs/test_id31_high_bandwidth_S.png}
\end{center}
\subcaption{\label{fig:test_id31_high_bandwidth_S}Sensitivity}
\end{subfigure}
\begin{subfigure}{0.49\textwidth}
\begin{center}
\includegraphics[scale=1,scale=0.9]{figs/test_id31_high_bandwidth_T.png}
\end{center}
\subcaption{\label{fig:test_id31_high_bandwidth_T}Complementary Sensitivity}
\end{subfigure}
\caption{\label{fig:test_id31_high_bandwidth}Measured Closed-Loop Sensitivity (\subref{fig:test_id31_high_bandwidth_S}) and Complementary Sensitivity (\subref{fig:test_id31_high_bandwidth_T}) transfer functions for the highest test bandwidth \(\omega_0 = 2\pi\cdot 60\,\text{rad/s}\).}
\end{figure}
\section*{Conclusion} \section*{Conclusion}
\label{ssec:test_id31_scans_conclusion} \label{ssec:test_id31_scans_conclusion}
@@ -1140,7 +1175,7 @@ The identified limitations, primarily related to high-speed lateral scanning and
\centering \centering
\begin{tabularx}{\linewidth}{Xccc} \begin{tabularx}{\linewidth}{Xccc}
\toprule \toprule
\textbf{Experiments} & \(\bm{D_y}\) \textbf{[nmRMS]} & \(\bm{D_z}\) \textbf{[nmRMS]} & \(\bm{R_y}\) \textbf{[nradRMS]}\\ \textbf{Experiments} & \(\bm{D_y}\) \textbf{{[}nmRMS]} & \(\bm{D_z}\) \textbf{{[}nmRMS]} & \(\bm{R_y}\) \textbf{{[}nradRMS]}\\
\midrule \midrule
Tomography (\(6\,\text{deg/s}\)) & \(142 \Rightarrow 15\) & \(32 \Rightarrow 5\) & \(464 \Rightarrow 56\)\\ Tomography (\(6\,\text{deg/s}\)) & \(142 \Rightarrow 15\) & \(32 \Rightarrow 5\) & \(464 \Rightarrow 56\)\\
Tomography (\(6\,\text{deg/s}\), 13kg) & \(149 \Rightarrow 25\) & \(26 \Rightarrow 6\) & \(471 \Rightarrow 55\)\\ Tomography (\(6\,\text{deg/s}\), 13kg) & \(149 \Rightarrow 25\) & \(26 \Rightarrow 6\) & \(471 \Rightarrow 55\)\\
@@ -1166,7 +1201,6 @@ Diffraction tomography (\(6\,\text{deg/s}\), \(1\,mm/s\)) & \(\bm{53}\) & \(10\)
\bottomrule \bottomrule
\end{tabularx} \end{tabularx}
\end{table} \end{table}
\chapter*{Conclusion} \chapter*{Conclusion}
\label{ssec:test_id31_conclusion} \label{ssec:test_id31_conclusion}
@@ -1187,6 +1221,5 @@ Some limitations were identified, particularly in handling heavy payloads during
The successful validation of the NASS demonstrates that once an accurate online metrology system is developed, it will be ready for integration into actual beamline operations. The successful validation of the NASS demonstrates that once an accurate online metrology system is developed, it will be ready for integration into actual beamline operations.
The system's ability to maintain precise sample positioning across a wide range of experimental conditions, combined with its robust performance and adaptive capabilities, suggests that it will significantly enhance the quality and efficiency of X-ray experiments at ID31. The system's ability to maintain precise sample positioning across a wide range of experimental conditions, combined with its robust performance and adaptive capabilities, suggests that it will significantly enhance the quality and efficiency of X-ray experiments at ID31.
Moreover, the systematic approach to system development and validation, along with a detailed understanding of performance limitations, provides valuable insights for future improvements and potential applications in similar high-precision positioning systems. Moreover, the systematic approach to system development and validation, along with a detailed understanding of performance limitations, provides valuable insights for future improvements and potential applications in similar high-precision positioning systems.
\printbibliography[heading=bibintoc,title={Bibliography}] \printbibliography[heading=bibintoc,title={Bibliography}]
\end{document} \end{document}