Go to file
2021-11-30 17:54:19 +01:00
figs First open/close noise budgeting 2021-11-30 17:54:19 +01:00
matlab First open/close noise budgeting 2021-11-30 17:54:19 +01:00
.gitignore Initial Commit 2021-11-30 11:16:48 +01:00
dcm-simscape.html First open/close noise budgeting 2021-11-30 17:54:19 +01:00
dcm-simscape.org First open/close noise budgeting 2021-11-30 17:54:19 +01:00
dcm-simscape.pdf First open/close noise budgeting 2021-11-30 17:54:19 +01:00
readme.org Add readme.org 2021-11-30 11:19:53 +01:00
ref.bib Initial Commit 2021-11-30 11:16:48 +01:00

ESRF Double Crystal Monochromator - Dynamical Multi-Body Model


This report is also available as a pdf.


Introduction   ignore

In this document, a Simscape (.e.g. multi-body) model of the ESRF Double Crystal Monochromator (DCM) is presented and used to develop and optimize the control strategy.

It is structured as follow:

  • Section sec:dcm_kinematics: the kinematics of the DCM is presented, and Jacobian matrices which are used to solve the inverse and forward kinematics are computed.
  • Section sec:open_loop_identification: the system dynamics is identified in the absence of control.
  • Section sec:dcm_noise_budget: an open-loop noise budget is performed.
  • Section sec:active_damping_strain_gauges: it is studied whether if the strain gauges fixed to the piezoelectric actuators can be used to actively damp the plant.
  • Section sec:active_damping_iff: piezoelectric force sensors are added in series with the piezoelectric actuators and are used to actively damp the plant using the Integral Force Feedback (IFF) control strategy.
  • Section sec:hac_iff: the High Authority Control - Low Authority Control (HAC-LAC) strategy is tested on the Simscape model.

System Kinematics

<<sec:dcm_kinematics>>

Introduction   ignore

Bragg Angle

There is a simple relation eqref:eq:bragg_angle_formula between:

  • $d_{\text{off}}$ is the wanted offset between the incident x-ray and the output x-ray
  • $\theta_b$ is the bragg angle
  • $d_z$ is the corresponding distance between the first and second crystals

\begin{equation} \label{eq:bragg_angle_formula} d_z = \frac{d_{\text{off}}}{2 cos θ_b}

\end{equation}

This relation is shown in Figure fig:jack_motion_bragg_angle.

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/jack_motion_bragg_angle.png

Jack motion as a function of Bragg angle

The required jack stroke is approximately 25mm.

%% Required Jack stroke
ans = 1e3*(dz(end) - dz(1))
24.963

Kinematics (111 Crystal)

Introduction   ignore

The reference frame is taken at the center of the 111 second crystal.

Interferometers - 111 Crystal

Three interferometers are pointed to the bottom surface of the 111 crystal.

The position of the measurement points are shown in Figure fig:sensor_111_crystal_points as well as the origin where the motion of the crystal is computed.

\begin{tikzpicture}
  % Crystal
  \draw (-15/2, -3.5/2) rectangle (15/2, 3.5/2);

  % Measurement Points
  \node[branch] (a1) at (-7,  1.5){};
  \node[branch] (a2) at ( 0, -1.5){};
  \node[branch] (a3) at ( 7,  1.5){};

  % Labels
  \node[right] at (a1) {$\mathcal{O}_1 = (-0.07, -0.015)$};
  \node[right] at (a2) {$\mathcal{O}_2 = (0,      0.015)$};
  \node[left]  at (a3) {$\mathcal{O}_3 = ( 0.07, -0.015)$};

  % Origin
  \draw[->] (0, 0) node[] -- ++(1,  0) node[right]{$x$};
  \draw[->] (0, 0) -- ++(0, -1) node[below]{$y$};
  \draw[fill, color=black] (0, 0) circle (0.05);

  \node[left] at (0,0) {$\mathcal{O}_{111}$};
\end{tikzpicture}

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/sensor_111_crystal_points.png

Bottom view of the second crystal 111. Position of the measurement points.

The inverse kinematics consisting of deriving the interferometer measurements from the motion of the crystal (see Figure fig:schematic_sensor_jacobian_inverse_kinematics):

\begin{equation} \begin{bmatrix} x_1 \\ x_2 \\ x_3 \end{bmatrix} = \bm{J}_{s,111} \begin{bmatrix} d_z \\ r_y \\ r_x \end{bmatrix} \end{equation}
\begin{tikzpicture}
  % Blocs
  \node[block] (Js) {$\bm{J}_{s,111}$};

  % Connections and labels
  \draw[->] ($(Js.west)+(-1.5,0)$) node[above right]{$\begin{bmatrix} d_z \\ r_y \\ r_x \end{bmatrix}$} -- (Js.west);
  \draw[->] (Js.east)  -- ++(1.5, 0) node[above left]{$\begin{bmatrix} x_1 \\ x_2 \\ x_3 \end{bmatrix}$};
\end{tikzpicture}

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/schematic_sensor_jacobian_inverse_kinematics.png

Inverse Kinematics - Interferometers

From the Figure fig:sensor_111_crystal_points, the inverse kinematics can be solved as follow (for small motion):

\begin{equation} \bm{J}_{s,111} = \begin{bmatrix} 1 & 0.07 & -0.015 \\ 1 & 0 & 0.015 \\ 1 & -0.07 & -0.015 \end{bmatrix} \end{equation}
%% Sensor Jacobian matrix for 111 crystal
J_s_111 = [1,  0.07, -0.015
           1,  0,     0.015
           1, -0.07, -0.015];
1.0 0.07 -0.015
1.0 0.0 0.015
1.0 -0.07 -0.015

The forward kinematics is solved by inverting the Jacobian matrix (see Figure fig:schematic_sensor_jacobian_forward_kinematics).

\begin{equation} \begin{bmatrix} d_z \\ r_y \\ r_x \end{bmatrix} = \bm{J}_{s,111}^{-1} \begin{bmatrix} x_1 \\ x_2 \\ x_3 \end{bmatrix} \end{equation}
\begin{tikzpicture}
  % Blocs
  \node[block] (Js_inv) {$\bm{J}_{s,111}^{-1}$};

  % Connections and labels
  \draw[->] ($(Js_inv.west)+(-1.5,0)$) node[above right]{$\begin{bmatrix} x_1 \\ x_2 \\ x_3 \end{bmatrix}$} -- (Js_inv.west);
  \draw[->] (Js_inv.east)  -- ++(1.5, 0) node[above left]{$\begin{bmatrix} d_z \\ r_y \\ r_x \end{bmatrix}$};
\end{tikzpicture}

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/schematic_sensor_jacobian_forward_kinematics.png

Forward Kinematics - Interferometers
0.25 0.5 0.25
7.14 0.0 -7.14
-16.67 33.33 -16.67

Piezo - 111 Crystal

The location of the actuators with respect with the center of the 111 second crystal are shown in Figure fig:actuator_jacobian_111_points.

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/actuator_jacobian_111_points.png

Inverse Kinematics consist of deriving the axial (z) motion of the 3 actuators from the motion of the crystal's center.

\begin{equation} \begin{bmatrix} d_{u_r} \\ d_{u_h} \\ d_{d} \end{bmatrix} = \bm{J}_{a,111} \begin{bmatrix} d_z \\ r_y \\ r_x \end{bmatrix} \end{equation}
\begin{tikzpicture}
  % Blocs
  \node[block] (Ja) {$\bm{J}_{a,111}$};

  % Connections and labels
  \draw[->] ($(Ja.west)+(-1.5,0)$) node[above right]{$\begin{bmatrix} d_z \\ r_y \\ r_x \end{bmatrix}$} -- (Ja.west);
  \draw[->] (Ja.east)  -- ++(1.5, 0) node[above left]{$\begin{bmatrix} d_{u_r} \\ d_{u_h} \\ d_d \end{bmatrix}$};
\end{tikzpicture}

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/schematic_actuator_jacobian_inverse_kinematics.png

Inverse Kinematics - Actuators

Based on the geometry in Figure fig:actuator_jacobian_111_points, we obtain:

\begin{equation} \bm{J}_{a,111} = \begin{bmatrix} 1 & 0.14 & -0.1525 \\ 1 & 0.14 & 0.0675 \\ 1 & -0.14 & -0.0425 \end{bmatrix} \end{equation}
%% Actuator Jacobian - 111 crystal
J_a_111 = [1,  0.14, -0.1525
           1,  0.14,  0.0675
           1, -0.14, -0.0425];
1.0 0.14 -0.1525
1.0 0.14 0.0675
1.0 -0.14 -0.0425

The forward Kinematics is solved by inverting the Jacobian matrix:

\begin{equation} \begin{bmatrix} d_z \\ r_y \\ r_x \end{bmatrix} = \bm{J}_{a,111}^{-1} \begin{bmatrix} d_{u_r} \\ d_{u_h} \\ d_{d} \end{bmatrix} \end{equation}
\begin{tikzpicture}
  % Blocs
  \node[block] (Ja_inv) {$\bm{J}_{a,111}^{-1}$};

  % Connections and labels
  \draw[->] ($(Ja_inv.west)+(-1.5,0)$) node[above right]{$\begin{bmatrix} d_{u_r} \\ d_{u_h} \\ d_d \end{bmatrix}$} -- (Ja_inv.west);
  \draw[->] (Ja_inv.east)  -- ++(1.5, 0) node[above left]{$\begin{bmatrix} d_z \\ r_y \\ r_x \end{bmatrix}$};
\end{tikzpicture}

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/schematic_actuator_jacobian_forward_kinematics.png

Forward Kinematics - Actuators for 111 crystal
0.0568 0.4432 0.5
1.7857 1.7857 -3.5714
-4.5455 4.5455 0.0

Save Kinematics

save('mat/dcm_kinematics.mat', 'J_a_111', 'J_s_111')

Open Loop System Identification

<<sec:open_loop_identification>>

Introduction   ignore

Identification

Let's considered the system $\bm{G}(s)$ with:

  • 3 inputs: force applied to the 3 fast jacks
  • 3 outputs: measured displacement by the 3 interferometers pointing at the 111 second crystal

It is schematically shown in Figure fig:schematic_system_inputs_outputs.

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

  % Connections and labels
  \draw[->] ($(G.west)+(-1.5,0)$) node[above right]{$\begin{bmatrix} u_{u_r} \\ u_{u_h} \\ u_d \end{bmatrix}$} -- (G.west);
  \draw[->] (G.east)  -- ++(1.5, 0) node[above left]{$\begin{bmatrix} x_1 \\ x_2 \\ x_3 \end{bmatrix}$};
\end{tikzpicture}

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/schematic_system_inputs_outputs.png

Dynamical system with inputs and outputs

The system is identified from the Simscape model.

%% Input/Output definition
clear io; io_i = 1;

%% Inputs
% Control Input {3x1} [N]
io(io_i) = linio([mdl, '/control_system'], 1, 'openinput');  io_i = io_i + 1;

%% Outputs
% Interferometers {3x1} [m]
io(io_i) = linio([mdl, '/DCM'], 1, 'openoutput'); io_i = io_i + 1;
%% Extraction of the dynamics
G = linearize(mdl, io);
size(G)
size(G)
State-space model with 3 outputs, 3 inputs, and 24 states.

Plant in the frame of the fastjacks

load('dcm_kinematics.mat');

Using the forward and inverse kinematics, we can computed the dynamics from piezo forces to axial motion of the 3 fastjacks (see Figure fig:schematic_jacobian_frame_fastjack).

\begin{tikzpicture}
  % Blocs
  \node[block] (G) {$\bm{G}(s)$};
  \node[block, right=1.5 of G] (Js) {$\bm{J}_{s}^{-1}$};
  \node[block, right=1.5 of Js] (Ja) {$\bm{J}_{a}$};

  % Connections and labels
  \draw[->] ($(G.west)+(-1.5,0)$) node[above right]{$\begin{bmatrix} u_{u_r} \\ u_{u_h} \\ u_d \end{bmatrix}$} -- (G.west);
  \draw[->] (G.east)  -- node[midway, above]{$\begin{bmatrix} x_1 \\ x_2 \\ x_3 \end{bmatrix}$} (Js.west);
  \draw[->] (Js.east) -- node[midway, above]{$\begin{bmatrix} d_z \\ r_y \\ r_x \end{bmatrix}$} (Ja.west);
  \draw[->] (Ja.east) -- ++(1.5, 0) node[above left]{$\begin{bmatrix} d_{u_r} \\ d_{u_h} \\ d_{d} \end{bmatrix}$};

  \begin{scope}[on background layer]
    \node[fit={(G.south west) ($(Ja.east)+(0, 1.4)$)}, fill=black!20!white, draw, inner sep=6pt] (system) {};
    \node[above] at (system.north) {$\bm{G}_{\text{fj}}(s)$};
  \end{scope}
\end{tikzpicture}

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/schematic_jacobian_frame_fastjack.png

Use of Jacobian matrices to obtain the system in the frame of the fastjacks
%% Compute the system in the frame of the fastjacks
G_pz = J_a_111*inv(J_s_111)*G;

The DC gain of the new system shows that the system is well decoupled at low frequency.

dcgain(G_pz)
4.4407e-09 2.7656e-12 1.0132e-12
2.7656e-12 4.4407e-09 1.0132e-12
1.0109e-12 1.0109e-12 4.4424e-09

The bode plot of $\bm{G}_{\text{fj}}(s)$ is shown in Figure fig:bode_plot_plant_fj.

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/bode_plot_plant_fj.png

Bode plot of the diagonal and off-diagonal elements of the plant in the frame of the fast jacks

Computing the system in the frame of the fastjack gives good decoupling at low frequency (until the first resonance of the system).

Plant in the frame of the crystal

\begin{tikzpicture}
  % Blocs
  \node[block] (G) {$\bm{G}(s)$};
  \node[block, left=1.5 of G] (Ja) {$\bm{J}_{a}^{-T}$};
  \node[block, right=1.5 of G] (Js) {$\bm{J}_{s}^{-1}$};

  % Connections and labels
  \draw[->] ($(Ja.west)+(-1.5,0)$) node[above right]{$\begin{bmatrix} \mathcal{F}_{z} \\ \mathcal{M}_{y} \\ \mathcal{M}_{x} \end{bmatrix}$} -- (Ja.west);
  \draw[->] (Ja.east)  -- node[midway, above]{$\begin{bmatrix} u_{u_r} \\ u_{u_h} \\ u_d \end{bmatrix}$} (G.west);
  \draw[->] (G.east) -- node[midway, above]{$\begin{bmatrix} x_1 \\ x_2 \\ x_3 \end{bmatrix}$} (Js.west);
  \draw[->] (Js.east) -- ++(1.5, 0) node[above left]{$\begin{bmatrix} d_z \\ r_y \\ r_x \end{bmatrix}$};

  \begin{scope}[on background layer]
    \node[fit={(Ja.south west) ($(Js.east)+(0, 1.4)$)}, fill=black!20!white, draw, inner sep=6pt] (system) {};
    \node[above] at (system.north) {$\bm{G}_{\text{cr}}(s)$};
  \end{scope}
\end{tikzpicture}

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/schematic_jacobian_frame_crystal.png

Use of Jacobian matrices to obtain the system in the frame of the crystal
G_mr = inv(J_s_111)*G*inv(J_a_111');
dcgain(G_mr)
1.9978e-09 3.9657e-09 7.7944e-09
3.9656e-09 8.4979e-08 -1.5135e-17
7.7944e-09 -3.9252e-17 1.834e-07

This results in a coupled system. The main reason is that, as we map forces to the center of the 111 crystal and not at the center of mass/stiffness of the moving part, vertical forces will induce rotation and torques will induce vertical motion.

Open-Loop Noise Budgeting

<<sec:dcm_noise_budget>>

Introduction   ignore

\begin{tikzpicture}
  % Blocs
  \node[block] (G) {$G(s)$};
  \node[addb,  left= of G] (adddu) {};
  \node[block, left= of adddu] (K) {$K(s)$};
  \node[addb={+}{}{}{}{-},  left= of K] (subL) {};
  \node[addb,  right= of G] (addd) {};
  \node[addb,  below right=0.8 and 0.6 of addd] (adddn) {};

  % Connections and labels
  \draw[->] (subL.east) -- (K.west);
  \draw[->] (K.east) -- (adddu.west);
  \draw[->] (adddu.east) -- (G.west);
  \draw[->] (G.east) -- (addd.west);
  \draw[->] (addd-|adddn)node[branch]{}node[above]{$y_{\text{fj}}$} -- (adddn.north);
  \draw[->] (adddn.west) -| (subL.south) node[below right]{$y_{\text{fj},m}$};
  \draw[<-] (adddu.north) -- ++(0, 1) node[below right]{$d_u$};
  \draw[<-] (addd.north) -- ++(0, 1) node[below right]{$d_{\text{fj}}$};
  \draw[<-] (adddn.east) -- ++(1, 0)coordinate(dn) node[above left]{$n_{\text{fj}}$};
  \draw[->] (addd.east) -- (addd-|dn);
\end{tikzpicture}

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/noise_budget_dcm_schematic_fast_jack_frame.png

Schematic representation of the control loop in the frame of one fast jack

Power Spectral Density of signals

Interferometer noise:

Wn = 6e-11*(1 + s/2/pi/200)/(1 + s/2/pi/60); % m/sqrt(Hz)
Measurement noise: 0.79 [nm,rms]

DAC noise (amplified by the PI voltage amplifier, and converted to newtons):

Wdac = tf(3e-8); % V/sqrt(Hz)
Wu = Wdac*22.5*10; % N/sqrt(Hz)
DAC noise: 0.95 [uV,rms]

Disturbances:

Wd = 5e-7/(1 + s/2/pi); % m/sqrt(Hz)
Disturbance motion: 0.61 [um,rms]
%% Save ASD of noise and disturbances
save('mat/asd_noises_disturbances.mat', 'Wn', 'Wu', 'Wd');

Open Loop disturbance and measurement noise

The comparison of the amplitude spectral density of the measurement noise and of the jack parasitic motion is performed in Figure fig:open_loop_noise_budget_fast_jack. It confirms that the sensor noise is low enough to measure the motion errors of the crystal.

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/open_loop_noise_budget_fast_jack.png

Open Loop noise budgeting

Active Damping Plant (Strain gauges)

<<sec:active_damping_strain_gauges>>

Introduction   ignore

In this section, we wish to see whether if strain gauges fixed to the piezoelectric actuator can be used for active damping.

Identification

%% Input/Output definition
clear io; io_i = 1;

%% Inputs
% Control Input {3x1} [N]
io(io_i) = linio([mdl, '/control_system'], 1, 'openinput');  io_i = io_i + 1;

%% Outputs
% Strain Gauges {3x1} [m]
io(io_i) = linio([mdl, '/DCM'], 2, 'openoutput'); io_i = io_i + 1;
%% Extraction of the dynamics
G_sg = linearize(mdl, io);
dcgain(G_sg)
4.4443e-09 1.0339e-13 3.774e-14
1.0339e-13 4.4443e-09 3.774e-14
3.7792e-14 3.7792e-14 4.4444e-09

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/strain_gauge_plant_bode_plot.png

Bode Plot of the transfer functions from piezoelectric forces to strain gauges measuremed displacements

As the distance between the poles and zeros in Figure fig:iff_plant_bode_plot is very small, little damping can be actively added using the strain gauges. This will be confirmed using a Root Locus plot.

Relative Active Damping

Krad_g1 = eye(3)*s/(s^2/(2*pi*500)^2 + 2*s/(2*pi*500) + 1);

As can be seen in Figure fig:relative_damping_root_locus, very little damping can be added using relative damping strategy using strain gauges.

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/relative_damping_root_locus.png

Root Locus for the relative damping control
Krad = -g*Krad_g1;

Damped Plant

The controller is implemented on Simscape, and the damped plant is identified.

%% Input/Output definition
clear io; io_i = 1;

%% Inputs
% Control Input {3x1} [N]
io(io_i) = linio([mdl, '/control_system'], 1, 'input');  io_i = io_i + 1;

%% Outputs
% Force Sensor {3x1} [m]
io(io_i) = linio([mdl, '/DCM'], 1, 'openoutput'); io_i = io_i + 1;
%% DCM Kinematics
load('dcm_kinematics.mat');
%% Identification of the Open Loop plant
controller.type = 0; % Open Loop
G_ol = J_a_111*inv(J_s_111)*linearize(mdl, io);
G_ol.InputName  = {'u_ur',  'u_uh',  'u_d'};
G_ol.OutputName = {'d_ur',  'd_uh',  'd_d'};
%% Identification of the damped plant with Relative Active Damping
controller.type = 2; % RAD
G_dp = J_a_111*inv(J_s_111)*linearize(mdl, io);
G_dp.InputName  = {'u_ur',  'u_uh',  'u_d'};
G_dp.OutputName = {'d_ur',  'd_uh',  'd_d'};

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/comp_damp_undamped_plant_rad_bode_plot.png

Bode plot of both the open-loop plant and the damped plant using relative active damping

Active Damping Plant (Force Sensors)

<<sec:active_damping_iff>>

Introduction   ignore

Force sensors are added above the piezoelectric actuators. They can consists of a simple piezoelectric ceramic stack. See for instance cite:fleming10_integ_strain_force_feedb_high.

Identification

%% Input/Output definition
clear io; io_i = 1;

%% Inputs
% Control Input {3x1} [N]
io(io_i) = linio([mdl, '/control_system'], 1, 'openinput');  io_i = io_i + 1;

%% Outputs
% Force Sensor {3x1} [m]
io(io_i) = linio([mdl, '/DCM'], 3, 'openoutput'); io_i = io_i + 1;
%% Extraction of the dynamics
G_fs = linearize(mdl, io);

The Bode plot of the identified dynamics is shown in Figure fig:iff_plant_bode_plot. At high frequency, the diagonal terms are constants while the off-diagonal terms have some roll-off.

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/iff_plant_bode_plot.png

Bode plot of IFF Plant

Controller - Root Locus

We want to have integral action around the resonances of the system, but we do not want to integrate at low frequency. Therefore, we can use a low pass filter.

%% Integral Force Feedback Controller
Kiff_g1 = eye(3)*1/(1 + s/2/pi/20);

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/iff_root_locus.png

Root Locus plot for the IFF Control strategy
%% Integral Force Feedback Controller with optimal gain
Kiff = g*Kiff_g1;
%% Save the IFF controller
save('mat/Kiff.mat', 'Kiff');

Damped Plant

Both the Open Loop dynamics (see Figure fig:schematic_jacobian_frame_fastjack) and the dynamics with IFF (see Figure fig:schematic_jacobian_frame_fastjack_iff) are identified.

We are here interested in the dynamics from $\bm{u}^\prime = [u_{u_r}^\prime,\ u_{u_h}^\prime,\ u_d^\prime]$ (input of the damped plant) to $\bm{d}_{\text{fj}} = [d_{u_r},\ d_{u_h},\ d_d]$ (motion of the crystal expressed in the frame of the fast-jacks). This is schematically represented in Figure fig:schematic_jacobian_frame_fastjack_iff.

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

  \node[block, right=1.5 of outputL] (Js) {$\bm{J}_{s}^{-1}$};
  \node[block, right=1.5 of Js] (Ja) {$\bm{J}_{a}$};
  \node[addb,  left= of G] (addF) {};
  \node[block, above=0.5 of G] (Kiff) {$\bm{K}_{\text{IFF}}(s)$};

  % Connections and labels
  \draw[->] ($(addF.west)+(-1.5,0)$) node[above right]{$\begin{bmatrix} u_{u_r}^\prime \\ u_{u_h}^\prime \\ u_d^\prime \end{bmatrix}$} -- (addF.west);
  \draw[->] (addF.east) -- node[miday, above]{$\begin{bmatrix} u_{u_r} \\ u_{u_h} \\ u_d \end{bmatrix}$} (inputF);
  \draw[->] (outputF) -- ++(2.0, 0) node[above left]{$\begin{bmatrix} \tau_{u_r} \\ \tau_{u_h} \\ \tau_d \end{bmatrix}$};
  \draw[->] ($(outputF) + (0.6, 0)$)node[branch]{} |- (Kiff.east);
  \draw[->] (Kiff.west) -| (addF.north);
  \draw[->] (outputL) -- node[midway, above]{$\begin{bmatrix} x_1 \\ x_2 \\ x_3 \end{bmatrix}$} (Js.west);
  \draw[->] (Js.east) -- node[midway, above]{$\begin{bmatrix} d_z \\ r_y \\ r_x \end{bmatrix}$} (Ja.west);
  \draw[->] (Ja.east) -- ++(1.5, 0) node[above left]{$\begin{bmatrix} d_{u_r} \\ d_{u_h} \\ d_{d} \end{bmatrix}$};

  \begin{scope}[on background layer]
    \node[fit={(G.south -| addF.west) (Ja.east |- Kiff.north)}, fill=black!20!white, draw, inner sep=6pt] (system) {};
    \node[above] at (system.north) {$\bm{G}_{\text{fj,IFF}}(s)$};
  \end{scope}
\end{tikzpicture}

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/schematic_jacobian_frame_fastjack_iff.png

Use of Jacobian matrices to obtain the system in the frame of the fastjacks

The dynamics from $\bm{u}$ to $\bm{d}_{\text{fj}}$ (open-loop dynamics) and from $\bm{u}^\prime$ to $\bm{d}_{\text{fs}}$ are compared in Figure fig:comp_damped_undamped_plant_iff_bode_plot. It is clear that the Integral Force Feedback control strategy is very effective in damping the resonances of the plant.

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/comp_damped_undamped_plant_iff_bode_plot.png

Bode plot of both the open-loop plant and the damped plant using IFF

The Integral Force Feedback control strategy is very effective in damping the modes present in the plant.

HAC-LAC (IFF) architecture

<<sec:hac_iff>>

Introduction   ignore

The HAC-LAC architecture is shown in Figure fig:schematic_jacobian_frame_fastjack_hac_iff.

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

  \node[block, right=1.2 of outputL] (Js) {$\bm{J}_{s}^{-1}$};

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

  \node[block, left=1.2 of addF] (Khac) {$\bm{K}_{\text{HAC}}(s)$};
  \node[block, left=1.2 of Khac] (Ja) {$\bm{J}_{a}$};
  \node[addb={+}{}{}{}{-},  left=1.0 of Ja] (subL) {};


  % Connections and labels
  \draw[->] (Khac.east) -- node[midway, above]{$\begin{bmatrix} u_{u_r}^\prime \\ u_{u_h}^\prime \\ u_d^\prime \end{bmatrix}$} (addF.west);
  \draw[->] (addF.east) -- node[midway, above]{$\begin{bmatrix} u_{u_r} \\ u_{u_h} \\ u_d \end{bmatrix}$} (inputF);
  \draw[->] (outputF) -- ++(2.0, 0) node[above left]{$\begin{bmatrix} \tau_{u_r} \\ \tau_{u_h} \\ \tau_d \end{bmatrix}$};
  \draw[->] ($(outputF) + (0.6, 0)$)node[branch]{} |- (Kiff.east);
  \draw[->] (Kiff.west) -| (addF.north);
  \draw[->] (outputL) -- node[midway, above]{$\begin{bmatrix} x_1 \\ x_2 \\ x_3 \end{bmatrix}$} (Js.west);
  \draw[->] (Js.east) -- ++(1.0, 0);


  \draw[->] ($(subL.west) + (-0.8, 0)$) -- node[midway, above]{$\begin{bmatrix} r_{d_z} \\ r_{r_y} \\ r_{r_x} \end{bmatrix}$} (subL.west);
  \draw[->] (subL.east) -- node[midway, above]{$\begin{bmatrix} \epsilon_{d_z} \\ \epsilon_{r_y} \\ \epsilon_{r_x} \end{bmatrix}$} (Ja.west);
  \draw[->] (Ja.east) -- node[midway, above]{$\begin{bmatrix} \epsilon_{d_{u_r}} \\ \epsilon_{d_{u_h}} \\ \epsilon_{d_d} \end{bmatrix}$} (Khac.west);

  \draw[->] ($(Js.east) + (0.6, 0)$)node[branch]{}node[above]{$\begin{bmatrix} d_z \\ r_y \\ r_x \end{bmatrix}$} -- ++(0, -1.0) -| (subL.south);
\end{tikzpicture}

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/schematic_jacobian_frame_fastjack_hac_iff.png

System Identification

Let's identify the damped plant.

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/bode_plot_hac_iff_plant.png

Bode Plot of the plant for the High Authority Controller (transfer function from $\bm{u}^\prime$ to $\bm{\epsilon}_d$)

High Authority Controller

Let's design a controller with a bandwidth of 100Hz. As the plant is well decoupled and well approximated by a constant at low frequency, the high authority controller can easily be designed with SISO loop shaping.

%% Controller design
wc = 2*pi*100; % Wanted crossover frequency [rad/s]
a = 2; % Lead parameter

Khac = diag(1./diag(abs(evalfr(G_dp, 1j*wc)))) * ... % Diagonal controller
        wc/s * ... % Integrator
        1/(sqrt(a))*(1 + s/(wc/sqrt(a)))/(1 + s/(wc*sqrt(a))) * ... % Lead
        1/(s^2/(4*wc)^2 + 2*s/(4*wc) + 1); % Low pass filter
%% Save the HAC controller
save('mat/Khac_iff.mat', 'Khac');
%% Loop Gain
L_hac_lac = G_dp * Khac;

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/hac_iff_loop_gain_bode_plot.png

Bode Plot of the Loop gain for the High Authority Controller

As shown in the Root Locus plot in Figure fig:loci_hac_iff_fast_jack, the closed loop system should be stable.

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/loci_hac_iff_fast_jack.png

Root Locus for the High Authority Controller

Performances

In order to estimate the performances of the HAC-IFF control strategy, the transfer function from motion errors of the stepper motors to the motion error of the crystal is identified both in open loop and with the HAC-IFF strategy.

It is first verified that the closed-loop system is stable:

isstable(T_hl)
1

And both transmissibilities are compared in Figure fig:stepper_transmissibility_comp_ol_hac_iff.

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/stepper_transmissibility_comp_ol_hac_iff.png

Comparison of the transmissibility of errors from vibrations of the stepper motor between the open-loop case and the hac-iff case.

The HAC-IFF control strategy can effectively reduce the transmissibility of the motion errors of the stepper motors. This reduction is effective inside the bandwidth of the controller.

Close Loop noise budget

Let's compute the amplitude spectral density of the jack motion errors due to the sensor noise, the actuator noise and disturbances.

%% Computation of ASD of contribution of inputs to the closed-loop motion
% Error due to disturbances
asd_d = abs(squeeze(freqresp(Wd*(1/(1 + G_dp(1,1)*Khac(1,1))), f, 'Hz')));
% Error due to actuator noise
asd_u = abs(squeeze(freqresp(Wu*(G_dp(1,1)/(1 + G_dp(1,1)*Khac(1,1))), f, 'Hz')));
% Error due to sensor noise
asd_n = abs(squeeze(freqresp(Wn*(G_dp(1,1)*Khac(1,1)/(1 + G_dp(1,1)*Khac(1,1))), f, 'Hz')));

The closed-loop ASD is then:

%% ASD of the closed-loop motion
asd_cl = sqrt(asd_d.^2 + asd_u.^2 + asd_n.^2);

The obtained ASD are shown in Figure fig:close_loop_asd_noise_budget_hac_iff.

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/close_loop_asd_noise_budget_hac_iff.png

Closed Loop noise budget

Let's compare the open-loop and close-loop cases (Figure fig:cps_comp_ol_cl_hac_iff).

/tdehaeze/dcm-simscape-model/media/commit/37e98a9f403d7d8297d699f60f516b3ac0a51807/figs/cps_comp_ol_cl_hac_iff.png

Cumulative Power Spectrum of the open-loop and closed-loop motion error along one fast-jack

Bibliography   ignore