test-bench-nano-hexapod/test-bench-nano-hexapod.org

49 KiB

Nano-Hexapod - Test Bench


This report is also available as a pdf.


Introduction   ignore

In this document, the dynamics of the nano-hexapod shown in Figure fig:picture_bench_granite_nano_hexapod is identified.

Here are the documentation of the equipment used for this test bench:

  • Voltage Amplifier: PiezoDrive PD200
  • Amplified Piezoelectric Actuator: Cedrat APA300ML
  • DAC/ADC: Speedgoat IO313
  • Encoder: Renishaw Vionic and used Ruler
  • Interferometers: Attocube

/tdehaeze/test-bench-nano-hexapod/media/commit/597ec7551fae3a9354caf6a2e94a1f325c7754fa/figs/IMG_20210608_152917.jpg

/tdehaeze/test-bench-nano-hexapod/media/commit/597ec7551fae3a9354caf6a2e94a1f325c7754fa/figs/IMG_20210608_154722.jpg

\definecolor{instrumentation}{rgb}{0, 0.447, 0.741}
\definecolor{mechanics}{rgb}{0.8500, 0.325, 0.098}

\begin{tikzpicture}
  % Blocs
  \node[block={4.0cm}{3.0cm}, fill=mechanics!20!white] (nano_hexapod) {Mechanics};
  \coordinate[] (inputF)  at (nano_hexapod.west);
  \coordinate[] (outputL) at ($(nano_hexapod.south east)!0.8!(nano_hexapod.north east)$);
  \coordinate[] (outputF) at ($(nano_hexapod.south east)!0.2!(nano_hexapod.north east)$);

  \node[block, left= 0.8 of inputF,  fill=instrumentation!20!white, align=center] (F_stack) {\tiny Actuator \\ \tiny stacks};
  \node[block, left= 0.8 of F_stack, fill=instrumentation!20!white] (PD200)   {PD200};
  \node[DAC,   left= 0.8 of PD200,   fill=instrumentation!20!white] (F_DAC)   {DAC};
  \node[block, right=0.8 of outputF, fill=instrumentation!20!white, align=center] (Fm_stack){\tiny Sensor \\ \tiny stack};
  \node[ADC,   right=0.8 of Fm_stack,fill=instrumentation!20!white] (Fm_ADC)  {ADC};
  \node[block, right=0.8 of outputL, fill=instrumentation!20!white] (encoder) {\tiny Encoder};

  % Connections and labels
  \draw[->] ($(F_DAC.west)+(-0.8,0)$) node[above right]{$\bm{u}$} node[below right]{$[V]$} -- node[sloped]{$/$} (F_DAC.west);
  \draw[->] (F_DAC.east)   -- node[midway, above]{$\tilde{\bm{u}}$}node[midway, below]{$[V]$} (PD200.west);
  \draw[->] (PD200.east)   -- node[midway, above]{$\bm{u}_a$}node[midway, below]{$[V]$} (F_stack.west);
  \draw[->] (F_stack.east) -- (inputF) node[above left]{$\bm{\tau}$}node[below left]{$[N]$};

  \draw[->] (outputF)       -- (Fm_stack.west) node[above left]{$\bm{\epsilon}$} node[below left]{$[m]$};
  \draw[->] (Fm_stack.east) -- node[midway, above]{$\tilde{\bm{\tau}}_m$}node[midway, below]{$[V]$} (Fm_ADC.west);
  \draw[->] (Fm_ADC.east)   -- node[sloped]{$/$} ++(0.8, 0)coordinate(end) node[above left]{$\bm{\tau}_m$}node[below left]{$[V]$};

  \draw[->] (outputL)      -- (encoder.west) node[above left]{$d\bm{\mathcal{L}}$} node[below left]{$[m]$};
  \draw[->] (encoder.east) -- node[sloped]{$/$} (encoder-|end) node[above left]{$d\bm{\mathcal{L}}_m$}node[below left]{$[m]$};

  % Nano-Hexapod
  \begin{scope}[on background layer]
    \node[fit={(F_stack.west|-nano_hexapod.south) (Fm_stack.east|-nano_hexapod.north)}, fill=black!20!white, draw, inner sep=2pt] (system) {};
    \node[above] at (system.north) {Nano-Hexapod};
  \end{scope}
\end{tikzpicture}

/tdehaeze/test-bench-nano-hexapod/media/commit/597ec7551fae3a9354caf6a2e94a1f325c7754fa/figs/nano_hexapod_signals.png

Unit Matlab Vector Elements
Control Input (wanted DAC voltage) [V] u $\bm{u}$ $u_i$
DAC Output Voltage [V] u $\tilde{\bm{u}}$ $\tilde{u}_i$
PD200 Output Voltage [V] ua $\bm{u}_a$ $u_{a,i}$
Actuator applied force [N] tau $\bm{\tau}$ $\tau_i$
Strut motion [m] dL $d\bm{\mathcal{L}}$ $d\mathcal{L}_i$
Encoder measured displacement [m] dLm $d\bm{\mathcal{L}}_m$ $d\mathcal{L}_{m,i}$
Force Sensor strain [m] epsilon $\bm{\epsilon}$ $\epsilon_i$
Force Sensor Generated Voltage [V] taum $\tilde{\bm{\tau}}_m$ $\tilde{\tau}_{m,i}$
Measured Generated Voltage [V] taum $\bm{\tau}_m$ $\tau_{m,i}$
Motion of the top platform [m,rad] dX $d\bm{\mathcal{X}}$ $d\mathcal{X}_i$
Metrology measured displacement [m,rad] dXm $d\bm{\mathcal{X}}_m$ $d\mathcal{X}_{m,i}$

Encoders fixed to the Struts

Introduction

In this section, the encoders are fixed to the struts.

Identification of the dynamics

Load Data

%% Load Identification Data
meas_data_lf = {};

for i = 1:6
    meas_data_lf(i) = {load(sprintf('mat/frf_data_exc_strut_%i_noise_lf.mat', i), 't', 'Va', 'Vs', 'de')};
    meas_data_hf(i) = {load(sprintf('mat/frf_data_exc_strut_%i_noise_hf.mat', i), 't', 'Va', 'Vs', 'de')};
end

Spectral Analysis - Setup

%% Setup useful variables
% Sampling Time [s]
Ts = (meas_data_lf{1}.t(end) - (meas_data_lf{1}.t(1)))/(length(meas_data_lf{1}.t)-1);

% Sampling Frequency [Hz]
Fs = 1/Ts;

% Hannning Windows
win = hanning(ceil(1*Fs));

% And we get the frequency vector
[~, f] = tfestimate(meas_data_lf{1}.Va, meas_data_lf{1}.de, win, [], [], 1/Ts);

i_lf = f < 250; % Points for low frequency excitation
i_hf = f > 250; % Points for high frequency excitation

DVF Plant

First, let's compute the coherence from the excitation voltage and the displacement as measured by the encoders (Figure fig:enc_struts_dvf_coh).

%% Coherence
coh_dvf_lf = zeros(length(f), 6, 6);
coh_dvf_hf = zeros(length(f), 6, 6);

for i = 1:6
    coh_dvf_lf(:, :, i) = mscohere(meas_data_lf{i}.Va, meas_data_lf{i}.de, win, [], [], 1/Ts);
    coh_dvf_hf(:, :, i) = mscohere(meas_data_hf{i}.Va, meas_data_hf{i}.de, win, [], [], 1/Ts);
end

/tdehaeze/test-bench-nano-hexapod/media/commit/597ec7551fae3a9354caf6a2e94a1f325c7754fa/figs/enc_struts_dvf_coh.png

Obtained coherence for the DVF plant

Then the 6x6 transfer function matrix is estimated (Figure fig:enc_struts_dvf_frf).

%% DVF Plant (transfer function from u to dLm)
G_dvf_lf = zeros(length(f), 6, 6);
G_dvf_hf = zeros(length(f), 6, 6);

for i = 1:6
    G_dvf_lf(:, :, i) = tfestimate(meas_data_lf{i}.Va, meas_data_lf{i}.de, win, [], [], 1/Ts);
    G_dvf_hf(:, :, i) = tfestimate(meas_data_hf{i}.Va, meas_data_hf{i}.de, win, [], [], 1/Ts);
end

/tdehaeze/test-bench-nano-hexapod/media/commit/597ec7551fae3a9354caf6a2e94a1f325c7754fa/figs/enc_struts_dvf_frf.png

Measured FRF for the DVF plant

IFF Plant

First, let's compute the coherence from the excitation voltage and the displacement as measured by the encoders (Figure fig:enc_struts_iff_coh).

%% Coherence for the IFF plant
coh_iff_lf = zeros(length(f), 6, 6);
coh_iff_hf = zeros(length(f), 6, 6);

for i = 1:6
    coh_iff_lf(:, :, i) = mscohere(meas_data_lf{i}.Va, meas_data_lf{i}.Vs, win, [], [], 1/Ts);
    coh_iff_hf(:, :, i) = mscohere(meas_data_hf{i}.Va, meas_data_hf{i}.Vs, win, [], [], 1/Ts);
end

/tdehaeze/test-bench-nano-hexapod/media/commit/597ec7551fae3a9354caf6a2e94a1f325c7754fa/figs/enc_struts_iff_coh.png

Obtained coherence for the IFF plant

Then the 6x6 transfer function matrix is estimated (Figure fig:enc_struts_iff_frf).

%% IFF Plant
G_iff_lf = zeros(length(f), 6, 6);
G_iff_hf = zeros(length(f), 6, 6);

for i = 1:6
    G_iff_lf(:, :, i) = tfestimate(meas_data_lf{i}.Va, meas_data_lf{i}.Vs, win, [], [], 1/Ts);
    G_iff_hf(:, :, i) = tfestimate(meas_data_hf{i}.Va, meas_data_hf{i}.Vs, win, [], [], 1/Ts);
end

/tdehaeze/test-bench-nano-hexapod/media/commit/597ec7551fae3a9354caf6a2e94a1f325c7754fa/figs/enc_struts_iff_frf.png

Measured FRF for the IFF plant

Comparison with the Simscape Model

Introduction   ignore

In this section, the measured dynamics is compared with the dynamics estimated from the Simscape model.

Dynamics from Actuator to Force Sensors

%% Initialize Nano-Hexapod
n_hexapod = initializeNanoHexapodFinal('flex_bot_type', '4dof', ...
                                       'flex_top_type', '4dof', ...
                                       'motion_sensor_type', 'struts', ...
                                       'actuator_type', '2dof');
%% Identify the IFF Plant (transfer function from u to taum)
clear io; io_i = 1;
io(io_i) = linio([mdl, '/F'],  1, 'openinput');   io_i = io_i + 1; % Actuator Inputs
io(io_i) = linio([mdl, '/Fm'],  1, 'openoutput'); io_i = io_i + 1; % Force Sensors

Giff = exp(-s*Ts)*linearize(mdl, io, 0.0, options);

/tdehaeze/test-bench-nano-hexapod/media/commit/597ec7551fae3a9354caf6a2e94a1f325c7754fa/figs/enc_struts_iff_comp_simscape.png

Diagonal elements of the IFF Plant

/tdehaeze/test-bench-nano-hexapod/media/commit/597ec7551fae3a9354caf6a2e94a1f325c7754fa/figs/enc_struts_iff_comp_offdiag_simscape.png

Off diagonal elements of the IFF Plant

Dynamics from Actuator to Encoder

%% Initialization of the Nano-Hexapod
n_hexapod = initializeNanoHexapodFinal('flex_bot_type', '4dof', ...
                                       'flex_top_type', '4dof', ...
                                       'motion_sensor_type', 'struts', ...
                                       'actuator_type', '2dof');
%% Identify the DVF Plant (transfer function from u to dLm)
clear io; io_i = 1;
io(io_i) = linio([mdl, '/F'],  1, 'openinput');  io_i = io_i + 1; % Actuator Inputs
io(io_i) = linio([mdl, '/D'],  1, 'openoutput'); io_i = io_i + 1; % Encoders

Gdvf = exp(-s*Ts)*linearize(mdl, io, 0.0, options);

/tdehaeze/test-bench-nano-hexapod/media/commit/597ec7551fae3a9354caf6a2e94a1f325c7754fa/figs/enc_struts_dvf_comp_simscape.png

Diagonal elements of the DVF Plant

/tdehaeze/test-bench-nano-hexapod/media/commit/597ec7551fae3a9354caf6a2e94a1f325c7754fa/figs/enc_struts_dvf_comp_offdiag_simscape.png

Off diagonal elements of the DVF Plant

Integral Force Feedback

Root Locus and Decentralized Loop gain

%% IFF Controller
Kiff_g1 = (1/(s + 2*pi*40))*... % Low pass filter (provides integral action above 40Hz)
          (s/(s + 2*pi*30))*... % High pass filter to limit low frequency gain
          (1/(1 + s/2/pi/500))*... % Low pass filter to be more robust to high frequency resonances
          eye(6); % Diagonal 6x6 controller

/tdehaeze/test-bench-nano-hexapod/media/commit/597ec7551fae3a9354caf6a2e94a1f325c7754fa/figs/enc_struts_iff_root_locus.png

Root Locus for the IFF control strategy

Then the "optimal" IFF controller is:

%% IFF controller with Optimal gain
Kiff = g*Kiff_g1;

/tdehaeze/test-bench-nano-hexapod/media/commit/597ec7551fae3a9354caf6a2e94a1f325c7754fa/figs/enc_struts_iff_opt_loop_gain.png

Bode plot of the "decentralized loop gain" $G_\text{iff}(i,i) \times K_\text{iff}(i,i)$

Multiple Gains - Simulation

%% Tested IFF gains
iff_gains = [4, 10, 20, 40, 100, 200, 400];
%% Initialize the Simscape model in closed loop
n_hexapod = initializeNanoHexapodFinal('flex_bot_type', '4dof', ...
                                       'flex_top_type', '4dof', ...
                                       'motion_sensor_type', 'struts', ...
                                       'actuator_type', '2dof', ...
                                       'controller_type', 'iff');
%% Identify the (damped) transfer function from u to dLm for different values of the IFF gain
Gd_iff = {zeros(1, length(iff_gains))};

clear io; io_i = 1;
io(io_i) = linio([mdl, '/F'],  1, 'openinput');  io_i = io_i + 1; % Actuator Inputs
io(io_i) = linio([mdl, '/D'],  1, 'openoutput'); io_i = io_i + 1; % Strut Displacement (encoder)

for i = 1:length(iff_gains)
    Kiff = iff_gains(i)*Kiff_g1*eye(6); % IFF Controller
    Gd_iff(i) = {exp(-s*Ts)*linearize(mdl, io, 0.0, options)};

    isstable(Gd_iff{i})
end

/tdehaeze/test-bench-nano-hexapod/media/commit/597ec7551fae3a9354caf6a2e94a1f325c7754fa/figs/enc_struts_iff_gains_effect_dvf_plant.png

Effect of the IFF gain $g$ on the transfer function from $\bm{\tau}$ to $d\bm{\mathcal{L}}_m$

Experimental Results - Gains

Introduction   ignore

Let's look at the damping introduced by IFF as a function of the IFF gain and compare that with the results obtained using the Simscape model.

Load Data
%% Load Identification Data
meas_iff_gains = {};

for i = 1:length(iff_gains)
    meas_iff_gains(i) = {load(sprintf('mat/iff_strut_1_noise_g_%i.mat', iff_gains(i)), 't', 'Vexc', 'Vs', 'de', 'u')};
end
Spectral Analysis - Setup
%% Setup useful variables
% Sampling Time [s]
Ts = (meas_iff_gains{1}.t(end) - (meas_iff_gains{1}.t(1)))/(length(meas_iff_gains{1}.t)-1);

% Sampling Frequency [Hz]
Fs = 1/Ts;

% Hannning Windows
win = hanning(ceil(1*Fs));

% And we get the frequency vector
[~, f] = tfestimate(meas_iff_gains{1}.Vexc, meas_iff_gains{1}.de, win, [], [], 1/Ts);
DVF Plant
%% DVF Plant (transfer function from u to dLm)
G_iff_gains = {};

for i = 1:length(iff_gains)
    G_iff_gains{i} = tfestimate(meas_iff_gains{i}.Vexc, meas_iff_gains{i}.de(:,1), win, [], [], 1/Ts);
end

/tdehaeze/test-bench-nano-hexapod/media/commit/597ec7551fae3a9354caf6a2e94a1f325c7754fa/figs/comp_iff_gains_dvf_plant.png

Transfer function from $u$ to $d\mathcal{L}_m$ for multiple values of the IFF gain

/tdehaeze/test-bench-nano-hexapod/media/commit/597ec7551fae3a9354caf6a2e94a1f325c7754fa/figs/comp_iff_gains_dvf_plant_zoom.png

Transfer function from $u$ to $d\mathcal{L}_m$ for multiple values of the IFF gain (Zoom)

The IFF control strategy is very effective for the damping of the suspension modes. It however does not damp the modes at 200Hz, 300Hz and 400Hz (flexible modes of the APA). This is very logical.

Also, the experimental results and the models obtained from the Simscape model are in agreement.

Experimental Results - Comparison of the un-damped and fully damped system

/tdehaeze/test-bench-nano-hexapod/media/commit/597ec7551fae3a9354caf6a2e94a1f325c7754fa/figs/comp_undamped_opt_iff_gain_diagonal.png

Comparison of the diagonal elements of the tranfer function from $\bm{u}$ to $d\bm{\mathcal{L}}_m$ without active damping and with optimal IFF gain

Experimental Results - Damped Plant with Optimal gain

Introduction   ignore

Let's now look at the $6 \times 6$ damped plant with the optimal gain $g = 400$.

Load Data
%% Load Identification Data
meas_iff_struts = {};

for i = 1:6
    meas_iff_struts(i) = {load(sprintf('mat/iff_strut_%i_noise_g_400.mat', i), 't', 'Vexc', 'Vs', 'de', 'u')};
end
Spectral Analysis - Setup
%% Setup useful variables
% Sampling Time [s]
Ts = (meas_iff_struts{1}.t(end) - (meas_iff_struts{1}.t(1)))/(length(meas_iff_struts{1}.t)-1);

% Sampling Frequency [Hz]
Fs = 1/Ts;

% Hannning Windows
win = hanning(ceil(1*Fs));

% And we get the frequency vector
[~, f] = tfestimate(meas_iff_struts{1}.Vexc, meas_iff_struts{1}.de, win, [], [], 1/Ts);
DVF Plant
%% DVF Plant (transfer function from u to dLm)
G_iff_opt = {};

for i = 1:6
    G_iff_opt{i} = tfestimate(meas_iff_struts{i}.Vexc, meas_iff_struts{i}.de, win, [], [], 1/Ts);
end

/tdehaeze/test-bench-nano-hexapod/media/commit/597ec7551fae3a9354caf6a2e94a1f325c7754fa/figs/damped_iff_plant_comp_diagonal.png

Comparison of the diagonal elements of the transfer functions from $\bm{u}$ to $d\bm{\mathcal{L}}_m$ with active damping (IFF) applied with an optimal gain $g = 400$

/tdehaeze/test-bench-nano-hexapod/media/commit/597ec7551fae3a9354caf6a2e94a1f325c7754fa/figs/damped_iff_plant_comp_off_diagonal.png

Comparison of the off-diagonal elements of the transfer functions from $\bm{u}$ to $d\bm{\mathcal{L}}_m$ with active damping (IFF) applied with an optimal gain $g = 400$

With the IFF control strategy applied and the optimal gain used, the suspension modes are very well dapmed. Remains the undamped flexible modes of the APA, and the modes of the plates.

The Simscape model and the experimental results are in very good agreement.

Encoders fixed to the plates

Introduction   ignore