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

207 KiB

Nano-Hexapod - Test Bench


This report is also available as a pdf.


Introduction   ignore

This document is dedicated to the experimental study of the nano-hexapod shown in Figure fig:picture_bench_granite_nano_hexapod.

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

Here are the documentation of the equipment used for this test bench (lots of them are shwon in Figure fig:picture_bench_granite_overview):

  • 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/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/IMG_20210608_154722.jpg

In Figure fig:nano_hexapod_signals is shown a block diagram of the experimental setup. When possible, the notations are consistent with this diagram and summarized in Table tab:list_signals.

\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/bf808861adaabbe2122b3c05454eff4d524eaeac/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}$

This document is divided in the following sections:

Encoders fixed to the Struts - Dynamics

<<sec:encoders_struts>>

Introduction   ignore

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

It is divided in the following sections:

Identification of the dynamics

<<sec:enc_struts_plant_id>>

Introduction   ignore

Load Measurement 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

Transfer function from Actuator to Encoder

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 = zeros(length(f), 6, 6);

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

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/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 = zeros(length(f), 6, 6);

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

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

Measured FRF for the DVF plant

Transfer function from Actuator to Force Sensor

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 = zeros(length(f), 6, 6);

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

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/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 = zeros(length(f), 6, 6);

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

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

Measured FRF for the IFF plant

Save Identified Plants

save('matlab/mat/identified_plants_enc_struts.mat', 'f', 'Ts', 'G_iff', 'G_dvf')

Comparison with the Simscape Model

<<sec:enc_struts_comp_simscape>>

Introduction   ignore

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

Load measured FRF

%% Load data
load('identified_plants_enc_struts.mat', 'f', 'Ts', 'G_iff', 'G_dvf')

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, '/du'],  1, 'openinput');   io_i = io_i + 1; % Actuator Inputs
io(io_i) = linio([mdl, '/dum'],  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/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/enc_struts_iff_comp_simscape.png

Diagonal elements of the IFF Plant

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/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', 'flexible');
%% Identify the DVF Plant (transfer function from u to dLm)
clear io; io_i = 1;
io(io_i) = linio([mdl, '/du'],  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/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/enc_struts_dvf_comp_simscape.png

Diagonal elements of the DVF Plant

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

Off diagonal elements of the DVF Plant

Effect of a change in bending damping of the joints

%% Tested bending dampings [Nm/(rad/s)]
cRs = [1e-3, 5e-3, 1e-2, 5e-2, 1e-1];
%% Identify the DVF Plant (transfer function from u to dLm)
clear io; io_i = 1;
io(io_i) = linio([mdl, '/du'],  1, 'openinput');  io_i = io_i + 1; % Actuator Inputs
io(io_i) = linio([mdl, '/D'],  1, 'openoutput'); io_i = io_i + 1; % Encoders

Then the identification is performed for all the values of the bending damping.

%% Idenfity the transfer function from actuator to encoder for all bending dampins
Gs = {zeros(length(cRs), 1)};

for i = 1:length(cRs)
    n_hexapod = initializeNanoHexapodFinal('flex_bot_type', '4dof', ...
                                           'flex_top_type', '4dof', ...
                                           'motion_sensor_type', 'struts', ...
                                           'actuator_type', 'flexible', ...
                                           'flex_bot_cRx', cRs(i), ...
                                           'flex_bot_cRy', cRs(i), ...
                                           'flex_top_cRx', cRs(i), ...
                                           'flex_top_cRy', cRs(i));

    G = exp(-s*Ts)*linearize(mdl, io, 0.0, options);
    G.InputName  = {'Va1', 'Va2', 'Va3', 'Va4', 'Va5', 'Va6'};
    G.OutputName = {'dL1', 'dL2', 'dL3', 'dL4', 'dL5', 'dL6'};

    Gs(i) = {G};
end
  • Could be nice
  • Actual damping is very small

Effect of a change in damping factor of the APA

%% Tested bending dampings [Nm/(rad/s)]
xis = [1e-3, 5e-3, 1e-2, 5e-2, 1e-1];
%% Identify the DVF Plant (transfer function from u to dLm)
clear io; io_i = 1;
io(io_i) = linio([mdl, '/du'],  1, 'openinput');  io_i = io_i + 1; % Actuator Inputs
io(io_i) = linio([mdl, '/D'],  1, 'openoutput'); io_i = io_i + 1; % Encoders
%% Idenfity the transfer function from actuator to encoder for all bending dampins
Gs = {zeros(length(xis), 1)};

for i = 1:length(xis)
    n_hexapod = initializeNanoHexapodFinal('flex_bot_type', '4dof', ...
                                           'flex_top_type', '4dof', ...
                                           'motion_sensor_type', 'struts', ...
                                           'actuator_type', 'flexible', ...
                                           'actuator_xi', xis(i));

    G = exp(-s*Ts)*linearize(mdl, io, 0.0, options);
    G.InputName  = {'Va1', 'Va2', 'Va3', 'Va4', 'Va5', 'Va6'};
    G.OutputName = {'dL1', 'dL2', 'dL3', 'dL4', 'dL5', 'dL6'};

    Gs(i) = {G};
end

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/bode_Va_dL_effect_xi_damp.png

Effect of the APA damping factor $\xi$ on the dynamics from $u$ to $d\mathcal{L}$

Damping factor $\xi$ has a large impact on the damping of the "spurious resonances" at 200Hz and 300Hz.

Why is the damping factor does not change the damping of the first peak?

Effect of a change in stiffness damping coef of the APA

m_coef = 1e1;
%% Tested bending dampings [Nm/(rad/s)]
k_coefs = [1e-6, 5e-6, 1e-5, 5e-5, 1e-4];
%% Identify the DVF Plant (transfer function from u to dLm)
clear io; io_i = 1;
io(io_i) = linio([mdl, '/du'],  1, 'openinput');  io_i = io_i + 1; % Actuator Inputs
io(io_i) = linio([mdl, '/D'],  1, 'openoutput'); io_i = io_i + 1; % Encoders
%% Idenfity the transfer function from actuator to encoder for all bending dampins
Gs = {zeros(length(k_coefs), 1)};
n_hexapod = initializeNanoHexapodFinal('flex_bot_type', '4dof', ...
                                       'flex_top_type', '4dof', ...
                                       'motion_sensor_type', 'struts', ...
                                       'actuator_type', 'flexible');

for i = 1:length(k_coefs)
    k_coef = k_coefs(i);

    G = exp(-s*Ts)*linearize(mdl, io, 0.0, options);
    G.InputName  = {'Va1', 'Va2', 'Va3', 'Va4', 'Va5', 'Va6'};
    G.OutputName = {'dL1', 'dL2', 'dL3', 'dL4', 'dL5', 'dL6'};

    Gs(i) = {G};
end

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/bode_Va_dL_effect_k_coef.png

Effect of a change of the damping "stiffness coeficient" on the transfer function from $u$ to $d\mathcal{L}$

Effect of a change in mass damping coef of the APA

k_coef = 1e-6;
%% Tested bending dampings [Nm/(rad/s)]
m_coefs = [1e1, 5e1, 1e2, 5e2, 1e3];
%% Identify the DVF Plant (transfer function from u to dLm)
clear io; io_i = 1;
io(io_i) = linio([mdl, '/du'],  1, 'openinput');  io_i = io_i + 1; % Actuator Inputs
io(io_i) = linio([mdl, '/D'],  1, 'openoutput'); io_i = io_i + 1; % Encoders
%% Idenfity the transfer function from actuator to encoder for all bending dampins
Gs = {zeros(length(m_coefs), 1)};
n_hexapod = initializeNanoHexapodFinal('flex_bot_type', '4dof', ...
                                       'flex_top_type', '4dof', ...
                                       'motion_sensor_type', 'struts', ...
                                       'actuator_type', 'flexible');

for i = 1:length(m_coefs)
    m_coef = m_coefs(i);

    G = exp(-s*Ts)*linearize(mdl, io, 0.0, options);
    G.InputName  = {'Va1', 'Va2', 'Va3', 'Va4', 'Va5', 'Va6'};
    G.OutputName = {'dL1', 'dL2', 'dL3', 'dL4', 'dL5', 'dL6'};

    Gs(i) = {G};
end

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/bode_Va_dL_effect_m_coef.png

Effect of a change of the damping "mass coeficient" on the transfer function from $u$ to $d\mathcal{L}$

TODO Using Flexible model

d_aligns = [[-0.05,  -0.3,  0];
            [ 0,      0.5,  0];
            [-0.1,   -0.3,  0];
            [ 0,      0.3,  0];
            [-0.05,   0.05, 0];
            [0,       0,    0]]*1e-3;
d_aligns = zeros(6,3);
% d_aligns(1,:) = [-0.05,  -0.3,  0]*1e-3;
d_aligns(2,:) = [ 0,      0.3,  0]*1e-3;
%% Initialize Nano-Hexapod
n_hexapod = initializeNanoHexapodFinal('flex_bot_type', '4dof', ...
                                       'flex_top_type', '4dof', ...
                                       'motion_sensor_type', 'struts', ...
                                       'actuator_type', 'flexible', ...
                                       'actuator_d_align', d_aligns);

Why do we have smaller resonances when using flexible APA? On the test bench we have the same resonance as the 2DoF model. Could it be due to the compliance in other dof of the flexible model?

%% Identify the DVF Plant (transfer function from u to dLm)
clear io; io_i = 1;
io(io_i) = linio([mdl, '/du'],  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);
%% Identify the IFF Plant (transfer function from u to taum)
clear io; io_i = 1;
io(io_i) = linio([mdl, '/du'],  1, 'openinput');   io_i = io_i + 1; % Actuator Inputs
io(io_i) = linio([mdl, '/dum'],  1, 'openoutput'); io_i = io_i + 1; % Force Sensors

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

Flexible model + encoders fixed to the plates

%% Identify the IFF Plant (transfer function from u to taum)
clear io; io_i = 1;
io(io_i) = linio([mdl, '/du'],  1, 'openinput');   io_i = io_i + 1; % Actuator Inputs
io(io_i) = linio([mdl, '/D'],  1, 'openoutput'); io_i = io_i + 1; % Force Sensors
d_aligns = [[-0.05,  -0.3,  0];
            [ 0,      0.5,  0];
            [-0.1,   -0.3,  0];
            [ 0,      0.3,  0];
            [-0.05,   0.05, 0];
            [0,       0,    0]]*1e-3;
%% Initialize Nano-Hexapod
n_hexapod = initializeNanoHexapodFinal('flex_bot_type', '4dof', ...
                                       'flex_top_type', '4dof', ...
                                       'motion_sensor_type', 'struts', ...
                                       'actuator_type', 'flexible', ...
                                       'actuator_d_align', d_aligns);
Gdvf_struts = exp(-s*Ts)*linearize(mdl, io, 0.0, options);
%% Initialize Nano-Hexapod
n_hexapod = initializeNanoHexapodFinal('flex_bot_type', '4dof', ...
                                       'flex_top_type', '4dof', ...
                                       'motion_sensor_type', 'plates', ...
                                       'actuator_type', 'flexible', ...
                                       'actuator_d_align', d_aligns);
Gdvf_plates = exp(-s*Ts)*linearize(mdl, io, 0.0, options);

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/dvf_plant_comp_struts_plates.png

Comparison of the dynamics from $V_a$ to $d_L$ when the encoders are fixed to the struts (blue) and to the plates (red). APA are modeled as a flexible element.

Integral Force Feedback

<<sec:enc_struts_iff>>

Introduction   ignore

In this section, the Integral Force Feedback (IFF) control strategy is applied to the nano-hexapod. The main goal of this to add damping to the nano-hexapod's modes.

The control architecture is shown in Figure fig:control_architecture_iff_struts where $\bm{K}_\text{IFF}$ is a diagonal $6 \times 6$ controller.

The system as then a new input $\bm{u}^\prime$, and the transfer function from $\bm{u}^\prime$ to $d\bm{\mathcal{L}}_m$ should be easier to control than the initial transfer function from $\bm{u}$ to $d\bm{\mathcal{L}}_m$.

\begin{tikzpicture}
  % Blocs
  \node[block={3.0cm}{2.0cm}] (P) {Plant};
  \coordinate[] (inputF) at ($(P.south west)!0.5!(P.north west)$);
  \coordinate[] (outputF) at ($(P.south east)!0.7!(P.north east)$);
  \coordinate[] (outputL) at ($(P.south east)!0.3!(P.north east)$);

  \node[block, above=0.4 of P] (Kiff) {$\bm{K}_\text{IFF}$};
  \node[addb, left= of inputF] (addF) {};

  % Connections and labels
  \draw[->] (outputF) -- ++(1, 0) node[below left]{$\bm{\tau}_m$};
  \draw[->] (outputL) -- ++(1, 0) node[below left]{$d\bm{\mathcal{L}}_m$};

  \draw[->] ($(outputF) + (0.6, 0)$)node[branch]{} |- (Kiff.east);
  \draw[->] (Kiff.west) -| (addF.north);
  \draw[->] (addF.east) -- (inputF) node[above left]{$\bm{u}$};
  \draw[<-] (addF.west) -- ++(-1, 0) node[above right]{$\bm{u}^\prime$};
\end{tikzpicture}

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/control_architecture_iff_struts.png

Integral Force Feedback Strategy

This section is structured as follow:

  • Section sec:iff_struts_plant_id: Using the Simscape model (APA taken as 2DoF model), the transfer function from $\bm{u}$ to $\bm{\tau}_m$ is identified. Based on the obtained dynamics, the control law is developed and the optimal gain is estimated using the Root Locus.
  • Section sec:iff_struts_effect_plant: Still using the Simscape model, the effect of the IFF gain on the the transfer function from $\bm{u}^\prime$ to $d\bm{\mathcal{L}}_m$ is studied.
  • Section sec:iff_struts_effect_plant_exp: The same is performed experimentally: several IFF gains are used and the damped plant is identified each time.
  • Section sec:iff_struts_opt_gain: The damped model and the identified damped system are compared for the optimal IFF gain. It is found that IFF indeed adds a lot of damping into the system. However it is not efficient in damping the spurious struts modes.
  • Section sec:iff_struts_comp_flex_model: Finally, a "flexible" model of the APA is used in the Simscape model and the optimally damped model is compared with the measurements.

IFF Control Law and Optimal Gain

<<sec:iff_struts_plant_id>>

Let's use a model of the Nano-Hexapod with the encoders fixed to the struts and the APA taken as 2DoF model.

%% Initialize Nano-Hexapod
n_hexapod = initializeNanoHexapodFinal('flex_bot_type', '4dof', ...
                                       'flex_top_type', '4dof', ...
                                       'motion_sensor_type', 'struts', ...
                                       'actuator_type', '2dof');

The transfer function from $\bm{u}$ to $\bm{\tau}_m$ is identified.

%% Identify the IFF Plant (transfer function from u to taum)
clear io; io_i = 1;
io(io_i) = linio([mdl, '/du'],  1, 'openinput');   io_i = io_i + 1; % Actuator Inputs
io(io_i) = linio([mdl, '/dum'],  1, 'openoutput'); io_i = io_i + 1; % Force Sensors

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

The IFF controller is defined as shown below:

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

Then, the poles of the system are shown in the complex plane as a function of the controller gain (i.e. Root Locus plot) in Figure fig:enc_struts_iff_root_locus. A gain of $400$ is chosen as the "optimal" gain as it visually seems to be the gain that adds the maximum damping to all the suspension modes simultaneously.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/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 = 400*Kiff_g1;

And it is saved for further use.

save('mat/Kiff.mat', 'Kiff')

The bode plots of the "diagonal" elements of the loop gain are shown in Figure fig:enc_struts_iff_opt_loop_gain. It is shown that the phase and gain margins are quite high and the loop gain is large arround the resonances.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/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)$

Effect of IFF on the plant - Simulations

<<sec:iff_struts_effect_plant>>

Still using the Simscape model with encoders fixed to the struts and 2DoF APA, the IFF strategy is tested.

%% 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');

The following IFF gains are tried:

%% Tested IFF gains
iff_gains = [4, 10, 20, 40, 100, 200, 400];

And the transfer functions from $\bm{u}^\prime$ to $d\bm{\mathcal{L}}_m$ are identified for all the IFF gains.

%% 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, '/du'], 1, 'openinput');  io_i = io_i + 1; % Actuator Inputs
io(io_i) = linio([mdl, '/dL'], 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

The obtained dynamics are shown in Figure fig:enc_struts_iff_gains_effect_dvf_plant.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/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$

Effect of IFF on the plant - Experimental Results

<<sec:iff_struts_effect_plant_exp>>

Introduction   ignore

The IFF strategy is applied experimentally and the transfer function from $\bm{u}^\prime$ to $d\bm{\mathcal{L}}_m$ is identified for all the defined values of the gain.

Load Data

First load the identification 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

And define the useful variables that will be used for the identification using the tfestimate function.

%% 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

The transfer functions are estimated for all the values of the gain.

%% 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

The obtained dynamics as shown in the bode plot in Figure fig:comp_iff_gains_dvf_plant. The dashed curves are the results obtained using the model, and the solid curves the results from the experimental identification.

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

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

The bode plot is then zoomed on the suspension modes of the nano-hexapod in Figure fig:comp_iff_gains_dvf_plant_zoom.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/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).

Also, the experimental results and the models obtained from the Simscape model are in agreement concerning the damped system (up to the flexible modes).

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

The un-damped and damped experimental plants are compared in Figure fig:comp_undamped_opt_iff_gain_diagonal (diagonal terms).

It is very clear that all the suspension modes are very well damped thanks to IFF. However, there is little to no effect on the flexible modes of the struts and of the plate.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/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

<<sec:iff_struts_opt_gain>>

Introduction   ignore

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

Load Data

The experimental data are loaded.

%% 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

And the parameters useful for the spectral analysis are defined.

%% 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

Finally, the $6 \times 6$ plant is identified using the tfestimate function.

%% 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

The obtained diagonal elements are compared with the model in Figure fig:damped_iff_plant_comp_diagonal.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/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$

And all the off-diagonal elements are compared with the model in Figure fig:damped_iff_plant_comp_off_diagonal.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/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 damped. Remains the un-damped flexible modes of the APA (200Hz, 300Hz, 400Hz), and the modes of the plates (700Hz).

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

Comparison with the Flexible model

<<sec:iff_struts_comp_flex_model>>

When using the 2-DoF model for the APA, the flexible modes of the struts were not modelled, and it was the main limitation of the model. Now, let's use a flexible model for the APA, and see if the obtained damped plant using the model is similar to the measured dynamics.

First, the nano-hexapod is initialized.

%% Estimated misalignement of the struts
d_aligns = [[-0.05,  -0.3,  0];
            [ 0,      0.5,  0];
            [-0.1,   -0.3,  0];
            [ 0,      0.3,  0];
            [-0.05,   0.05, 0];
            [0,       0,    0]]*1e-3;


%% Initialize Nano-Hexapod
n_hexapod = initializeNanoHexapodFinal('flex_bot_type', '4dof', ...
                                       'flex_top_type', '4dof', ...
                                       'motion_sensor_type', 'struts', ...
                                       'actuator_type', 'flexible', ...
                                       'actuator_d_align', d_aligns, ...
                                       'controller_type', 'iff');

And the "optimal" controller is loaded.

%% Optimal IFF controller
load('Kiff.mat', 'Kiff');

The transfer function from $\bm{u}^\prime$ to $d\bm{\mathcal{L}}_m$ is identified using the Simscape model.

%% Linearized inputs/outputs
clear io; io_i = 1;
io(io_i) = linio([mdl, '/du'],  1, 'openinput');  io_i = io_i + 1; % Actuator Inputs
io(io_i) = linio([mdl, '/dL'],  1, 'openoutput'); io_i = io_i + 1; % Strut Displacement (encoder)

%% Identification of the plant
Gd_iff = exp(-s*Ts)*linearize(mdl, io, 0.0, options);

The obtained diagonal elements are shown in Figure fig:enc_struts_iff_opt_damp_comp_flex_model_diag while the off-diagonal elements are shown in Figure fig:enc_struts_iff_opt_damp_comp_flex_model_off_diag.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/enc_struts_iff_opt_damp_comp_flex_model_diag.png

Diagonal elements of the transfer function from $\bm{u}^\prime$ to $d\bm{\mathcal{L}}_m$ - comparison of the measured FRF and the identified dynamics using the flexible model

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/enc_struts_iff_opt_damp_comp_flex_model_off_diag.png

Off-diagonal elements of the transfer function from $\bm{u}^\prime$ to $d\bm{\mathcal{L}}_m$ - comparison of the measured FRF and the identified dynamics using the flexible model

Using flexible models for the APA, the agreement between the Simscape model of the nano-hexapod and the measured FRF is very good.

Only the flexible mode of the top-plate is not appearing in the model which is very logical as the top plate is taken as a solid body.

Conclusion

The decentralized Integral Force Feedback strategy applied on the nano-hexapod is very effective in damping all the suspension modes.

The Simscape model (especially when using a flexible model for the APA) is shown to be very accurate, even when IFF is applied.

Modal Analysis

<<sec:enc_struts_modal_analysis>>

Introduction   ignore

Several 3-axis accelerometers are fixed on the top platform of the nano-hexapod as shown in Figure fig:compliance_vertical_comp_iff.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/accelerometers_nano_hexapod.jpg

The top platform is then excited using an instrumented hammer as shown in Figure fig:hammer_excitation_compliance_meas.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/hammer_excitation_compliance_meas.jpg

From this experiment, the resonance frequencies and the associated mode shapes can be computed (Section sec:modal_analysis_mode_shapes). Then, in Section sec:compliance_effect_iff, the vertical compliance of the nano-hexapod is experimentally estimated. Finally, in Section sec:compliance_effect_iff_comp_model, the measured compliance is compare with the estimated one from the Simscape model.

Obtained Mode Shapes

<<sec:modal_analysis_mode_shapes>>

We can observe the mode shapes of the first 6 modes that are the suspension modes (the plate is behaving as a solid body) in Figure fig:mode_shapes_annotated.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/mode_shapes_annotated.gif

Then, there is a mode at 692Hz which corresponds to a flexible mode of the top plate (Figure fig:mode_shapes_flexible_annotated).

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/ModeShapeFlex1_crop.gif

The obtained modes are summarized in Table tab:description_modes.

Mode Freq. [Hz] Description
1 105 Suspension Mode: Y-translation
2 107 Suspension Mode: X-translation
3 131 Suspension Mode: Z-translation
4 161 Suspension Mode: Y-tilt
5 162 Suspension Mode: X-tilt
6 180 Suspension Mode: Z-rotation
7 692 (flexible) Membrane mode of the top platform

Nano-Hexapod Compliance - Effect of IFF

<<sec:compliance_effect_iff>>

In this section, we wish to estimated the effectiveness of the IFF strategy concerning the compliance.

The top plate is excited vertically using the instrumented hammer two times:

  1. no control loop is used
  2. decentralized IFF is used

The data is loaded.

frf_ol  = load('Measurement_Z_axis.mat'); % Open-Loop
frf_iff = load('Measurement_Z_axis_damped.mat'); % IFF

The mean vertical motion of the top platform is computed by averaging all 5 accelerometers.

%% Multiply by 10 (gain in m/s^2/V) and divide by 5 (number of accelerometers)
d_frf_ol = 10/5*(frf_ol.FFT1_H1_4_1_RMS_Y_Mod + frf_ol.FFT1_H1_7_1_RMS_Y_Mod + frf_ol.FFT1_H1_10_1_RMS_Y_Mod + frf_ol.FFT1_H1_13_1_RMS_Y_Mod + frf_ol.FFT1_H1_16_1_RMS_Y_Mod)./(2*pi*frf_ol.FFT1_H1_16_1_RMS_X_Val).^2;
d_frf_iff = 10/5*(frf_iff.FFT1_H1_4_1_RMS_Y_Mod + frf_iff.FFT1_H1_7_1_RMS_Y_Mod + frf_iff.FFT1_H1_10_1_RMS_Y_Mod + frf_iff.FFT1_H1_13_1_RMS_Y_Mod + frf_iff.FFT1_H1_16_1_RMS_Y_Mod)./(2*pi*frf_iff.FFT1_H1_16_1_RMS_X_Val).^2;

The vertical compliance (magnitude of the transfer function from a vertical force applied on the top plate to the vertical motion of the top plate) is shown in Figure fig:compliance_vertical_comp_iff.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/compliance_vertical_comp_iff.png

Measured vertical compliance with and without IFF

From Figure fig:compliance_vertical_comp_iff, it is clear that the IFF control strategy is very effective in damping the suspensions modes of the nano-hexapod. It also has the effect of (slightly) degrading the vertical compliance at low frequency.

It also seems some damping can be added to the modes at around 205Hz which are flexible modes of the struts.

Comparison with the Simscape Model

<<sec:compliance_effect_iff_comp_model>>

Let's now compare the measured vertical compliance with the vertical compliance as estimated from the Simscape model.

The transfer function from a vertical external force to the absolute motion of the top platform is identified (with and without IFF) using the Simscape model.

The comparison is done in Figure fig:compliance_vertical_comp_model_iff. Again, the model is quite accurate!

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/compliance_vertical_comp_model_iff.png

Measured vertical compliance with and without IFF

Conclusion

From the previous analysis, several conclusions can be drawn:

Therefore, in the following sections, the encoders will be fixed to the plates. The goal is to be less sensitive to the flexible modes of the struts.

Encoders fixed to the plates - Dynamics

<<sec:encoders_plates>>

Introduction   ignore

In this section, the encoders are fixed to the plates rather than to the struts as shown in Figure fig:enc_fixed_to_struts.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/IMG_20210625_083801.jpg

It is structured as follow:

  • Section sec:enc_plates_plant_id: The dynamics of the nano-hexapod is identified.
  • Section sec:enc_plates_comp_simscape: The identified dynamics is compared with the Simscape model.
  • Section sec:enc_plates_iff: The Integral Force Feedback (IFF) control strategy is applied and the dynamics of the damped nano-hexapod is identified and compare with the Simscape model.

Identification of the dynamics

<<sec:enc_plates_plant_id>>

Introduction   ignore

In this section, the dynamics of the nano-hexapod with the encoders fixed to the plates is identified.

First, the measurement data are loaded in Section sec:enc_plates_plant_id_setup, then the transfer function matrix from the actuators to the encoders are estimated in Section sec:enc_plates_plant_id_dvf. Finally, the transfer function matrix from the actuators to the force sensors is estimated in Section sec:enc_plates_plant_id_iff.

Data Loading and Spectral Analysis Setup

<<sec:enc_plates_plant_id_setup>>

The actuators are excited one by one using a low pass filtered white noise. For each excitation, the 6 force sensors and 6 encoders are measured and saved.

%% Load Identification Data
meas_data_lf = {};

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

Transfer function from Actuator to Encoder

<<sec:enc_plates_plant_id_dvf>>

Let's compute the coherence from the excitation voltage $\bm{u}$ and the displacement $d\bm{\mathcal{L}}_m$ as measured by the encoders.

%% Coherence
coh_dvf = zeros(length(f), 6, 6);

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

The obtained coherence shown in Figure fig:enc_plates_dvf_coh is quite good up to 400Hz.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/enc_plates_dvf_coh.png

Obtained coherence for the DVF plant

Then the 6x6 transfer function matrix is estimated.

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

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

The diagonal and off-diagonal terms of this transfer function matrix are shown in Figure fig:enc_plates_dvf_frf.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/enc_plates_dvf_frf.png

Measured FRF for the DVF plant

From Figure fig:enc_plates_dvf_frf, we can draw few conclusions on the transfer functions from $\bm{u}$ to $d\bm{\mathcal{L}}_m$ when the encoders are fixed to the plates:

  • the decoupling is rather good at low frequency (below the first suspension mode). The low frequency gain is constant for the off diagonal terms, whereas when the encoders where fixed to the struts, the low frequency gain of the off-diagonal terms were going to zero (Figure fig:enc_struts_dvf_frf).
  • the flexible modes of the struts at 226Hz and 337Hz are indeed shown in the transfer functions, but their amplitudes are rather low.
  • the diagonal terms have alternating poles and zeros up to at least 600Hz: the flexible modes of the struts are not affecting the alternating pole/zero pattern. This what not the case when the encoders were fixed to the struts (Figure fig:enc_struts_dvf_frf).

Transfer function from Actuator to Force Sensor

<<sec:enc_plates_plant_id_iff>>

Let's now compute the coherence from the excitation voltage $\bm{u}$ and the voltage $\bm{\tau}_m$ generated by the Force senors.

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

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

The coherence is shown in Figure fig:enc_plates_iff_coh, and is very good for from 10Hz up to 2kHz.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/enc_plates_iff_coh.png

Obtained coherence for the IFF plant

Then the 6x6 transfer function matrix is estimated.

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

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

The bode plot of the diagonal and off-diagonal terms are shown in Figure fig:enc_plates_iff_frf.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/enc_plates_iff_frf.png

Measured FRF for the IFF plant

It is shown in Figure fig:enc_plates_iff_comp_simscape_all that:

  • The IFF plant has alternating poles and zeros
  • The first flexible mode of the struts as 235Hz is appearing, and therefore is should be possible to add some damping to this mode using IFF
  • The decoupling is quite good at low frequency (below the first model) as well as high frequency (above the last suspension mode, except near the flexible modes of the top plate)

Save Identified Plants

The identified dynamics is saved for further use.

save('mat/identified_plants_enc_plates.mat', 'f', 'Ts', 'G_iff', 'G_dvf')

Comparison with the Simscape Model

<<sec:enc_plates_comp_simscape>>

Introduction   ignore

In this section, the measured dynamics done in Section sec:enc_plates_plant_id is compared with the dynamics estimated from the Simscape model.

Identification Setup

The nano-hexapod is initialized with the APA taken as flexible models.

%% Initialize Nano-Hexapod
n_hexapod = initializeNanoHexapodFinal('flex_bot_type', '4dof', ...
                                       'flex_top_type', '4dof', ...
                                       'motion_sensor_type', 'plates', ...
                                       'actuator_type', 'flexible');

Dynamics from Actuator to Force Sensors

Then the transfer function from $\bm{u}$ to $\bm{\tau}_m$ is identified using the Simscape model.

%% Identify the IFF Plant (transfer function from u to taum)
clear io; io_i = 1;
io(io_i) = linio([mdl, '/du'],  1, 'openinput');   io_i = io_i + 1; % Actuator Inputs
io(io_i) = linio([mdl, '/dum'],  1, 'openoutput'); io_i = io_i + 1; % Force Sensors

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

The identified dynamics is compared with the measured FRF:

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/enc_plates_iff_comp_simscape_all.png

IFF Plant for the first actuator input and all the force senosrs

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/enc_plates_iff_comp_simscape.png

Diagonal elements of the IFF Plant

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/enc_plates_iff_comp_offdiag_simscape.png

Off diagonal elements of the IFF Plant

Dynamics from Actuator to Encoder

Now, the dynamics from the DAC voltage $\bm{u}$ to the encoders $d\bm{\mathcal{L}}_m$ is estimated using the Simscape model.

%% Identify the DVF Plant (transfer function from u to dLm)
clear io; io_i = 1;
io(io_i) = linio([mdl, '/du'],  1, 'openinput');  io_i = io_i + 1; % Actuator Inputs
io(io_i) = linio([mdl, '/dL'], 1, 'openoutput'); io_i = io_i + 1; % Encoders

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

The identified dynamics is compared with the measured FRF:

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/enc_plates_dvf_comp_simscape_all.png

DVF Plant for the first actuator input and all the encoders

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/enc_plates_dvf_comp_simscape.png

Diagonal elements of the DVF Plant

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/enc_plates_dvf_comp_offdiag_simscape.png

Off diagonal elements of the DVF Plant

Conclusion

The Simscape model is quite accurate for the transfer function matrices from $\bm{u}$ to $\bm{\tau}_m$ and from $\bm{u}$ to $d\bm{\mathcal{L}}_m$ except at frequencies of the flexible modes of the top-plate. The Simscape model can therefore be used to develop the control strategies.

Integral Force Feedback

<<sec:enc_plates_iff>>

Introduction   ignore

In this section, the Integral Force Feedback (IFF) control strategy is applied to the nano-hexapod in order to add damping to the suspension modes.

The control architecture is shown in Figure fig:control_architecture_iff:

  • $\bm{\tau}_m$ is the measured voltage of the 6 force sensors
  • $\bm{K}_{\text{IFF}}$ is the $6 \times 6$ diagonal controller
  • $\bm{u}$ is the plant input (voltage generated by the 6 DACs)
  • $\bm{u}^\prime$ is the new plant inputs with added damping
\begin{tikzpicture}
  % Blocs
  \node[block={3.0cm}{2.0cm}] (P) {Plant};
  \coordinate[] (inputF) at ($(P.south west)!0.5!(P.north west)$);
  \coordinate[] (outputF) at ($(P.south east)!0.7!(P.north east)$);
  \coordinate[] (outputL) at ($(P.south east)!0.3!(P.north east)$);

  \node[block, above=0.4 of P] (Kiff) {$\bm{K}_\text{IFF}$};
  \node[addb, left= of inputF] (addF) {};

  % Connections and labels
  \draw[->] (outputF) -- ++(1, 0) node[below left]{$\bm{\tau}_m$};
  \draw[->] (outputL) -- ++(1, 0) node[below left]{$d\bm{\mathcal{L}}_m$};

  \draw[->] ($(outputF) + (0.6, 0)$)node[branch]{} |- (Kiff.east);
  \draw[->] (Kiff.west) -| (addF.north);
  \draw[->] (addF.east) -- (inputF) node[above left]{$\bm{u}$};
  \draw[<-] (addF.west) -- ++(-1, 0) node[above right]{$\bm{u}^\prime$};
\end{tikzpicture}

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/control_architecture_iff.png

Integral Force Feedback Strategy

Effect of IFF on the plant - Simscape Model

<<sec:enc_struts_effect_iff_plant>>

The nano-hexapod is initialized with flexible APA and the encoders fixed to the struts.

%% Initialize the Simscape model in closed loop
n_hexapod = initializeNanoHexapodFinal('flex_bot_type', '4dof', ...
                                       'flex_top_type', '4dof', ...
                                       'motion_sensor_type', 'plates', ...
                                       'actuator_type', 'flexible');

The same controller as the one developed when the encoder were fixed to the struts is used.

%% Optimal IFF controller
load('Kiff.mat', 'Kiff')

The transfer function from $\bm{u}^\prime$ to $d\bm{\mathcal{L}}_m$ is identified.

%% Identify the (damped) transfer function from u to dLm for different values of the IFF gain
clear io; io_i = 1;
io(io_i) = linio([mdl, '/du'],  1, 'openinput');  io_i = io_i + 1; % Actuator Inputs
io(io_i) = linio([mdl, '/dL'], 1, 'openoutput'); io_i = io_i + 1; % Plate Displacement (encoder)

First in Open-Loop:

%% Transfer function from u to dL (open-loop)
Gd_ol = exp(-s*Ts)*linearize(mdl, io, 0.0, options);

And then with the IFF controller:

%% Initialize the Simscape model in closed loop
n_hexapod = initializeNanoHexapodFinal('flex_bot_type', '4dof', ...
                                       'flex_top_type', '4dof', ...
                                       'motion_sensor_type', 'plates', ...
                                       'actuator_type', 'flexible', ...
                                       'controller_type', 'iff');

%% Transfer function from u to dL (IFF)
Gd_iff = exp(-s*Ts)*linearize(mdl, io, 0.0, options);

It is first verified that the system is stable:

isstable(Gd_iff)
1

The diagonal and off-diagonal terms of the $6 \times 6$ transfer function matrices identified are compared in Figure fig:enc_plates_iff_gains_effect_dvf_plant. It is shown, as was the case when the encoders were fixed to the struts, that the IFF control strategy is very effective in damping the suspension modes of the nano-hexapod.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/enc_plates_iff_gains_effect_dvf_plant.png

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

Effect of IFF on the plant - FRF

The IFF control strategy is experimentally implemented. The (damped) transfer function from $\bm{u}^\prime$ to $d\bm{\mathcal{L}}_m$ is experimentally identified.

The identification data are loaded:

%% Load Identification Data
meas_iff_plates = {};

for i = 1:6
    meas_iff_plates(i) = {load(sprintf('mat/frf_exc_iff_strut_%i_enc_plates_noise.mat', i), 't', 'Va', 'Vs', 'de', 'u')};
end

And the parameters used for the transfer function estimation are defined below.

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

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

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

The estimation is performed using the tfestimate command.

%% Estimation of the transfer function matrix from u to dL when IFF is applied
G_enc_iff_opt = zeros(length(f), 6, 6);

for i = 1:6
    G_enc_iff_opt(:,:,i) = tfestimate(meas_iff_plates{i}.Va, meas_iff_plates{i}.de, win, [], [], 1/Ts);
end

The obtained diagonal and off-diagonal elements of the transfer function from $\bm{u}^\prime$ to $d\bm{\mathcal{L}}_m$ are shown in Figure fig:enc_plant_plates_effect_iff both without and with IFF.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/enc_plant_plates_effect_iff.png

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

As was predicted with the Simscape model, the IFF control strategy is very effective in damping the suspension modes of the nano-hexapod. Little damping is also applied on the first flexible mode of the strut at 235Hz. However, no damping is applied on other modes, such as the flexible modes of the top plate.

Comparison of the measured FRF and the Simscape model

Let's now compare the obtained damped plants obtained experimentally with the one extracted from Simscape:

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/enc_plates_opt_iff_comp_simscape_all.png

FRF from one actuator to all the encoders when the plant is damped using IFF

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/damped_iff_plates_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/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/damped_iff_plates_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$

From Figures fig:damped_iff_plates_plant_comp_diagonal and fig:damped_iff_plates_plant_comp_off_diagonal, it is clear that the Simscape model very well represents the dynamics of the nano-hexapod. This is true to around 400Hz, then the dynamics depends on the flexible modes of the top plate which are not modelled.

Save Damped Plant

The experimentally identified plant is saved for further use.

save('matlab/mat/damped_plant_enc_plates.mat', 'f', 'Ts', 'G_enc_iff_opt')
save('mat/damped_plant_enc_plates.mat', 'f', 'Ts', 'G_enc_iff_opt')

Conclusion

In this section, the dynamics of the nano-hexapod with the encoders fixed to the plates is studied.

It has been found that:

  • The measured dynamics is in agreement with the dynamics of the simscape model, up to the flexible modes of the top plate. See figures fig:enc_plates_iff_comp_simscape and fig:enc_plates_iff_comp_offdiag_simscape for the transfer function to the force sensors and Figures fig:enc_plates_dvf_comp_simscape and fig:enc_plates_dvf_comp_offdiag_simscapefor the transfer functions to the encoders
  • The Integral Force Feedback strategy is very effective in damping the suspension modes of the nano-hexapod (Figure fig:enc_plant_plates_effect_iff).
  • The transfer function from $\bm{u}^\prime$ to $d\bm{\mathcal{L}}_m$ show nice dynamical properties and is a much better candidate for the high-authority-control than when the encoders were fixed to the struts. At least up to the flexible modes of the top plate, the diagonal elements of the transfer function matrix have alternating poles and zeros, and the phase is moving smoothly. Only the flexible modes of the top plates seems to be problematic for control.

Decentralized High Authority Control with Integral Force Feedback

<<sec:decentralized_hac_iff>>

Introduction   ignore

In this section is studied the HAC-LAC architecture for the Nano-Hexapod. More precisely:

  • The LAC control is a decentralized force feedback as studied in Section sec:enc_plates_iff
  • The HAC control is a decentralized controller working in the frame of the struts

The corresponding control architecture is shown in Figure fig:control_architecture_hac_iff_struts with:

  • $\bm{r}_{\mathcal{X}_n}$: the $6 \times 1$ reference signal in the cartesian frame
  • $\bm{r}_{d\mathcal{L}}$: the $6 \times 1$ reference signal transformed in the frame of the struts thanks to the inverse kinematic
  • $\bm{\epsilon}_{d\mathcal{L}}$: the $6 \times 1$ length error of the 6 struts
  • $\bm{u}^\prime$: input of the damped plant
  • $\bm{u}$: generated DAC voltages
  • $\bm{\tau}_m$: measured force sensors
  • $d\bm{\mathcal{L}}_m$: measured displacement of the struts by the encoders
\begin{tikzpicture}
  % Blocs
  \node[block={3.0cm}{2.0cm}] (P) {Plant};
  \coordinate[] (inputF) at ($(P.south west)!0.5!(P.north west)$);
  \coordinate[] (outputF) at ($(P.south east)!0.8!(P.north east)$);
  \coordinate[] (outputL) at ($(P.south east)!0.2!(P.north east)$);

  \node[block, above=0.4 of P] (Kiff) {$\bm{K}_\text{IFF}$};
  \node[addb, left= of inputF] (addF) {};
  \node[block, left= of addF] (K) {$\bm{K}_\mathcal{L}$};
  \node[addb={+}{}{}{}{-}, left= of K] (subr) {};
  \node[block, align=center, left= of subr] (J) {Inverse\\Kinematics};

  % Connections and labels
  \draw[->] (outputF) -- ++(1, 0) node[below left]{$\bm{\tau}_m$};
  \draw[->] ($(outputF) + (0.6, 0)$)node[branch]{} |- (Kiff.east);
  \draw[->] (Kiff.west) -| (addF.north);
  \draw[->] (addF.east) -- (inputF) node[above left]{$\bm{u}$};

  \draw[->] (outputL) -- ++(1, 0) node[above left]{$d\bm{\mathcal{L}_m}$};
  \draw[->] ($(outputL) + (0.6, 0)$)node[branch]{} -- ++(0, -1) -| (subr.south);
  \draw[->] (subr.east) -- (K.west) node[above left]{$\bm{\epsilon}_{d\mathcal{L}}$};
  \draw[->] (K.east) -- (addF.west) node[above left]{$\bm{u}^\prime$};

  \draw[->] (J.east) -- (subr.west) node[above left]{$\bm{r}_{d\mathcal{L}}$};
  \draw[<-] (J.west)node[above left]{$\bm{r}_{\mathcal{X}_n}$} -- ++(-1, 0);
\end{tikzpicture}

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/control_architecture_hac_iff_struts.png

HAC-LAC: IFF + Control in the frame of the legs

High Authority Controller

<<sec:hac_iff_struts_controller>>

Introduction   ignore

In this section, the decentralized high authority controller $\bm{K}_{\mathcal{L}}$ is first tuned using the Simscape model.

Simscape Model

First initialized the nano-hexapod with a flexible APA model and with the IFF control strategy.

%% Initialize the Simscape model
n_hexapod = initializeNanoHexapodFinal('flex_bot_type', '4dof', ...
                                       'flex_top_type', '4dof', ...
                                       'motion_sensor_type', 'plates', ...
                                       'actuator_type', 'flexible', ...
                                       'controller_type', 'iff');

Then the controller is loaded

%% Load the decentralized IFF controller
load('Kiff.mat', 'Kiff')

The inputs and outputs for the transfer function estimation are defined.

%% Identify the (damped) transfer function from u to dLm for different values of the IFF gain
clear io; io_i = 1;
io(io_i) = linio([mdl, '/du'],  1, 'openinput');  io_i = io_i + 1; % Actuator Inputs
io(io_i) = linio([mdl, '/dL'], 1, 'openoutput'); io_i = io_i + 1; % Plate Displacement (encoder)

And the plant from $\bm{u}^\prime$ to $d\bm{\mathcal{L}}_m$ is identified and the bode plot of its diagonal terms are shown in Figure fig:hac_iff_struts_enc_plates_plant_bode.

%% Identified of the damped TF from u' to dL
Gd_iff_opt = exp(-s*Ts)*linearize(mdl, io, 0.0, options);

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/hac_iff_struts_enc_plates_plant_bode.png

Transfer functions from $u$ to $d\mathcal{L}_m$ with IFF (diagonal and off-diagonal elements)

HAC Controller

Let's first try to design a first decentralized controller with:

  • a bandwidth of 100Hz
  • sufficient phase margin
  • simple and understandable components

After some very basic and manual loop shaping, the following controller is developed:

%% Lead to increase phase margin
a  = 2;  % Amount of phase lead / width of the phase lead / high frequency gain
wc = 2*pi*100; % Frequency with the maximum phase lead [rad/s]

H_lead = (1 + s/(wc/sqrt(a)))/(1 + s/(wc*sqrt(a)));

%% Low Pass filter to increase robustness
H_lpf = 1/(1 + s/2/pi/200);

%% Notch at the top-plate resonance
gm = 0.02;
xi = 0.3;
wn = 2*pi*700;

H_notch = (s^2 + 2*gm*xi*wn*s + wn^2)/(s^2 + 2*xi*wn*s + wn^2);

%% Decentralized HAC
Khac_iff_struts = -(1/(2.87e-5)) * ... % Gain
                  H_lead * ...       % Lead
                  H_notch * ...      % Notch
                  (2*pi*100/s) * ... % Integrator
                  eye(6);            % 6x6 Diagonal

This controller is saved for further use.

save('mat/Khac_iff_struts.mat', 'Khac_iff_struts')

The Loop Gain is computed and shown in Figure fig:loop_gain_hac_iff_struts.

Lhac_iff_struts = Khac_iff_struts*Gd_iff_opt;

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/loop_gain_hac_iff_struts.png

Diagonal and off-diagonal elements of the Loop gain for "HAC-IFF-Struts"

Verification of the Stability using the Simscape model

The HAC-IFF control strategy is implemented using Simscape.

%% Initialize the Simscape model in closed loop
n_hexapod = initializeNanoHexapodFinal('flex_bot_type', '4dof', ...
                                       'flex_top_type', '4dof', ...
                                       'motion_sensor_type', 'plates', ...
                                       'actuator_type', 'flexible', ...
                                       'controller_type', 'hac-iff-struts');

We identify the closed-loop system.

%% Identification
Gd_iff_hac_opt = linearize(mdl, io, 0.0, options);

And verify that it is indeed stable.

%% Verify the stability
isstable(Gd_iff_hac_opt)
1

Experimental Loop Gain

Now, the loop gain is estimated from the measured FRF.

L_frf = zeros(size(G_enc_iff_opt));

for i = 1:size(G_enc_iff_opt, 1)
    L_frf(i, :, :) = squeeze(G_enc_iff_opt(i,:,:))*freqresp(Khac_iff_struts, f(i), 'Hz');
end

The bode plot of the loop gain is shown in Figure fig:hac_iff_plates_exp_loop_gain_diag.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/hac_iff_plates_exp_loop_gain_diag.png

Diagonal and Off-diagonal elements of the Loop gain (experimental data)

Reference Tracking - Trajectories

<<sec:hac_iff_struts_ref_track>>

Introduction   ignore

In this section, several trajectories representing the wanted pose (position and orientation) of the top platform with respect to the bottom platform are defined.

These trajectories will be used to test the HAC-LAC architecture.

In order to transform the wanted pose to the wanted displacement of the 6 struts, the inverse kinematic is required. As a first approximation, the Jacobian matrix can be used instead of using the full inverse kinematic equations.

Therefore, the control architecture with the input trajectory $\bm{r}_{\mathcal{X}_n}$ is shown in Figure fig:control_architecture_hac_iff_L.

\begin{tikzpicture}
  % Blocs
  \node[block={3.0cm}{3.0cm}] (P) {Plant};
  \coordinate[] (inputF) at ($(P.south west)!0.5!(P.north west)$);
  \coordinate[] (outputF) at ($(P.south east)!0.8!(P.north east)$);
  \coordinate[] (outputL) at ($(P.south east)!0.2!(P.north east)$);

  \node[block, above=0.4 of P] (Kiff) {$\bm{K}_\text{IFF}$};
  \node[addb, left= of inputF] (addF) {};
  \node[block, left= of addF] (K) {$\bm{K}_\mathcal{L}$};
  \node[addb={+}{}{}{}{-}, left= of K] (subr) {};
  \node[block, left= of subr] (J) {$J$};

  % Connections and labels
  \draw[->] (outputF) -- ++(1, 0) node[below left]{$\bm{\tau}_m$};
  \draw[->] ($(outputF) + (0.6, 0)$)node[branch]{} |- (Kiff.east);
  \draw[->] (Kiff.west) -| (addF.north);
  \draw[->] (addF.east) -- (inputF) node[above left]{$\bm{u}$};

  \draw[->] (outputL) -- ++(1, 0) node[above left]{$d\bm{\mathcal{L}}$};
  \draw[->] ($(outputL) + (0.6, 0)$)node[branch]{} -- ++(0, -1) -| (subr.south);
  \draw[->] (subr.east) -- (K.west) node[above left]{$\bm{\epsilon}_{d\mathcal{L}_m}$};
  \draw[->] (K.east) -- (addF.west) node[above left]{$\bm{u}^\prime$};

  \draw[->] (J.east) -- (subr.west) node[above left]{$\bm{r}_{d\mathcal{L}}$};
  \draw[<-] (J.west)node[above left]{$\bm{r}_{\mathcal{X}_n}$} -- ++(-1, 0);
\end{tikzpicture}

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/control_architecture_hac_iff_L.png

HAC-LAC: IFF + Control in the frame of the legs

In the following sections, several reference trajectories are defined:

Y-Z Scans

<<sec:yz_scans>>

Generate the Scan

A function generateYZScanTrajectory has been developed (accessible here) in order to easily generate scans in the Y-Z plane.

For instance, the following generated trajectory is represented in Figure fig:yz_scan_example_trajectory_yz_plane.

%% Generate the Y-Z trajectory scan
Rx_yz = generateYZScanTrajectory(...
    'y_tot', 4e-6, ... % Length of Y scans [m]
    'z_tot', 8e-6, ... % Total Z distance [m]
    'n', 5, ...     % Number of Y scans
    'Ts', 1e-3, ... % Sampling Time [s]
    'ti', 2, ...    % Time to go to initial position [s]
    'tw', 0.5, ...  % Waiting time between each points [s]
    'ty', 2, ...    % Time for a scan in Y [s]
    'tz', 1);       % Time for a scan in Z [s]

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/yz_scan_example_trajectory_yz_plane.png

Generated scan in the Y-Z plane

The Y and Z positions as a function of time are shown in Figure fig:yz_scan_example_trajectory.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/yz_scan_example_trajectory.png

Y and Z trajectories as a function of time
Reference Signal for the Strut lengths

Using the Jacobian matrix, it is possible to compute the wanted struts lengths as a function of time:

\begin{equation} \bm{r}_{d\mathcal{L}} = \bm{J} \bm{r}_{\mathcal{X}_n} \end{equation}
dL_ref = [n_hexapod.geometry.J*Rx_yz(:, 2:7)']';

The reference signal for the strut length is shown in Figure fig:yz_scan_example_trajectory_struts.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/yz_scan_example_trajectory_struts.png

Trajectories for the 6 individual struts
Time domain simulation with 2DoF model

Before trying to follow this reference with the nano-hexapod, let's try to do it using the Simscape model.

The nano-hexapod is initialized with the APA modelled as 2DoF system (for the simulation to run quickly).

%% Initialize the Simscape model in closed loop
n_hexapod = initializeNanoHexapodFinal('flex_bot_type', '2dof', ...
                                       'flex_top_type', '3dof', ...
                                       'motion_sensor_type', 'plates', ...
                                       'actuator_type', '2dof', ...
                                       'controller_type', 'hac-iff-struts');

The reference path as well as the measured motion are compared in Figure fig:ref_track_hac_iff_struts_yz_plane.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/ref_track_hac_iff_struts_yz_plane.png

Simulated Y-Z motion

The motion errors are computed and shown in Figure fig:ref_track_hac_iff_struts_pos_error. It is clear that the hexapod is indeed tracking the reference path. However, in this simulation, no disturbances are included nor sensor noises.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/ref_track_hac_iff_struts_pos_error.png

Positioning errors as a function of time

TODO Tilt Scans

<<sec:tilt_scans>>

"NASS" reference path

<<sec:nass_scans>> In this section, a reference path that "draws" the work "NASS" is developed.

First, a series of points representing each letter are defined. Between each letter, a negative Z motion is performed.

%% List of points that draws "NASS"
ref_path = [ ...
    0, 0,0; % Initial Position
    0,0,1; 0,4,1; 3,0,1; 3,4,1; % N
    3,4,0; 4,0,0; % Transition
    4,0,1; 4,3,1; 5,4,1; 6,4,1; 7,3,1; 7,2,1; 4,2,1; 4,3,1; 5,4,1; 6,4,1; 7,3,1; 7,0,1; % A
    7,0,0; 8,0,0; % Transition
    8,0,1; 11,0,1; 11,2,1; 8,2,1; 8,4,1; 11,4,1; % S
    11,4,0; 12,0,0; % Transition
    12,0,1; 15,0,1; 15,2,1; 12,2,1; 12,4,1; 15,4,1; % S
    15,4,0;
           ];

%% Center the trajectory arround zero
ref_path = ref_path - (max(ref_path) - min(ref_path))/2;

%% Define the X-Y-Z cuboid dimensions containing the trajectory
X_max = 10e-6;
Y_max =  4e-6;
Z_max =  2e-6;

ref_path = ([X_max, Y_max, Z_max]./max(ref_path)).*ref_path; % [m]

Then, using the generateXYZTrajectory function, the $6 \times 1$ trajectory signal is computed.

%% Generating the trajectory
Rx_nass = generateXYZTrajectory('points', ref_path);

The trajectory in the X-Y plane is shown in Figure fig:ref_track_test_nass (the transitions between the letters are removed).

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/ref_track_test_nass.png

Reference path corresponding to the "NASS" acronym

It can also be better viewed in a 3D representation as in Figure fig:ref_track_test_nass_3d.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/ref_track_test_nass_3d.png

Reference path that draws "NASS" - 3D view

First Experimental Tests with the HAC

<<sec:hac_iff_struts_first_tests>>

Introduction   ignore

Both the Integral Force Feedback controller (developed in Section sec:enc_plates_iff) and the high authority controller working in the frame of the struts (developed in Section sec:hac_iff_struts_controller) are implemented experimentally.

Initial Controller

The controller designed in Section sec:hac_iff_struts_controller is implemented experimentally and some reference tracking tests are performed.

%% Load the experimental data
load('hac_iff_struts_yz_scans.mat', 't', 'de')

The position of the top-platform is estimated using the Jacobian matrix:

%% Pose of the top platform from the encoder values
load('jacobian.mat', 'J');
Xe = [inv(J)*de']';

The reference path as well as the measured position are partially shown in the Y-Z plane in Figure fig:yz_scans_exp_results_first_K.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/yz_scans_exp_results_first_K.png

Measured position $\bm{\mathcal{X}}_n$ and reference signal $\bm{r}_{\mathcal{X}_n}$ in the Y-Z plane - Zoom on a change of direction

It is clear from Figure fig:yz_scans_exp_results_first_K that the position of the nano-hexapod effectively tracks to reference signal. However, oscillations with amplitudes as large as 50nm can be observe.

It turns out that the frequency of these oscillations is 100Hz which is corresponding to the crossover frequency of the High Authority Control loop. This clearly indicates poor stability margins. In the next section, the controller is re-designed to improve the stability margins.

Controller with increased stability margins

The High Authority Controller is re-designed in order to improve the stability margins.

%% Lead
a  = 5;  % Amount of phase lead / width of the phase lead / high frequency gain
wc = 2*pi*110; % Frequency with the maximum phase lead [rad/s]

H_lead = (1 + s/(wc/sqrt(a)))/(1 + s/(wc*sqrt(a)));

%% Low Pass Filter
H_lpf = 1/(1 + s/2/pi/300);

%% Notch
gm = 0.02;
xi = 0.5;
wn = 2*pi*700;

H_notch = (s^2 + 2*gm*xi*wn*s + wn^2)/(s^2 + 2*xi*wn*s + wn^2);

%% HAC Controller
Khac_iff_struts = -2.2e4 * ... % Gain
            H_lead * ...       % Lead
            H_lpf * ...        % Lead
            H_notch * ...      % Notch
            (2*pi*100/s) * ... % Integrator
            eye(6);            % 6x6 Diagonal

The bode plot of the new loop gain is shown in Figure fig:hac_iff_plates_exp_loop_gain_redesigned_K.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/hac_iff_plates_exp_loop_gain_redesigned_K.png

Loop Gain for the updated decentralized HAC controller

This new controller is implemented experimentally and several tracking tests are performed.

%% Load Measurements
load('hac_iff_more_lead_nass_scan.mat', 't', 'de')

The pose of the top platform is estimated from the encoder position using the Jacobian matrix.

%% Compute the pose of the top platform
load('jacobian.mat', 'J');
Xe = [inv(J)*de']';

The measured motion as well as the trajectory are shown in Figure fig:nass_scans_first_test_exp.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/nass_scans_first_test_exp.png

Measured position $\bm{\mathcal{X}}_n$ and reference signal $\bm{r}_{\mathcal{X}_n}$ for the "NASS" trajectory

The trajectory and measured motion are also shown in the X-Y plane in Figure fig:ref_track_nass_exp_hac_iff_struts.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/ref_track_nass_exp_hac_iff_struts.png

Reference path and measured motion in the X-Y plane

The orientations errors as a function of time are shown in Figure fig:ref_track_nass_exp_hac_iff_struts_errors_angle.

/tdehaeze/test-bench-nano-hexapod/media/commit/bf808861adaabbe2122b3c05454eff4d524eaeac/figs/ref_track_nass_exp_hac_iff_struts_errors_angle.png

Orientation errors as a function of time during the "NASS" trajectory

Using the updated High Authority Controller, the nano-hexapod can follow trajectories with high accuracy (the position errors are in the order of 50nm peak to peak, and the orientation errors 300nrad peak to peak).

Functions

generateXYZTrajectory

<<sec:generateXYZTrajectory>>

Function description

function [ref] = generateXYZTrajectory(args)
% generateXYZTrajectory -
%
% Syntax: [ref] = generateXYZTrajectory(args)
%
% Inputs:
%    - args
%
% Outputs:
%    - ref - Reference Signal

Optional Parameters

arguments
    args.points double {mustBeNumeric} = zeros(2, 3) % [m]

    args.ti    (1,1) double {mustBeNumeric, mustBePositive} = 1 % Time to go to first point and after last point [s]
    args.tw    (1,1) double {mustBeNumeric, mustBePositive} = 0.5 % Time wait between each point [s]
    args.tm    (1,1) double {mustBeNumeric, mustBePositive} = 1 % Motion time between points [s]

    args.Ts    (1,1) double {mustBeNumeric, mustBePositive} = 1e-3 % Sampling Time [s]
end

Initialize Time Vectors

time_i = 0:args.Ts:args.ti;
time_w = 0:args.Ts:args.tw;
time_m = 0:args.Ts:args.tm;

XYZ Trajectory

% Go to initial position
xyz = (args.points(1,:))'*(time_i/args.ti);

% Wait
xyz = [xyz, xyz(:,end).*ones(size(time_w))];

% Scans
for i = 2:size(args.points, 1)
    % Go to next point
    xyz = [xyz, xyz(:,end) + (args.points(i,:)' - xyz(:,end))*(time_m/args.tm)];
    % Wait a litle bit
    xyz = [xyz, xyz(:,end).*ones(size(time_w))];
end

% End motion
xyz = [xyz, xyz(:,end) - xyz(:,end)*(time_i/args.ti)];

Reference Signal

t = 0:args.Ts:args.Ts*(length(xyz) - 1);
ref = zeros(length(xyz), 7);

ref(:, 1) = t;
ref(:, 2:4) = xyz';

generateYZScanTrajectory

<<sec:generateYZScanTrajectory>>

Function description

function [ref] = generateYZScanTrajectory(args)
% generateYZScanTrajectory -
%
% Syntax: [ref] = generateYZScanTrajectory(args)
%
% Inputs:
%    - args
%
% Outputs:
%    - ref - Reference Signal

Optional Parameters

arguments
    args.y_tot (1,1) double {mustBeNumeric} = 10e-6 % [m]
    args.z_tot (1,1) double {mustBeNumeric} = 10e-6 % [m]

    args.n     (1,1) double {mustBeInteger, mustBePositive} = 10 % [-]

    args.Ts    (1,1) double {mustBeNumeric, mustBePositive} = 1e-4 % [s]

    args.ti    (1,1) double {mustBeNumeric, mustBePositive} = 1 % [s]
    args.tw    (1,1) double {mustBeNumeric, mustBePositive} = 1 % [s]
    args.ty    (1,1) double {mustBeNumeric, mustBePositive} = 1 % [s]
    args.tz    (1,1) double {mustBeNumeric, mustBePositive} = 1 % [s]
end

Initialize Time Vectors

time_i = 0:args.Ts:args.ti;
time_w = 0:args.Ts:args.tw;
time_y = 0:args.Ts:args.ty;
time_z = 0:args.Ts:args.tz;

Y and Z vectors

% Go to initial position
y = (time_i/args.ti)*(args.y_tot/2);

% Wait
y = [y, y(end)*ones(size(time_w))];

% Scans
for i = 1:args.n
    if mod(i,2) == 0
        y = [y, -(args.y_tot/2) + (time_y/args.ty)*args.y_tot];
    else
        y = [y,  (args.y_tot/2) - (time_y/args.ty)*args.y_tot];
    end

    if i < args.n
        y = [y, y(end)*ones(size(time_z))];
    end
end

% Wait a litle bit
y = [y, y(end)*ones(size(time_w))];

% End motion
y = [y, y(end) - y(end)*time_i/args.ti];
% Go to initial position
z = (time_i/args.ti)*(args.z_tot/2);

% Wait
z = [z, z(end)*ones(size(time_w))];

% Scans
for i = 1:args.n
    z = [z, z(end)*ones(size(time_y))];

    if i < args.n
        z = [z, z(end) - (time_z/args.tz)*args.z_tot/(args.n-1)];
    end
end

% Wait a litle bit
z = [z, z(end)*ones(size(time_w))];

% End motion
z = [z, z(end) - z(end)*time_i/args.ti];

Reference Signal

t = 0:args.Ts:args.Ts*(length(y) - 1);
ref = zeros(length(y), 7);

ref(:, 1) = t;
ref(:, 3) = y;
ref(:, 4) = z;

getTransformationMatrixAcc

<<sec:getTransformationMatrixAcc>>

Function description

function [M] = getTransformationMatrixAcc(Opm, Osm)
% getTransformationMatrixAcc -
%
% Syntax: [M] = getTransformationMatrixAcc(Opm, Osm)
%
% Inputs:
%    - Opm - Nx3 (N = number of accelerometer measurements) X,Y,Z position of accelerometers
%    - Opm - Nx3 (N = number of accelerometer measurements) Unit vectors representing the accelerometer orientation
%
% Outputs:
%    - M - Transformation Matrix

Transformation matrix from motion of the solid body to accelerometer measurements

Let's try to estimate the x-y-z acceleration of any point of the solid body from the acceleration/angular acceleration of the solid body expressed in $\{O\}$. For any point $p_i$ of the solid body (corresponding to an accelerometer), we can write:

\begin{equation} \begin{bmatrix} a_{i,x} \\ a_{i,y} \\ a_{i,z} \end{bmatrix} = \begin{bmatrix} \dot{v}_x \\ \dot{v}_y \\ \dot{v}_z \end{bmatrix} + p_i \times \begin{bmatrix} \dot{\omega}_x \\ \dot{\omega}_y \\ \dot{\omega}_z \end{bmatrix} \end{equation}

We can write the cross product as a matrix product using the skew-symmetric transformation:

\begin{equation} \begin{bmatrix} a_{i,x} \\ a_{i,y} \\ a_{i,z} \end{bmatrix} = \begin{bmatrix} \dot{v}_x \\ \dot{v}_y \\ \dot{v}_z \end{bmatrix} + \underbrace{\begin{bmatrix} 0 & p_{i,z} & -p_{i,y} \\ -p_{i,z} & 0 & p_{i,x} \\ p_{i,y} & -p_{i,x} & 0 \end{bmatrix}}_{P_{i,[\times]}} \cdot \begin{bmatrix} \dot{\omega}_x \\ \dot{\omega}_y \\ \dot{\omega}_z \end{bmatrix} \end{equation}

If we now want to know the (scalar) acceleration $a_i$ of the point $p_i$ in the direction of the accelerometer direction $\hat{s}_i$, we can just project the 3d acceleration on $\hat{s}_i$:

\begin{equation} a_i = \hat{s}_i^T \cdot \begin{bmatrix} a_{i,x} \\ a_{i,y} \\ a_{i,z} \end{bmatrix} = \hat{s}_i^T \cdot \begin{bmatrix} \dot{v}_x \\ \dot{v}_y \\ \dot{v}_z \end{bmatrix} + \left( \hat{s}_i^T \cdot P_{i,[\times]} \right) \cdot \begin{bmatrix} \dot{\omega}_x \\ \dot{\omega}_y \\ \dot{\omega}_z \end{bmatrix} \end{equation}

Which is equivalent as a simple vector multiplication:

\begin{equation} a_i = \begin{bmatrix} \hat{s}_i^T & \hat{s}_i^T \cdot P_{i,[\times]} \end{bmatrix} \begin{bmatrix} \dot{v}_x \\ \dot{v}_y \\ \dot{v}_z \\ \dot{\omega}_x \\ \dot{\omega}_y \\ \dot{\omega}_z \end{bmatrix} = \begin{bmatrix} \hat{s}_i^T & \hat{s}_i^T \cdot P_{i,[\times]} \end{bmatrix} {}^O\vec{x} \end{equation}

And finally we can combine the 6 (line) vectors for the 6 accelerometers to write that in a matrix form. We obtain Eq. eqref:eq:M_matrix.

The transformation from solid body acceleration ${}^O\vec{x}$ from sensor measured acceleration $\vec{a}$ is: \begin{equation} \label{eq:M_matrix} \vec{a} = _brace{\begin{bmatrix} \hat{s}_1^T & \hat{s}_1^T \cdot P_{1,[\times]} \\ \vdots & \vdots \\ \hat{s}_6^T & \hat{s}_6^T \cdot P_{6,[\times]} \end{bmatrix}}M {}^O\vec{x}

\end{equation}

with $\hat{s}_i$ the unit vector representing the measured direction of the i'th accelerometer expressed in frame $\{O\}$ and $P_{i,[\times]}$ the skew-symmetric matrix representing the cross product of the position of the i'th accelerometer expressed in frame $\{O\}$.

Let's define such matrix using matlab:

M = zeros(length(Opm), 6);

for i = 1:length(Opm)
    Ri = [0,         Opm(3,i), -Opm(2,i);
         -Opm(3,i),  0,         Opm(1,i);
          Opm(2,i), -Opm(1,i),  0];
    M(i, 1:3) = Osm(:,i)';
    M(i, 4:6) = Osm(:,i)'*Ri;
end
end

getJacobianNanoHexapod

<<sec:getJacobianNanoHexapod>>

Function description

function [J] = getJacobianNanoHexapod(Hbm)
% getJacobianNanoHexapod -
%
% Syntax: [J] = getJacobianNanoHexapod(Hbm)
%
% Inputs:
%    - Hbm - Height of {B} w.r.t. {M} [m]
%
% Outputs:
%    - J - Jacobian Matrix

Transformation matrix from motion of the solid body to accelerometer measurements

Fa = [[-86.05,  -74.78, 22.49],
      [ 86.05,  -74.78, 22.49],
      [ 107.79, -37.13, 22.49],
      [ 21.74,  111.91, 22.49],
      [-21.74,  111.91, 22.49],
      [-107.79, -37.13, 22.49]]'*1e-3; % Ai w.r.t. {F} [m]

Mb = [[-28.47, -106.25, -22.50],
      [ 28.47, -106.25, -22.50],
      [ 106.25, 28.47,  -22.50],
      [ 77.78,  77.78,  -22.50],
      [-77.78,  77.78,  -22.50],
      [-106.25, 28.47,  -22.50]]'*1e-3; % Bi w.r.t. {M} [m]

H = 95e-3; % Stewart platform height [m]
Fb = Mb + [0; 0; H]; % Bi w.r.t. {F} [m]

si = Fb - Fa;
si = si./vecnorm(si); % Normalize

Bb = Mb - [0; 0; Hbm];

J = [si', cross(Bb, si)'];