stewart-simscape/org/control-study.org
2020-03-03 15:53:02 +01:00

44 KiB

Stewart Platform - Vibration Isolation

HAC-LAC (Cascade) Control - Integral Control

Introduction

In this section, we wish to study the use of the High Authority Control - Low Authority Control (HAC-LAC) architecture on the Stewart platform.

The control architectures are shown in Figures fig:control_arch_hac_iff and fig:control_arch_hac_dvf.

First, the LAC loop is closed (the LAC control is described here), and then the HAC controller is designed and the outer loop is closed.

  \begin{tikzpicture}
    % Blocs
    \node[block={2.0cm}{2.0cm}] (P) {};
    \node[above] at (P.north) {Plant};
    \node[block, below=0.7 of P] (Kiff) {$\bm{K}_\text{IFF}$};
    \node[block, below=0.7 of Kiff] (Khac) {$\bm{K}_\text{HAC}$};

    % Add
    \node[addb, left=1 of P] (add) {};

    \node[block, left=1 of add] (J) {$\bm{J}^{-T}$};

    % Input and outputs coordinates
    \coordinate[] (outputhac) at ($(P.south east)!0.75!(P.north east)$);
    \coordinate[] (outputiff) at ($(P.south east)!0.25!(P.north east)$);

    \draw[->] (outputiff) node[above right]{$\bm{\tau}_m$} -- ++(0.8, 0) |- (Kiff.east);
    \draw[->] (outputhac) node[above right]{$\bm{\mathcal{X}}$} -- ++(1.6, 0) |- (Khac.east);

    \draw[->] (Kiff.west) -| (add.south);

    \draw[->] (J.east) -- (add.west);
    \draw[<-] (J.west) node[above left]{$\bm{\mathcal{F}}$} -- ++(-0.8, 0) |- (Khac.west);
    \draw[->] (add.east) -- (P.west) node[above left]{$\bm{\tau}$};
  \end{tikzpicture}

/tdehaeze/stewart-simscape/media/commit/d87701c3ad7edf99aacf75bc4240ea8aeb5740fc/org/figs/control_arch_hac_iff.png

HAC-LAC architecture with IFF
  \begin{tikzpicture}
    % Blocs
    \node[block={2.0cm}{2.0cm}] (P) {};
    \node[above] at (P.north) {Plant};
    \node[block, below=0.7 of P] (Kdvf) {$\bm{K}_\text{DVF}$};
    \node[block, below=0.7 of Kdvf] (Khac) {$\bm{K}_\text{HAC}$};

    % Add
    \node[addb, left=1 of P] (add) {};

    \node[block, left=1 of add] (J) {$\bm{J}^{-T}$};

    % Input and outputs coordinates
    \coordinate[] (outputhac) at ($(P.south east)!0.75!(P.north east)$);
    \coordinate[] (outputdvf) at ($(P.south east)!0.25!(P.north east)$);

    \draw[->] (outputdvf) node[above right]{$\delta \bm{\mathcal{L}}_m$} -- ++(0.8, 0) |- (Kdvf.east);
    \draw[->] (outputhac) node[above right]{$\bm{\mathcal{X}}$} -- ++(1.6, 0) |- (Khac.east);

    \draw[->] (Kdvf.west) -| (add.south);

    \draw[->] (J.east) -- (add.west);
    \draw[<-] (J.west) node[above left]{$\bm{\mathcal{F}}$} -- ++(-0.8, 0) |- (Khac.west);
    \draw[->] (add.east) -- (P.west) node[above left]{$\bm{\tau}$};
  \end{tikzpicture}

/tdehaeze/stewart-simscape/media/commit/d87701c3ad7edf99aacf75bc4240ea8aeb5740fc/org/figs/control_arch_hac_dvf.png

HAC-LAC architecture with DVF

Initialization

We first initialize the Stewart platform.

  stewart = initializeStewartPlatform();
  stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
  stewart = generateGeneralConfiguration(stewart);
  stewart = computeJointsPose(stewart);
  stewart = initializeStrutDynamics(stewart);
  stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical');
  stewart = initializeCylindricalPlatforms(stewart);
  stewart = initializeCylindricalStruts(stewart);
  stewart = computeJacobian(stewart);
  stewart = initializeStewartPose(stewart);
  stewart = initializeInertialSensor(stewart, 'type', 'none');

The rotation point of the ground is located at the origin of frame $\{A\}$.

  ground = initializeGround('type', 'rigid', 'rot_point', stewart.platform_F.FO_A);
  payload = initializePayload('type', 'none');

Identification

Introduction   ignore

We identify the transfer function from the actuator forces $\bm{\tau}$ to the absolute displacement of the mobile platform $\bm{\mathcal{X}}$ in three different cases:

  • Open Loop plant
  • Already damped plant using Integral Force Feedback
  • Already damped plant using Direct velocity feedback

HAC - Without LAC

  controller = initializeController('type', 'open-loop');
  %% Name of the Simulink File
  mdl = 'stewart_platform_model';

  %% Input/Output definition
  clear io; io_i = 1;
  io(io_i) = linio([mdl, '/Controller'],              1, 'input');      io_i = io_i + 1; % Actuator Force Inputs [N]
  io(io_i) = linio([mdl, '/Absolute Motion Sensor'],  1, 'openoutput'); io_i = io_i + 1; % Absolute Sensor [m, rad]

  %% Run the linearization
  G_ol = linearize(mdl, io);
  G_ol.InputName  = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
  G_ol.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};

HAC - IFF

  controller = initializeController('type', 'iff');
  K_iff = -(1e4/s)*eye(6);
  %% Name of the Simulink File
  mdl = 'stewart_platform_model';

  %% Input/Output definition
  clear io; io_i = 1;
  io(io_i) = linio([mdl, '/Controller'],              1, 'input');      io_i = io_i + 1; % Actuator Force Inputs [N]
  io(io_i) = linio([mdl, '/Absolute Motion Sensor'],  1, 'openoutput'); io_i = io_i + 1; % Absolute Sensor [m, rad]

  %% Run the linearization
  G_iff = linearize(mdl, io);
  G_iff.InputName  = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
  G_iff.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};

HAC - DVF

  controller = initializeController('type', 'dvf');
  K_dvf = -1e4*s/(1+s/2/pi/5000)*eye(6);
  %% Name of the Simulink File
  mdl = 'stewart_platform_model';

  %% Input/Output definition
  clear io; io_i = 1;
  io(io_i) = linio([mdl, '/Controller'],              1, 'input');      io_i = io_i + 1; % Actuator Force Inputs [N]
  io(io_i) = linio([mdl, '/Absolute Motion Sensor'],  1, 'openoutput'); io_i = io_i + 1; % Absolute Sensor [m, rad]

  %% Run the linearization
  G_dvf = linearize(mdl, io);
  G_dvf.InputName  = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
  G_dvf.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};

Control Architecture

We use the Jacobian to express the actuator forces in the cartesian frame, and thus we obtain the transfer functions from $\bm{\mathcal{F}}$ to $\bm{\mathcal{X}}$.

  Gc_ol = minreal(G_ol)/stewart.kinematics.J';
  Gc_ol.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};

  Gc_iff = minreal(G_iff)/stewart.kinematics.J';
  Gc_iff.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};

  Gc_dvf = minreal(G_dvf)/stewart.kinematics.J';
  Gc_dvf.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};

We then design a controller based on the transfer functions from $\bm{\mathcal{F}}$ to $\bm{\mathcal{X}}$, finally, we will pre-multiply the controller by $\bm{J}^{-T}$.

6x6 Plant Comparison

<<plt-matlab>>
/tdehaeze/stewart-simscape/media/commit/d87701c3ad7edf99aacf75bc4240ea8aeb5740fc/org/figs/hac_lac_coupling_jacobian.png
Norm of the transfer functions from $\bm{\mathcal{F}}$ to $\bm{\mathcal{X}}$ (png, pdf)

HAC - DVF

Plant

<<plt-matlab>>
/tdehaeze/stewart-simscape/media/commit/d87701c3ad7edf99aacf75bc4240ea8aeb5740fc/org/figs/hac_lac_plant_dvf.png
Diagonal elements of the plant for HAC control when DVF is previously applied (png, pdf)

Controller Design

We design a diagonal controller with equal bandwidth for the 6 terms. The controller is a pure integrator with a small lead near the crossover.

  wc = 2*pi*300; % Wanted Bandwidth [rad/s]

  h = 1.2;
  H_lead = 1/h*(1 + s/(wc/h))/(1 + s/(wc*h));

  Kd_dvf = diag(1./abs(diag(freqresp(1/s*Gc_dvf, wc)))) .* H_lead .* 1/s;
<<plt-matlab>>
/tdehaeze/stewart-simscape/media/commit/d87701c3ad7edf99aacf75bc4240ea8aeb5740fc/org/figs/hac_lac_loop_gain_dvf.png
Diagonal elements of the Loop Gain for the HAC control (png, pdf)

Finally, we pre-multiply the diagonal controller by $\bm{J}^{-T}$ prior implementation.

  K_hac_dvf = inv(stewart.kinematics.J')*Kd_dvf;

Obtained Performance

We identify the transmissibility and compliance of the system.

  controller = initializeController('type', 'open-loop');
  [T_ol, T_norm_ol, freqs] = computeTransmissibility();
  [C_ol, C_norm_ol, ~] = computeCompliance();
  controller = initializeController('type', 'dvf');
  [T_dvf, T_norm_dvf, ~] = computeTransmissibility();
  [C_dvf, C_norm_dvf, ~] = computeCompliance();
  controller = initializeController('type', 'hac-dvf');
  [T_hac_dvf, T_norm_hac_dvf, ~] = computeTransmissibility();
  [C_hac_dvf, C_norm_hac_dvf, ~] = computeCompliance();
<<plt-matlab>>
/tdehaeze/stewart-simscape/media/commit/d87701c3ad7edf99aacf75bc4240ea8aeb5740fc/org/figs/hac_lac_C_T_dvf.png
Obtained Compliance and Transmissibility (png, pdf)

HAC - IFF

Plant

<<plt-matlab>>
/tdehaeze/stewart-simscape/media/commit/d87701c3ad7edf99aacf75bc4240ea8aeb5740fc/org/figs/hac_lac_plant_iff.png
Diagonal elements of the plant for HAC control when IFF is previously applied (png, pdf)

Controller Design

We design a diagonal controller with equal bandwidth for the 6 terms. The controller is a pure integrator with a small lead near the crossover.

  wc = 2*pi*300; % Wanted Bandwidth [rad/s]

  h = 1.2;
  H_lead = 1/h*(1 + s/(wc/h))/(1 + s/(wc*h));

  Kd_iff = diag(1./abs(diag(freqresp(1/s*Gc_iff, wc)))) .* H_lead .* 1/s;
<<plt-matlab>>
/tdehaeze/stewart-simscape/media/commit/d87701c3ad7edf99aacf75bc4240ea8aeb5740fc/org/figs/hac_lac_loop_gain_iff.png
Diagonal elements of the Loop Gain for the HAC control (png, pdf)

Finally, we pre-multiply the diagonal controller by $\bm{J}^{-T}$ prior implementation.

  K_hac_iff = inv(stewart.kinematics.J')*Kd_iff;

Obtained Performance

We identify the transmissibility and compliance of the system.

  controller = initializeController('type', 'open-loop');
  [T_ol, T_norm_ol, freqs] = computeTransmissibility();
  [C_ol, C_norm_ol, ~] = computeCompliance();
  controller = initializeController('type', 'iff');
  [T_iff, T_norm_iff, ~] = computeTransmissibility();
  [C_iff, C_norm_iff, ~] = computeCompliance();
  controller = initializeController('type', 'hac-iff');
  [T_hac_iff, T_norm_hac_iff, ~] = computeTransmissibility();
  [C_hac_iff, C_norm_hac_iff, ~] = computeCompliance();
<<plt-matlab>>
/tdehaeze/stewart-simscape/media/commit/d87701c3ad7edf99aacf75bc4240ea8aeb5740fc/org/figs/hac_lac_C_T_iff.png
Obtained Compliance and Transmissibility (png, pdf)

Comparison

<<plt-matlab>>
/tdehaeze/stewart-simscape/media/commit/d87701c3ad7edf99aacf75bc4240ea8aeb5740fc/org/figs/hac_lac_C_full_comparison.png
Comparison of the norm of the Compliance matrices for the HAC-LAC architecture (png, pdf)
<<plt-matlab>>
/tdehaeze/stewart-simscape/media/commit/d87701c3ad7edf99aacf75bc4240ea8aeb5740fc/org/figs/hac_lac_T_full_comparison.png
Comparison of the norm of the Transmissibility matrices for the HAC-LAC architecture (png, pdf)
<<plt-matlab>>
/tdehaeze/stewart-simscape/media/commit/d87701c3ad7edf99aacf75bc4240ea8aeb5740fc/org/figs/hac_lac_C_T_comparison.png
Comparison of the Frobenius norm of the Compliance and Transmissibility for the HAC-LAC architecture with both IFF and DVF (png, pdf)

MIMO Analysis

Introduction   ignore

Let's define the system as shown in figure fig:general_control_names.

  \begin{tikzpicture}

    % Blocs
    \node[block={2.0cm}{2.0cm}] (P) {$P$};
    \node[block={1.5cm}{1.5cm}, below=0.7 of P] (K) {$K$};

    % Input and outputs coordinates
    \coordinate[] (inputw)  at ($(P.south west)!0.75!(P.north west)$);
    \coordinate[] (inputu)  at ($(P.south west)!0.25!(P.north west)$);
    \coordinate[] (outputz) at ($(P.south east)!0.75!(P.north east)$);
    \coordinate[] (outputv) at ($(P.south east)!0.25!(P.north east)$);

    % Connections and labels
    \draw[<-] (inputw) node[above left, align=right]{(weighted)\\exogenous inputs\\$w$} -- ++(-1.5, 0);
    \draw[<-] (inputu) -- ++(-0.8, 0) |- node[left, near start, align=right]{control signals\\$u$} (K.west);

    \draw[->] (outputz) node[above right, align=left]{(weighted)\\exogenous outputs\\$z$} -- ++(1.5, 0);
    \draw[->] (outputv) -- ++(0.8, 0) |- node[right, near start, align=left]{sensed output\\$v$} (K.east);
  \end{tikzpicture}

/tdehaeze/stewart-simscape/media/commit/d87701c3ad7edf99aacf75bc4240ea8aeb5740fc/org/figs/general_control_names.png

General Control Architecture
Exogenous Inputs $\bm{\mathcal{X}}_w$ Ground motion
$\bm{\mathcal{F}}_d$ External Forces applied to the Payload
$\bm{r}$ Reference signal for tracking
Exogenous Outputs $\bm{\mathcal{X}}$ Absolute Motion of the Payload
$\bm{\tau}$ Actuator Rate
Sensed Outputs $\bm{\tau}_m$ Force Sensors in each leg
$\delta \bm{\mathcal{L}}_m$ Measured displacement of each leg
$\bm{\mathcal{X}}$ Absolute Motion of the Payload
Control Signals $\bm{\tau}$ Actuator Inputs
Signals definition for the generalized plant

Initialization

We first initialize the Stewart platform.

  stewart = initializeStewartPlatform();
  stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
  stewart = generateGeneralConfiguration(stewart);
  stewart = computeJointsPose(stewart);
  stewart = initializeStrutDynamics(stewart);
  stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical');
  stewart = initializeCylindricalPlatforms(stewart);
  stewart = initializeCylindricalStruts(stewart);
  stewart = computeJacobian(stewart);
  stewart = initializeStewartPose(stewart);
  stewart = initializeInertialSensor(stewart, 'type', 'none');

The rotation point of the ground is located at the origin of frame $\{A\}$.

  ground = initializeGround('type', 'rigid', 'rot_point', stewart.platform_F.FO_A);
  payload = initializePayload('type', 'none');

Identification

HAC - Without LAC

  controller = initializeController('type', 'open-loop');
  %% Name of the Simulink File
  mdl = 'stewart_platform_model';

  %% Input/Output definition
  clear io; io_i = 1;
  io(io_i) = linio([mdl, '/Controller'],              1, 'input');      io_i = io_i + 1; % Actuator Force Inputs [N]
  io(io_i) = linio([mdl, '/Absolute Motion Sensor'],  1, 'openoutput'); io_i = io_i + 1; % Absolute Sensor [m, rad]

  %% Run the linearization
  G_ol = linearize(mdl, io);
  G_ol.InputName  = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
  G_ol.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};

HAC - DVF

  controller = initializeController('type', 'dvf');
  K_dvf = -1e4*s/(1+s/2/pi/5000)*eye(6);
  %% Name of the Simulink File
  mdl = 'stewart_platform_model';

  %% Input/Output definition
  clear io; io_i = 1;
  io(io_i) = linio([mdl, '/Controller'],              1, 'input');      io_i = io_i + 1; % Actuator Force Inputs [N]
  io(io_i) = linio([mdl, '/Absolute Motion Sensor'],  1, 'openoutput'); io_i = io_i + 1; % Absolute Sensor [m, rad]

  %% Run the linearization
  G_dvf = linearize(mdl, io);
  G_dvf.InputName  = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
  G_dvf.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};

Cartesian Frame

  Gc_ol = minreal(G_ol)/stewart.kinematics.J';
  Gc_ol.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};

  Gc_dvf = minreal(G_dvf)/stewart.kinematics.J';
  Gc_dvf.InputName = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'};

Singular Value Decomposition

  freqs = logspace(1, 4, 1000);

  U_ol = zeros(6,6,length(freqs));
  S_ol = zeros(6,length(freqs));
  V_ol = zeros(6,6,length(freqs));

  U_dvf = zeros(6,6,length(freqs));
  S_dvf = zeros(6,length(freqs));
  V_dvf = zeros(6,6,length(freqs));

  for i = 1:length(freqs)
    [U,S,V] = svd(freqresp(Gc_ol, freqs(i), 'Hz'));
    U_ol(:,:,i) = U;
    S_ol(:,i) = diag(S);
    V_ol(:,:,i) = V;

    [U,S,V] = svd(freqresp(Gc_dvf, freqs(i), 'Hz'));
    U_dvf(:,:,i) = U;
    S_dvf(:,i) = diag(S);
    V_dvf(:,:,i) = V;
  end

Diagonal Control based on the damped plant

Introduction   ignore

From cite:skogestad07_multiv_feedb_contr, a simple approach to multivariable control is the following two-step procedure:

  1. Design a pre-compensator $W_1$, which counteracts the interactions in the plant and results in a new shaped plant $G_S(s) = G(s) W_1(s)$ which is more diagonal and easier to control than the original plant $G(s)$.
  2. Design a diagonal controller $K_S(s)$ for the shaped plant using methods similar to those for SISO systems.

The overall controller is then: \[ K(s) = W_1(s)K_s(s) \]

There are mainly three different cases:

  1. Dynamic decoupling: $G_S(s)$ is diagonal at all frequencies. For that we can choose $W_1(s) = G^{-1}(s)$ and this is an inverse-based controller.
  2. Steady-state decoupling: $G_S(0)$ is diagonal. This can be obtained by selecting $W_1(s) = G^{-1}(0)$.
  3. Approximate decoupling at frequency $\w_0$: $G_S(j\w_0)$ is as diagonal as possible. Decoupling the system at $\w_0$ is a good choice because the effect on performance of reducing interaction is normally greatest at this frequency.

Initialization

We first initialize the Stewart platform.

  stewart = initializeStewartPlatform();
  stewart = initializeFramesPositions(stewart, 'H', 90e-3, 'MO_B', 45e-3);
  stewart = generateGeneralConfiguration(stewart);
  stewart = computeJointsPose(stewart);
  stewart = initializeStrutDynamics(stewart);
  stewart = initializeJointDynamics(stewart, 'type_F', 'universal', 'type_M', 'spherical');
  stewart = initializeCylindricalPlatforms(stewart);
  stewart = initializeCylindricalStruts(stewart);
  stewart = computeJacobian(stewart);
  stewart = initializeStewartPose(stewart);
  stewart = initializeInertialSensor(stewart, 'type', 'none');

The rotation point of the ground is located at the origin of frame $\{A\}$.

  ground = initializeGround('type', 'rigid', 'rot_point', stewart.platform_F.FO_A);
  payload = initializePayload('type', 'none');

Identification

  controller = initializeController('type', 'dvf');
  K_dvf = -1e4*s/(1+s/2/pi/5000)*eye(6);
  %% Name of the Simulink File
  mdl = 'stewart_platform_model';

  %% Input/Output definition
  clear io; io_i = 1;
  io(io_i) = linio([mdl, '/Controller'],              1, 'input');      io_i = io_i + 1; % Actuator Force Inputs [N]
  io(io_i) = linio([mdl, '/Absolute Motion Sensor'],  1, 'openoutput'); io_i = io_i + 1; % Absolute Sensor [m, rad]

  %% Run the linearization
  G_dvf = linearize(mdl, io);
  G_dvf.InputName  = {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'};
  G_dvf.OutputName = {'Dx', 'Dy', 'Dz', 'Rx', 'Ry', 'Rz'};

Steady State Decoupling

Pre-Compensator Design

We choose $W_1 = G^{-1}(0)$.

  W1 = inv(freqresp(G_dvf, 0));

The (static) decoupled plant is $G_s(s) = G(s) W_1$.

  Gs = G_dvf*W1;

In the case of the Stewart platform, the pre-compensator for static decoupling is equal to $\mathcal{K} \bm{J}$:

\begin{align*} W_1 &= \left( \frac{\bm{\mathcal{X}}}{\bm{\tau}}(s=0) \right)^{-1}\\ &= \left( \frac{\bm{\mathcal{X}}}{\bm{\tau}}(s=0) \bm{J}^T \right)^{-1}\\ &= \left( \bm{C} \bm{J}^T \right)^{-1}\\ &= \left( \bm{J}^{-1} \mathcal{K}^{-1} \right)^{-1}\\ &= \mathcal{K} \bm{J} \end{align*}

The static decoupled plant is schematic shown in Figure fig:control_arch_static_decoupling and the bode plots of its diagonal elements are shown in Figure fig:static_decoupling_diagonal_plant.

  \begin{tikzpicture}
    % Blocs
    \node[block] (G) {$G(s)$};
    \node[block, left=1 of G] (J) {$\mathcal{K}\bm{J}$};
    \node[block, left=1 of J] (Ks) {$\bm{K}_s(s)$};

    \draw[->] (Ks.east) -- (J.west);
    \draw[->] (J.east) -- (G.west) node[above left]{$\bm{\tau}$};
    \draw[->] (G.east) node[above right]{$\bm{\mathcal{X}}$} -| ++(0.8, -0.8) -| ($(Ks.west) + (-0.8, 0)$) -- (Ks.west);

    \begin{scope}[on background layer]
      \node[fit={(J.north west) (G.south east)}, inner sep=4pt, draw, dashed, fill=black!20!white, label={$G_s(s)$}] {};
    \end{scope}
  \end{tikzpicture}

/tdehaeze/stewart-simscape/media/commit/d87701c3ad7edf99aacf75bc4240ea8aeb5740fc/org/figs/control_arch_static_decoupling.png

Static Decoupling of the Stewart platform
<<plt-matlab>>
/tdehaeze/stewart-simscape/media/commit/d87701c3ad7edf99aacf75bc4240ea8aeb5740fc/org/figs/static_decoupling_diagonal_plant.png
Bode plot of the diagonal elements of $G_s(s)$ (png, pdf)

Diagonal Control Design

We design a diagonal controller $K_s(s)$ that consist of a pure integrator and a lead around the crossover.

  wc = 2*pi*300; % Wanted Bandwidth [rad/s]

  h = 1.5;
  H_lead = 1/h*(1 + s/(wc/h))/(1 + s/(wc*h));

  Ks_dvf = diag(1./abs(diag(freqresp(1/s*Gs, wc)))) .* H_lead .* 1/s;

The overall controller is then $K(s) = W_1 K_s(s)$ as shown in Figure fig:control_arch_static_decoupling_K.

  K_hac_dvf = W1 * Ks_dvf;
  \begin{tikzpicture}
    % Blocs
    \node[block] (G) {$G(s)$};
    \node[block, left=1 of G] (J) {$\mathcal{K}\bm{J}$};
    \node[block, left=1 of J] (Ks) {$\bm{K}_s(s)$};

    \draw[->] (Ks.east) -- (J.west);
    \draw[->] (J.east) -- (G.west) node[above left]{$\bm{\tau}$};
    \draw[->] (G.east) node[above right]{$\bm{\mathcal{X}}$} -| ++(0.8, -0.8) -| ($(Ks.west) + (-0.8, 0)$) -- (Ks.west);

    \begin{scope}[on background layer]
      \node[fit={(Ks.north west) (J.south east)}, inner sep=4pt, draw, dashed, fill=black!20!white, label={$K(s)$}] {};
    \end{scope}
  \end{tikzpicture}

/tdehaeze/stewart-simscape/media/commit/d87701c3ad7edf99aacf75bc4240ea8aeb5740fc/org/figs/control_arch_static_decoupling_K.png

Controller including the static decoupling matrix

Results

We identify the transmissibility and compliance of the Stewart platform under open-loop and closed-loop control.

  controller = initializeController('type', 'open-loop');
  [T_ol, T_norm_ol, freqs] = computeTransmissibility();
  [C_ol, C_norm_ol, ~] = computeCompliance();
  controller = initializeController('type', 'hac-dvf');
  [T_hac_dvf, T_norm_hac_dvf, ~] = computeTransmissibility();
  [C_hac_dvf, C_norm_hac_dvf, ~] = computeCompliance();

The results are shown in figure

<<plt-matlab>>
/tdehaeze/stewart-simscape/media/commit/d87701c3ad7edf99aacf75bc4240ea8aeb5740fc/org/figs/static_decoupling_C_T_frobenius_norm.png
Frobenius norm of the Compliance and transmissibility matrices (png, pdf)

Decoupling at Crossover

  • Find a method for real approximation of a complex matrix

Functions

initializeController: Initialize the Controller

<<sec:initializeController>>

Function description

  function [controller] = initializeController(args)
  % initializeController - Initialize the Controller
  %
  % Syntax: [] = initializeController(args)
  %
  % Inputs:
  %    - args - Can have the following fields:

Optional Parameters

  arguments
    args.type   char   {mustBeMember(args.type, {'open-loop', 'iff', 'dvf', 'hac-iff', 'hac-dvf'})} = 'open-loop'
  end

Structure initialization

  controller = struct();

Add Type

  switch args.type
    case 'open-loop'
      controller.type = 0;
    case 'iff'
      controller.type = 1;
    case 'dvf'
      controller.type = 2;
    case 'hac-iff'
      controller.type = 3;
    case 'hac-dvf'
      controller.type = 4;
  end