This repository has been archived on 2025-04-18. You can view files and clone it, but cannot push or open issues or pull requests.

127 KiB
Raw Blame History

Analysis backup of HAC - Decoupling analysis

<<sec:test_nhexa_decentralized_hac_iff>>

Introduction   ignore

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

  • The LAC control is a decentralized integral force feedback as studied in Section ref:sec:test_nhexa_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 ref:fig:test_nhexa_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
\definecolor{instrumentation}{rgb}{0, 0.447, 0.741}
\definecolor{mechanics}{rgb}{0.8500, 0.325, 0.098}
\definecolor{control}{rgb}{0.4660, 0.6740, 0.1880}

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

  \node[block, below=0.4 of P, fill=control!20!white] (Kiff) {$\bm{K}_\text{IFF}$};
  \node[block, left=0.8 of inputF, fill=instrumentation!20!white] (pd200) {\tiny PD200};
  \node[addb,  left=0.8 of pd200, fill=control!20!white] (addF) {};
  \node[block, left=0.8 of addF, fill=control!20!white] (K) {$\bm{K}_\mathcal{L}$};
  \node[addb={+}{}{-}{}{}, left=0.8 of K, fill=control!20!white] (subr) {};
  \node[block, align=center, left= of subr, fill=control!20!white] (J) {\tiny Inverse\\\tiny Kinematics};

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

  \draw[->] (outputL) -- ++(1.0, 0) node[below left]{$d\bm{\mathcal{L}_m}$};
  \draw[->] ($(outputL) + (0.6, 0)$)node[branch]{} -- ++(0, 1) -| (subr.north);
  \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/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_control_architecture_hac_iff_struts.png

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

This part is structured as follow:

  • Section ref:sec:test_nhexa_hac_iff_struts_ref_track: some reference tracking tests are performed
  • Section ref:sec:test_nhexa_hac_iff_struts_controller: the decentralized high authority controller is tuned using the Simscape model and is implemented and tested experimentally
  • Section ref:sec:test_nhexa_interaction_analysis: an interaction analysis is performed, from which the best decoupling strategy can be determined
  • Section ref:sec:test_nhexa_robust_hac_design: Robust High Authority Controller are designed

Reference Tracking - Trajectories

<<sec:test_nhexa_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 $\bm{J}$ 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 ref:fig:test_nhexa_control_architecture_hac_iff_L.

\definecolor{instrumentation}{rgb}{0, 0.447, 0.741}
\definecolor{mechanics}{rgb}{0.8500, 0.325, 0.098}
\definecolor{control}{rgb}{0.4660, 0.6740, 0.1880}

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

  \node[block, below=0.4 of P, fill=control!20!white] (Kiff) {$\bm{K}_\text{IFF}$};
  \node[block, left=0.8 of inputF, fill=instrumentation!20!white] (pd200) {\tiny PD200};
  \node[addb,  left=0.8 of pd200, fill=control!20!white] (addF) {};
  \node[block, left=0.8 of addF, fill=control!20!white] (K) {$\bm{K}_\mathcal{L}$};
  \node[addb={+}{}{-}{}{}, left=0.8 of K, fill=control!20!white] (subr) {};
  \node[block, align=center, left= of subr, fill=control!20!white] (J) {$\bm{J}$};

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

  \draw[->] (outputL) -- ++(1.0, 0) node[below left]{$d\bm{\mathcal{L}_m}$};
  \draw[->] ($(outputL) + (0.6, 0)$)node[branch]{} -- ++(0, 1) -| (subr.north);
  \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/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_control_architecture_hac_iff_struts_L.png

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

In the following sections, several reference trajectories are defined:

  • Section ref:sec:test_nhexa_yz_scans: simple scans in the Y-Z plane
  • Section ref:sec:test_nhexa_tilt_scans: scans in tilt are performed
  • Section ref:sec:test_nhexa_nass_scans: scans with X-Y-Z translations in order to draw the word "NASS"
Y-Z Scans

<<sec:test_nhexa_yz_scans>> A function generateYZScanTrajectory has been developed in order to easily generate scans in the Y-Z plane.

For instance, the following generated trajectory is represented in Figure ref:fig:test_nhexa_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', 4e-6, ... % Total Z distance [m]
    'n', 5, ...     % Number of Y scans
    'Ts', 1e-3, ... % Sampling Time [s]
    'ti', 1, ...    % Time to go to initial position [s]
    'tw', 0, ...    % Waiting time between each points [s]
    'ty', 0.6, ...  % Time for a scan in Y [s]
    'tz', 0.2);     % Time for a scan in Z [s]

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_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 ref:fig:test_nhexa_yz_scan_example_trajectory.

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_yz_scan_example_trajectory.png

Y and Z trajectories as a function of time

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}
%% Compute the reference in the frame of the legs
dL_ref = [J*Rx_yz(:, 2:7)']';

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

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_yz_scan_example_trajectory_struts.png

Trajectories for the 6 individual struts
Tilt Scans

<<sec:test_nhexa_tilt_scans>>

A function generalSpiralAngleTrajectory has been developed in order to easily generate $R_x,R_y$ tilt scans.

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

%% Generate the "tilt-spiral" trajectory scan
R_tilt = generateSpiralAngleTrajectory(...
    'R_tot',  20e-6, ... % Total Tilt [ad]
    'n_turn', 5, ...     % Number of scans
    'Ts',     1e-3, ...  % Sampling Time [s]
    't_turn', 1, ...     % Turn time [s]
    't_end',  1);        % End time to go back to zero [s]

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_tilt_scan_example_trajectory.png

Generated "spiral" scan

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

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_tilt_scan_example_trajectory_struts.png

Trajectories for the 6 individual struts - Tilt scan
"NASS" reference path

<<sec:test_nhexa_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 ref:fig:test_nhexa_ref_track_test_nass (the transitions between the letters are removed).

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_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 ref:fig:test_nhexa_ref_track_test_nass_3d.

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_ref_track_test_nass_3d.png

Reference path that draws "NASS" - 3D view

First Basic High Authority Controller

<<sec:test_nhexa_hac_iff_struts_controller>>

Introduction   ignore

In this section, a simple decentralized high authority controller $\bm{K}_{\mathcal{L}}$ is developed to work without any payload.

The diagonal controller is tuned using classical Loop Shaping in Section ref:sec:test_nhexa_hac_iff_no_payload_tuning. The stability is verified in Section ref:sec:test_nhexa_hac_iff_no_payload_stability using the Simscape model.

HAC Controller

<<sec:test_nhexa_hac_iff_no_payload_tuning>>

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, A diagonal controller is developed. Each diagonal terms are identical and are composed of:

  • A lead around 100Hz
  • A first order low pass filter starting at 200Hz to add some robustness to high frequency modes
  • A notch at 700Hz to cancel the flexible modes of the top plate
  • A pure integrator
%% 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('data_sim/Khac_iff_struts.mat', 'Khac_iff_struts')

The experimental loop gain is computed and shown in Figure ref:fig:test_nhexa_loop_gain_hac_iff_struts.

L_hac_iff_struts = pagemtimes(permute(frf_iff.G_de{1}, [2 3 1]), squeeze(freqresp(Khac_iff_struts, frf_iff.f, 'Hz')));

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_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

<<sec:test_nhexa_hac_iff_no_payload_stability>>

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');
%% Identify the (damped) 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; % Plate Displacement (encoder)

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 Validation

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

Two reference tracking experiments are performed to evaluate the stability and performances of the implemented control.

%% 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']';
%% 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', 1, ...    % Time to go to initial position [s]
    'tw', 0, ...    % Waiting time between each points [s]
    'ty', 0.6, ...  % Time for a scan in Y [s]
    'tz', 0.2);     % Time for a scan in Z [s]

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

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_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 ref:fig:test_nhexa_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 ref:fig:test_nhexa_hac_iff_plates_exp_loop_gain_redesigned_K.

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_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 ref:fig:test_nhexa_nass_scans_first_test_exp.

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_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 ref:fig:test_nhexa_ref_track_nass_exp_hac_iff_struts.

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_ref_track_nass_exp_hac_iff_struts.png

Reference path and measured motion in the X-Y plane

The orientation errors during all the scans are shown in Figure ref:fig:test_nhexa_nass_ref_rx_ry.

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_nass_ref_rx_ry.png

Orientation errors during the scan

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).

Interaction Analysis and Decoupling

<<sec:test_nhexa_interaction_analysis>>

Introduction   ignore

In this section, the interaction in the identified plant is estimated using the Relative Gain Array (RGA) Chap. 3.4.

Then, several decoupling strategies are compared for the nano-hexapod.

The RGA Matrix is defined as follow:

\begin{equation} \text{RGA}(G(f)) = G(f) \times (G(f)^{-1})^T \end{equation}

Then, the RGA number is defined:

\begin{equation} \text{RGA-num}(f) = \| \text{I - RGA(G(f))} \|_{\text{sum}} \end{equation}

In this section, the plant with 2 added mass is studied.

Parameters
wc = 100; % Wanted crossover frequency [Hz]
[~, i_wc] = min(abs(frf_iff.f - wc)); % Indice corresponding to wc
%% Plant to be decoupled
frf_coupled = frf_iff.G_de{2};
G_coupled = sim_iff.G_de{2};
No Decoupling (Decentralized)

<<sec:test_nhexa_interaction_decentralized>>

\begin{tikzpicture}
  \node[block] (G) {$\bm{G}$};

  % Connections and labels
  \draw[<-] (G.west) -- ++(-1.8, 0) node[above right]{$\bm{\tau}$};
  \draw[->] (G.east) -- ++( 1.8, 0) node[above left]{$d\bm{\mathcal{L}}$};

  \begin{scope}[on background layer]
    \node[fit={(G.south west) (G.north east)}, fill=black!10!white, draw, dashed, inner sep=16pt] (Gdec) {};
    \node[below right] at (Gdec.north west) {$\bm{G}_{\text{dec}}$};
  \end{scope}
\end{tikzpicture}

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_decoupling_arch_decentralized.png

Block diagram representing the plant.

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_interaction_decentralized_plant.png

Bode Plot of the decentralized plant (diagonal and off-diagonal terms)

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_interaction_rga_decentralized.png

RGA number for the decentralized plant
Static Decoupling

<<sec:test_nhexa_interaction_static>>

\begin{tikzpicture}
  \node[block] (G) {$\bm{G}$};
  \node[block, left=0.8 of G] (Ginv) {$\bm{\hat{G}}(j0)^{-1}$};

  % Connections and labels
  \draw[<-] (Ginv.west) -- ++(-1.8, 0) node[above right]{$\bm{u}$};
  \draw[->] (Ginv.east) -- (G.west)    node[above left]{$\bm{\tau}$};
  \draw[->] (G.east) -- ++( 1.8, 0)    node[above left]{$d\bm{\mathcal{L}}$};

  \begin{scope}[on background layer]
    \node[fit={(Ginv.south west) (G.north east)}, fill=black!10!white, draw, dashed, inner sep=16pt] (Gx) {};
    \node[below right] at (Gx.north west) {$\bm{G}_{\text{static}}$};
  \end{scope}
\end{tikzpicture}

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_decoupling_arch_static.png

Decoupling using the inverse of the DC gain of the plant

The DC gain is evaluated from the model as be have bad low frequency identification.

-62011.5 3910.6 4299.3 660.7 -4016.5 -4373.6
3914.4 -61991.2 -4356.8 -4019.2 640.2 4281.6
-4020.0 -4370.5 -62004.5 3914.6 4295.8 653.8
660.9 4292.4 3903.3 -62012.2 -4366.5 -4008.9
4302.8 655.6 -4025.8 -4377.8 -62006.0 3919.7
-4377.9 -4013.2 668.6 4303.7 3906.8 -62019.3

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_interaction_static_dec_plant.png

Bode Plot of the static decoupled plant

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_interaction_rga_static_dec.png

RGA number for the statically decoupled plant
Decoupling at the Crossover

<<sec:test_nhexa_interaction_crossover>>

\begin{tikzpicture}
  \node[block] (G) {$\bm{G}$};
  \node[block, left=0.8 of G] (Ginv) {$\bm{\hat{G}}(j\omega_c)^{-1}$};

  % Connections and labels
  \draw[<-] (Ginv.west) -- ++(-1.8, 0) node[above right]{$\bm{u}$};
  \draw[->] (Ginv.east) -- (G.west)    node[above left]{$\bm{\tau}$};
  \draw[->] (G.east) -- ++( 1.8, 0)    node[above left]{$d\bm{\mathcal{L}}$};

  \begin{scope}[on background layer]
    \node[fit={(Ginv.south west) (G.north east)}, fill=black!10!white, draw, dashed, inner sep=16pt] (Gx) {};
    \node[below right] at (Gx.north west) {$\bm{G}_{\omega_c}$};
  \end{scope}
\end{tikzpicture}

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_decoupling_arch_crossover.png

Decoupling using the inverse of a dynamical model $\bm{\hat{G}}$ of the plant dynamics $\bm{G}$
67229.8 3769.3 -13704.6 -23084.8 -6318.2 23378.7
3486.2 67708.9 23220.0 -6314.5 -22699.8 -14060.6
-5731.7 22471.7 66701.4 3070.2 -13205.6 -21944.6
-23305.5 -14542.6 2743.2 70097.6 24846.8 -5295.0
-14882.9 -22957.8 -5344.4 25786.2 70484.6 2979.9
24353.3 -5195.2 -22449.0 -14459.2 2203.6 69484.2

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_interaction_wc_plant.png

Bode Plot of the plant decoupled at the crossover
%% Compute RGA Matrix
RGA_wc = zeros(size(frf_coupled));
for i = 1:length(frf_iff.f)
    RGA_wc(i,:,:) = squeeze(G_de_wc(i,:,:)).*inv(squeeze(G_de_wc(i,:,:))).';
end

%% Compute RGA-number
RGA_wc_sum = zeros(size(RGA_wc, 1), 1);
for i = 1:size(RGA_wc, 1)
    RGA_wc_sum(i) = sum(sum(abs(eye(6) - squeeze(RGA_wc(i,:,:)))));
end

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_interaction_rga_wc.png

RGA number for the plant decoupled at the crossover
SVD Decoupling

<<sec:test_nhexa_interaction_svd>>

\begin{tikzpicture}
  \node[block] (G) {$\bm{G}$};

  \node[block, left=0.8 of G.west] (V) {$V^{-T}$};
  \node[block, right=0.8 of G.east] (U) {$U^{-1}$};

  % Connections and labels
  \draw[<-] (V.west) -- ++(-1.0, 0) node[above right]{$u$};
  \draw[->] (V.east) -- (G.west) node[above left]{$\bm{\tau}$};
  \draw[->] (G.east) -- (U.west) node[above left]{$d\bm{\mathcal{L}}$};
  \draw[->] (U.east) -- ++( 1.0, 0) node[above left]{$y$};

  \begin{scope}[on background layer]
    \node[fit={(V.south west) (G.north-|U.east)}, fill=black!10!white, draw, dashed, inner sep=14pt] (Gsvd) {};
    \node[below right] at (Gsvd.north west) {$\bm{G}_{SVD}$};
  \end{scope}
\end{tikzpicture}

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_decoupling_arch_svd.png

Decoupling using the Singular Value Decomposition

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_interaction_svd_plant.png

Bode Plot of the plant decoupled using the Singular Value Decomposition
%% Compute the RGA matrix for the SVD decoupled plant
RGA_svd = zeros(size(frf_coupled));
for i = 1:length(frf_iff.f)
    RGA_svd(i,:,:) = squeeze(G_de_svd(i,:,:)).*inv(squeeze(G_de_svd(i,:,:))).';
end

%% Compute the RGA-number
RGA_svd_sum = zeros(size(RGA_svd, 1), 1);
for i = 1:length(frf_iff.f)
    RGA_svd_sum(i) = sum(sum(abs(eye(6) - squeeze(RGA_svd(i,:,:)))));
end
%% RGA Number for the SVD decoupled plant
figure;
plot(frf_iff.f, RGA_svd_sum, 'k-');
set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log');
xlabel('Frequency [Hz]'); ylabel('RGA Number');
xlim([10, 1e3]); ylim([1e-2, 1e2]);

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_interaction_rga_svd.png

RGA number for the plant decoupled using the SVD
Dynamic decoupling

<<sec:test_nhexa_interaction_dynamic>>

\begin{tikzpicture}
  \node[block] (G) {$\bm{G}$};
  \node[block, left=0.8 of G] (Ginv) {$\bm{\hat{G}}^{-1}$};

  % Connections and labels
  \draw[<-] (Ginv.west) -- ++(-1.8, 0) node[above right]{$\bm{u}$};
  \draw[->] (Ginv.east) -- (G.west)    node[above left]{$\bm{\tau}$};
  \draw[->] (G.east) -- ++( 1.8, 0)    node[above left]{$d\bm{\mathcal{L}}$};

  \begin{scope}[on background layer]
    \node[fit={(Ginv.south west) (G.north east)}, fill=black!10!white, draw, dashed, inner sep=16pt] (Gx) {};
    \node[below right] at (Gx.north west) {$\bm{G}_{\text{inv}}$};
  \end{scope}
\end{tikzpicture}

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_decoupling_arch_dynamic.png

Decoupling using the inverse of a dynamical model $\bm{\hat{G}}$ of the plant dynamics $\bm{G}$

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_interaction_dynamic_dec_plant.png

Bode Plot of the dynamically decoupled plant

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_interaction_rga_dynamic_dec.png

RGA number for the dynamically decoupled plant
Jacobian Decoupling - Center of Stiffness

<<sec:test_nhexa_interaction_jacobian_cok>>

\begin{tikzpicture}
  \node[block] (G) {$\bm{G}$};
  \node[block, left=0.8 of G] (Jt) {$J_{s,\{K\}}^{-T}$};
  \node[block, right=0.8 of G] (Ja) {$J_{a,\{K\}}^{-1}$};

  % Connections and labels
  \draw[<-] (Jt.west) -- ++(-1.8, 0) node[above right]{$\bm{\mathcal{F}}_{\{K\}}$};
  \draw[->] (Jt.east) -- (G.west)  node[above left]{$\bm{\tau}$};
  \draw[->] (G.east) -- (Ja.west)  node[above left]{$d\bm{\mathcal{L}}$};
  \draw[->] (Ja.east) -- ++( 1.8, 0)  node[above left]{$\bm{\mathcal{X}}_{\{K\}}$};

  \begin{scope}[on background layer]
    \node[fit={(Jt.south west) (Ja.north east)}, fill=black!10!white, draw, dashed, inner sep=16pt] (Gx) {};
    \node[below right] at (Gx.north west) {$\bm{G}_{\{K\}}$};
  \end{scope}
\end{tikzpicture}

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_decoupling_arch_jacobian_cok.png

Decoupling using Jacobian matrices evaluated at the Center of Stiffness

The obtained plant is shown in Figure ref:fig:test_nhexa_interaction_J_cok_plant_not_normalized. We can see that the stiffness in the $x$, $y$ and $z$ directions are equal, which is due to the cubic architecture of the Stewart platform.

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_interaction_J_cok_plant_not_normalized.png

Bode Plot of the plant decoupled using the Jacobian evaluated at the "center of stiffness"

Because the plant in translation and rotation has very different gains, we choose to normalize the plant inputs such that the gain of the diagonal term is equal to $1$ at 100Hz.

The results is shown in Figure ref:fig:test_nhexa_interaction_J_cok_plant.

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_interaction_J_cok_plant.png

Bode Plot of the plant decoupled using the Jacobian evaluated at the "center of stiffness"

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_interaction_rga_J_cok.png

RGA number for the plant decoupled using the Jacobian evaluted at the Center of Stiffness
Jacobian Decoupling - Center of Mass

<<sec:test_nhexa_interaction_jacobian_com>>

\begin{tikzpicture}
  \node[block] (G) {$\bm{G}$};
  \node[block, left=0.8 of G] (Jt) {$J_{s,\{M\}}^{-T}$};
  \node[block, right=0.8 of G] (Ja) {$J_{a,\{M\}}^{-1}$};

  % Connections and labels
  \draw[<-] (Jt.west) -- ++(-1.8, 0) node[above right]{$\bm{\mathcal{F}}_{\{M\}}$};
  \draw[->] (Jt.east) -- (G.west)  node[above left]{$\bm{\tau}$};
  \draw[->] (G.east) -- (Ja.west)  node[above left]{$d\bm{\mathcal{L}}$};
  \draw[->] (Ja.east) -- ++( 1.8, 0)  node[above left]{$\bm{\mathcal{X}}_{\{M\}}$};

  \begin{scope}[on background layer]
    \node[fit={(Jt.south west) (Ja.north east)}, fill=black!10!white, draw, dashed, inner sep=16pt] (Gx) {};
    \node[below right] at (Gx.north west) {$\bm{G}_{\{M\}}$};
  \end{scope}
\end{tikzpicture}

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_decoupling_arch_jacobian_com.png

Decoupling using Jacobian matrices evaluated at the Center of Mass

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_interaction_J_com_plant.png

Bode Plot of the plant decoupled using the Jacobian evaluated at the Center of Mass

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_interaction_rga_J_com.png

RGA number for the plant decoupled using the Jacobian evaluted at the Center of Mass
Decoupling Comparison

<<sec:test_nhexa_interaction_comparison>>

Let's now compare all of the decoupling methods (Figure ref:fig:test_nhexa_interaction_compare_rga_numbers).

From Figure ref:fig:test_nhexa_interaction_compare_rga_numbers, the following remarks are made:

  • Decentralized plant: well decoupled below suspension modes
  • Static inversion: similar to the decentralized plant as the decentralized plant has already a good decoupling at low frequency
  • Crossover inversion: the decoupling is improved around the crossover frequency as compared to the decentralized plant. However, the decoupling is increased at lower frequency.
  • SVD decoupling: Very good decoupling up to 235Hz. Especially between 100Hz and 200Hz.
  • Dynamic Inversion: the plant is very well decoupled at frequencies where the model is accurate (below 235Hz where flexible modes are not modelled).
  • Jacobian - Stiffness: good decoupling at low frequency. The decoupling increases at the frequency of the suspension modes, but is acceptable up to the strut flexible modes (235Hz).
  • Jacobian - Mass: bad decoupling at low frequency. Better decoupling above the frequency of the suspension modes, and acceptable decoupling up to the strut flexible modes (235Hz).

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_interaction_compare_rga_numbers.png

Comparison of the obtained RGA-numbers for all the decoupling methods
Decoupling Robustness

<<sec:test_nhexa_interaction_robustness>>

Let's now see how the decoupling is changing when changing the payload's mass.

frf_new = frf_iff.G_de{3};

The obtained RGA-numbers are shown in Figure ref:fig:test_nhexa_interaction_compare_rga_numbers_rob.

From Figure ref:fig:test_nhexa_interaction_compare_rga_numbers_rob:

  • The decoupling using the Jacobian evaluated at the "center of stiffness" seems to give the most robust results.

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_interaction_compare_rga_numbers_rob.png

Change of the RGA-number with a change of the payload. Indication of the robustness of the inversion method.
Conclusion

Several decoupling methods can be used:

  • SVD
  • Inverse
  • Jacobian (CoK)
Method RGA Diag Plant Robustness
Decentralized Equal ++
Static dec. Equal ++
Crossover dec. - Equal 0
SVD ++ Diff +
Dynamic dec. ++ Unity, equal -
Jacobian - CoK + Diff ++
Jacobian - CoM 0 Diff +

Robust High Authority Controller

<<sec:test_nhexa_robust_hac_design>>

Introduction   ignore

In this section we wish to develop a robust High Authority Controller (HAC) that is working for all payloads.

cite:indri20_mechat_robot

Using Jacobian evaluated at the center of stiffness
Decoupled Plant
G_nom = frf_iff.G_de{2}; % Nominal Plant

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_bode_plot_hac_iff_plant_jacobian_cok.png

Bode plot of the decoupled plant using the Jacobian evaluated at the Center of Stiffness
SISO Controller Design

As the diagonal elements of the plant are not equal, several SISO controllers are designed and then combined to form a diagonal controller. All the diagonal terms of the controller consists of:

  • A double integrator to have high gain at low frequency
  • A lead around the crossover frequency to increase stability margins
  • Two second order low pass filters above the crossover frequency to increase the robustness to high frequency modes
Obtained Loop Gain

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_bode_plot_hac_iff_loop_gain_jacobian_cok.png

Bode plot of the Loop Gain when using the Jacobian evaluated at the Center of Stiffness to decouple the system
%% Controller to be implemented
Kd = inv(J_cok')*input_normalize*ss(Kd_diag)*inv(Js_cok);
Verification of the Stability

Now the stability of the feedback loop is verified using the generalized Nyquist criteria.

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_loci_hac_iff_loop_gain_jacobian_cok.png

Loci of $L(j\omega)$ in the complex plane.
Save for further analysis
save('data_sim/Khac_iff_struts_jacobian_cok.mat', 'Kd')
Sensitivity transfer function from the model

The results are shown in Figure ref:fig:test_nhexa_sensitivity_hac_jacobian_cok_3m_comp_model.

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_sensitivity_hac_jacobian_cok_3m_comp_model.png

Estimated sensitivity transfer functions for the HAC controller using the Jacobian estimated at the Center of Stiffness
Using Singular Value Decomposition
Decoupled Plant
G_nom = frf_iff.G_de{2}; % Nominal Plant

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_bode_plot_hac_iff_plant_svd.png

Bode plot of the decoupled plant using the SVD
Controller Design
Loop Gain

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_bode_plot_hac_iff_loop_gain_svd.png

Bode plot of Loop Gain when using the SVD
Stability Verification
%% Compute the Eigenvalues of the loop gain
Ldet = zeros(3, 6, length(frf_iff.f));

for i = 1:3
    Lmimo = pagemtimes(permute(frf_iff.G_de{i}, [2,3,1]),squeeze(freqresp(Kd, frf_iff.f, 'Hz')));
    for i_f = 2:length(frf_iff.f)
        Ldet(i,:, i_f) = eig(squeeze(Lmimo(:,:,i_f)));
    end
end

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_loci_hac_iff_loop_gain_svd.png

Locis of $L(j\omega)$ in the complex plane.
Save for further analysis
save('data_sim/Khac_iff_struts_svd.mat', 'Kd')
Measured Sensitivity Transfer Function

The sensitivity transfer function is estimated by adding a reference signal $R_x$ consisting of a low pass filtered white noise, and measuring the position error $E_x$ at the same time.

The transfer function from $R_x$ to $E_x$ is the sensitivity transfer function.

In order to identify the sensitivity transfer function for all directions, six reference signals are used, one for each direction.

An example is shown in Figure ref:fig:test_nhexa_ref_track_hac_svd_3m where both the reference signal and the measured position are shown for translations in the $x$ direction.

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_ref_track_hac_svd_3m.png

Reference position and measured position

The sensitivity transfer functions estimated for all directions are shown in Figure ref:fig:test_nhexa_sensitivity_hac_svd_3m.

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_sensitivity_hac_svd_3m.png

Measured diagonal elements of the sensitivity transfer function matrix.

From Figure ref:fig:test_nhexa_sensitivity_hac_svd_3m:

  • The sensitivity transfer functions are similar for all directions
  • The disturbance attenuation at 1Hz is almost a factor 1000 as wanted
  • The sensitivity transfer functions for $R_x$ and $R_y$ have high peak values which indicate poor stability margins.
Sensitivity transfer function from the model

The sensitivity transfer function is now estimated using the model and compared with the one measured.

The results are shown in Figure ref:fig:test_nhexa_sensitivity_hac_svd_3m_comp_model. The model is quite effective in estimating the sensitivity transfer functions except around 60Hz were there is a peak for the measurement.

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_sensitivity_hac_svd_3m_comp_model.png

Comparison of the measured sensitivity transfer functions with the model

Other Backups

Nano-Hexapod Compliance - Effect of IFF

<<sec:test_nhexa_compliance_effect_iff>>

In this section, we wish to estimate the effectiveness of the IFF strategy regarding 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 are 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 vertical 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 ref:fig:test_nhexa_compliance_vertical_comp_iff.

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_compliance_vertical_comp_iff.png

Measured vertical compliance with and without IFF

From Figure ref:fig:test_nhexa_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:test_nhexa_compliance_effect_iff_comp_model>>

Let's initialize the Simscape model such that it corresponds to the experiment.

%% Nano-Hexapod is fixed on a rigid granite
support.type = 0;

%% No Payload on top of the Nano-Hexapod
payload.type = 0;

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

And let's 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 ref:fig:test_nhexa_compliance_vertical_comp_model_iff. Again, the model is quite accurate in predicting the (closed-loop) behavior of the system.

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_compliance_vertical_comp_model_iff.png

Measured vertical compliance with and without IFF

Computation of the transmissibility from accelerometer data

Introduction   ignore

The goal is to compute the $6 \times 6$ transfer function matrix corresponding to the transmissibility of the Nano-Hexapod.

To do so, several accelerometers are located both on the vibration table and on the top of the nano-hexapod.

The vibration table is then excited using a Shaker and all the accelerometers signals are recorded.

Using transformation (jacobian) matrices, it is then possible to compute both the motion of the top and bottom platform of the nano-hexapod.

Finally, it is possible to compute the $6 \times 6$ transmissibility matrix.

Such procedure is explained in cite:marneffe04_stewar_platf_activ_vibrat_isolat.

Jacobian matrices

How to compute the Jacobian matrices is explained in Section ref:sec:meas_transformation.

%% Bottom Accelerometers
Opb = [-0.1875, -0.1875, -0.245;
       -0.1875, -0.1875, -0.245;
        0.1875, -0.1875, -0.245;
        0.1875, -0.1875, -0.245;
        0.1875,  0.1875, -0.245;
        0.1875,  0.1875, -0.245]';

Osb = [0, 1, 0;
       0, 0, 1;
       1, 0, 0;
       0, 0, 1;
       1, 0, 0;
       0, 0, 1;]';

Jb = zeros(length(Opb), 6);

for i = 1:length(Opb)
    Ri = [0,         Opb(3,i), -Opb(2,i);
         -Opb(3,i),  0,         Opb(1,i);
          Opb(2,i), -Opb(1,i),  0];
    Jb(i, 1:3) = Osb(:,i)';
    Jb(i, 4:6) = Osb(:,i)'*Ri;
end

Jbinv = inv(Jb);
$a_1$ $a_2$ $a_3$ $a_4$ $a_5$ $a_6$
$\dot{x}_x$ 0.0 0.7 0.5 -0.7 0.5 0.0
$\dot{x}_y$ 1.0 0.0 0.5 0.7 -0.5 -0.7
$\dot{x}_z$ 0.0 0.5 0.0 0.0 0.0 0.5
$\dot{\omega}_x$ 0.0 0.0 0.0 -2.7 0.0 2.7
$\dot{\omega}_y$ 0.0 2.7 0.0 -2.7 0.0 0.0
$\dot{\omega}_z$ 0.0 0.0 2.7 0.0 -2.7 0.0
%% Top Accelerometers
Opt = [-0.1,   0,     -0.150;
       -0.1,   0,     -0.150;
        0.05,  0.075, -0.150;
        0.05,  0.075, -0.150;
        0.05, -0.075, -0.150;
        0.05, -0.075, -0.150]';

Ost = [0, 1, 0;
       0, 0, 1;
       1, 0, 0;
       0, 0, 1;
       1, 0, 0;
       0, 0, 1;]';

Jt = zeros(length(Opt), 6);

for i = 1:length(Opt)
    Ri = [0,         Opt(3,i), -Opt(2,i);
         -Opt(3,i),  0,         Opt(1,i);
          Opt(2,i), -Opt(1,i),  0];
    Jt(i, 1:3) = Ost(:,i)';
    Jt(i, 4:6) = Ost(:,i)'*Ri;
end

Jtinv = inv(Jt);
$b_1$ $b_2$ $b_3$ $b_4$ $b_5$ $b_6$
$\dot{x}_x$ 0.0 1.0 0.5 -0.5 0.5 -0.5
$\dot{x}_y$ 1.0 0.0 -0.7 -1.0 0.7 1.0
$\dot{x}_z$ 0.0 0.3 0.0 0.3 0.0 0.3
$\dot{\omega}_x$ 0.0 0.0 0.0 6.7 0.0 -6.7
$\dot{\omega}_y$ 0.0 6.7 0.0 -3.3 0.0 -3.3
$\dot{\omega}_z$ 0.0 0.0 -6.7 0.0 6.7 0.0
Using linearize function
acc_3d.type = 2; % 1: inertial mass, 2: perfect

%% Name of the Simulink File
mdl = 'vibration_table';

%% Input/Output definition
clear io; io_i = 1;
io(io_i) = linio([mdl, '/F_shaker'], 1, 'openinput');  io_i = io_i + 1;
io(io_i) = linio([mdl, '/acc'],      1, 'openoutput'); io_i = io_i + 1;
io(io_i) = linio([mdl, '/acc_top'],  1, 'openoutput'); io_i = io_i + 1;

%% Run the linearization
G = linearize(mdl, io);
G.InputName  = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
G.OutputName  = {'a1', 'a2', 'a3', 'a4', 'a5', 'a6', ...
                 'b1', 'b2', 'b3', 'b4', 'b5', 'b6'};
Gb = Jbinv*G({'a1', 'a2', 'a3', 'a4', 'a5', 'a6'}, :);
Gt = Jtinv*G({'b1', 'b2', 'b3', 'b4', 'b5', 'b6'}, :);
T = inv(Gb)*Gt;
T = minreal(T);
T = prescale(T, {2*pi*0.1, 2*pi*1e3});

Comparison with "true" transmissibility

%% Name of the Simulink File
mdl = 'test_transmissibility';

%% Input/Output definition
clear io; io_i = 1;
io(io_i) = linio([mdl, '/d'],   1, 'openinput');  io_i = io_i + 1;
io(io_i) = linio([mdl, '/acc'], 1, 'openoutput'); io_i = io_i + 1;

%% Run the linearization
G = linearize(mdl, io);
G.InputName  = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};
G.OutputName  = {'Ax', 'Ay', 'Az', 'Bx', 'By', 'Bz'};
Tp = G/s^2;

Rigidification of the added payloads

  • figure
%% Load Identification Data
meas_added_mass = {};

for i_strut = 1:6
    meas_added_mass(i_strut) = {load(sprintf('frf_data_exc_strut_%i_spindle_1m_solid.mat', i_strut), 't', 'Va', 'Vs', 'de')};
end

Finally the $6 \times 6$ transfer function matrices from $\bm{u}$ to $d\bm{\mathcal{L}}_m$ and from $\bm{u}$ to $\bm{\tau}_m$ are identified:

%% DVF Plant (transfer function from u to dLm)

G_de = zeros(length(f), 6, 6);
for i_strut = 1:6
    G_de(:,:,i_strut) = tfestimate(meas_added_mass{i_strut}.Va, meas_added_mass{i_strut}.de, win, Noverlap, Nfft, 1/Ts);
end

%% IFF Plant (transfer function from u to taum)
G_Vs = zeros(length(f), 6, 6);
for i_strut = 1:6
    G_Vs(:,:,i_strut) = tfestimate(meas_added_mass{i_strut}.Va, meas_added_mass{i_strut}.Vs, win, Noverlap, Nfft, 1/Ts);
end

Table with signals

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}$

RGA

The RGA-number, which is a measure of the interaction in the system, is computed for the transfer function matrix from $\mathbf{u}$ to $d\mathbf{\mathcal{L}}_m$ for all the payloads. The obtained numbers are compared in Figure ref:fig:test_nhexa_rga_num_ol_masses.

/tdehaeze/phd-test-bench-nano-hexapod/media/commit/39a5950de7aabecadd44ff7290d4cb2020170420/figs/test_nhexa_rga_num_ol_masses.png

RGA-number for the open-loop transfer function from $\mathbf{u}$ to $d\mathbf{\mathcal{L}}_m$

From Figure ref:fig:test_nhexa_rga_num_ol_masses, it is clear that the coupling is quite large starting from the first suspension mode of the nano-hexapod. Therefore, is the payload's mass is increase, the coupling in the system start to become unacceptably large at lower frequencies.