From 7fb03f7b9074f37dba0d5e119b2e44e5a056ab90 Mon Sep 17 00:00:00 2001 From: Thomas Dehaeze Date: Mon, 25 Mar 2019 18:12:43 +0100 Subject: [PATCH] Update study: cubic configuration, renew the function for generation --- .gitignore | 263 ++++- cubic-configuration.html | 1349 ++++++++++++++++++++++++++ cubic-configuration.org | 607 ++++++++++++ figs/3d-cubic-stewart-aligned.png | Bin 0 -> 22156 bytes figs/3d-cubic-stewart-misaligned.png | Bin 0 -> 22010 bytes figs/stiffness_cube_size.pdf | Bin 0 -> 39000 bytes figs/stiffness_cube_size.png | Bin 0 -> 23430 bytes figs/stiffness_cube_size.svg | 113 +++ figs/stiffness_cube_size.tex | 54 ++ identification.org | 121 ++- index.html | 25 +- index.org | 3 +- kinematic-study.org | 24 + mat/sample.mat | Bin 278 -> 278 bytes mat/stewart.mat | Bin 1474 -> 729 bytes references.bib | 37 + simscape-model.html | 716 +++++++++----- simscape-model.org | 574 +++++------ src/computeGeometricalProperties.m | 59 ++ src/identifyPlant.m | 2 +- src/initializeCubicConfiguration.m | 89 ++ src/initializeGeneralConfiguration.m | 47 + src/initializeHexapod.m | 203 +--- src/initializeMechanicalElements.m | 94 ++ src/initializeSample.m | 33 +- src/initializeSimscapeData.m | 59 ++ src/initializeStewartPlatform.m | 94 ++ stewart.slx | Bin 67479 -> 59838 bytes stiffness-study.org | 24 + 29 files changed, 3773 insertions(+), 817 deletions(-) create mode 100644 cubic-configuration.html create mode 100644 cubic-configuration.org create mode 100644 figs/3d-cubic-stewart-aligned.png create mode 100644 figs/3d-cubic-stewart-misaligned.png create mode 100644 figs/stiffness_cube_size.pdf create mode 100644 figs/stiffness_cube_size.png create mode 100644 figs/stiffness_cube_size.svg create mode 100644 figs/stiffness_cube_size.tex create mode 100644 references.bib create mode 100644 src/computeGeometricalProperties.m create mode 100644 src/initializeCubicConfiguration.m create mode 100644 src/initializeGeneralConfiguration.m create mode 100644 src/initializeMechanicalElements.m create mode 100644 src/initializeSimscapeData.m create mode 100644 src/initializeStewartPlatform.m diff --git a/.gitignore b/.gitignore index ddb0206..f218434 100644 --- a/.gitignore +++ b/.gitignore @@ -1,2 +1,261 @@ -Figures/ -slprj/ \ No newline at end of file +mat/ +figures/ +ltximg/ +slprj/ +*.autosave +*.original +old/ + + +# ============================================================ +# ============================================================ +# LATEX +# ============================================================ +# ============================================================ + +## Core latex/pdflatex auxiliary files: +*.aux +*.lof +*.log +*.lot +*.fls +*.out +*.toc +*.fmt +*.fot +*.cb +*.cb2 +.*.lb + +## Intermediate documents: +*.dvi +*.xdv +*-converted-to.* +# these rules might exclude image files for figures etc. +# *.ps +# *.eps +# *.pdf + +## Generated if empty string is given at "Please type another file name for output:" +.pdf + +## Bibliography auxiliary files (bibtex/biblatex/biber): +*.bbl +*.bcf +*.blg +*-blx.aux +*-blx.bib +*.run.xml + +## Build tool auxiliary files: +*.fdb_latexmk +*.synctex +*.synctex(busy) +*.synctex.gz +*.synctex.gz(busy) +*.pdfsync + +## Build tool directories for auxiliary files +# latexrun +latex.out/ + +## Auxiliary and intermediate files from other packages: +# algorithms +*.alg +*.loa + +# achemso +acs-*.bib + +# amsthm +*.thm + +# beamer +*.nav +*.pre +*.snm +*.vrb + +# changes +*.soc + +# cprotect +*.cpt + +# elsarticle (documentclass of Elsevier journals) +*.spl + +# endnotes +*.ent + +# fixme +*.lox + +# feynmf/feynmp +*.mf +*.mp +*.t[1-9] +*.t[1-9][0-9] +*.tfm + +#(r)(e)ledmac/(r)(e)ledpar +*.end +*.?end +*.[1-9] +*.[1-9][0-9] +*.[1-9][0-9][0-9] +*.[1-9]R +*.[1-9][0-9]R +*.[1-9][0-9][0-9]R +*.eledsec[1-9] +*.eledsec[1-9]R +*.eledsec[1-9][0-9] +*.eledsec[1-9][0-9]R +*.eledsec[1-9][0-9][0-9] +*.eledsec[1-9][0-9][0-9]R + +# glossaries +*.acn +*.acr +*.glg +*.glo +*.gls +*.glsdefs + +# gnuplottex +*-gnuplottex-* + +# gregoriotex +*.gaux +*.gtex + +# htlatex +*.4ct +*.4tc +*.idv +*.lg +*.trc +*.xref + +# hyperref +*.brf + +# knitr +*-concordance.tex +# TODO Comment the next line if you want to keep your tikz graphics files +*.tikz +*-tikzDictionary + +# listings +*.lol + +# makeidx +*.idx +*.ilg +*.ind +*.ist + +# minitoc +*.maf +*.mlf +*.mlt +*.mtc[0-9]* +*.slf[0-9]* +*.slt[0-9]* +*.stc[0-9]* + +# minted +_minted* +*.pyg + +# morewrites +*.mw + +# nomencl +*.nlg +*.nlo +*.nls + +# pax +*.pax + +# pdfpcnotes +*.pdfpc + +# sagetex +*.sagetex.sage +*.sagetex.py +*.sagetex.scmd + +# scrwfile +*.wrt + +# sympy +*.sout +*.sympy +sympy-plots-for-*.tex/ + +# pdfcomment +*.upa +*.upb + +# pythontex +*.pytxcode +pythontex-files-*/ + +# thmtools +*.loe + +# TikZ & PGF +*.dpth +*.md5 +*.auxlock + +# todonotes +*.tdo + +# easy-todo +*.lod + +# xmpincl +*.xmpi + +# xindy +*.xdy + +# xypic precompiled matrices +*.xyc + +# endfloat +*.ttt +*.fff + +# Latexian +TSWLatexianTemp* + +## Editors: +# WinEdt +*.bak +*.sav + +# Texpad +.texpadtmp + +# LyX +*.lyx~ + +# Kile +*.backup + +# KBibTeX +*~[0-9]* + +# auto folder when using emacs and auctex +./auto/* +*.el + +# expex forward references with \gathertags +*-tags.tex + +# standalone packages +*.sta \ No newline at end of file diff --git a/cubic-configuration.html b/cubic-configuration.html new file mode 100644 index 0000000..ee32eb4 --- /dev/null +++ b/cubic-configuration.html @@ -0,0 +1,1349 @@ + + + + + + + +Cubic configuration for the Stewart Platform + + + + + + + + + + + + + + +
+

Cubic configuration for the Stewart Platform

+ + +

+The discovery of the Cubic configuration is done in. 1 +The specificity of the Cubic configuration is that each actuator is orthogonal with the others. +

+ +

+To generate and study the Cubic configuration, initializeCubicConfiguration is used (description in section 4). +

+ +
+

1 Questions we wish to answer with this analysis

+
+

+The goal is to study the benefits of using a cubic configuration: +

+
    +
  • Equal stiffness in all the degrees of freedom?
  • +
  • No coupling between the actuators?
  • +
  • Is the center of the cube an important point?
  • +
+
+
+ +
+

2 Configuration Analysis - Stiffness Matrix

+
+
+
+

2.1 Cubic Stewart platform centered with the cube center - Jacobian estimated at the cube center

+
+

+We create a cubic Stewart platform (figure 1) in such a way that the center of the cube (black dot) is located at the center of the Stewart platform (blue dot). +The Jacobian matrix is estimated at the location of the center of the cube. +

+ + +
+

3d-cubic-stewart-aligned.png +

+

Figure 1: Centered cubic configuration

+
+ +
+
opts = struct(...
+    'H_tot', 100, ... % Total height of the Hexapod [mm]
+    'L',     200/sqrt(3), ... % Size of the Cube [mm]
+    'H',     60, ... % Height between base joints and platform joints [mm]
+    'H0',    200/2-60/2 ... % Height between the corner of the cube and the plane containing the base joints [mm]
+    );
+stewart = initializeCubicConfiguration(opts);
+opts = struct(...
+    'Jd_pos', [0, 0, -50], ... % Position of the Jacobian for displacement estimation from the top of the mobile platform [mm]
+    'Jf_pos', [0, 0, -50]  ... % Position of the Jacobian for force location from the top of the mobile platform [mm]
+    );
+stewart = computeGeometricalProperties(stewart, opts);
+
+save('./mat/stewart.mat', 'stewart');
+
+
+ +
+
K = stewart.Jd'*stewart.Jd;
+
+
+ + + + +++ ++ ++ ++ ++ ++ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
21.9e-18-2.3e-171.8e-185.5e-17-1.5e-17
1.9e-1826.8e-18-6.1e-17-1.6e-184.8e-18
-2.3e-176.8e-182-6.7e-184.9e-185.3e-19
1.8e-18-6.1e-17-6.7e-180.0067-2.3e-20-6.1e-20
5.5e-17-1.6e-184.9e-18-2.3e-200.00671e-18
-1.5e-174.8e-185.3e-19-6.1e-201e-180.027
+
+
+ +
+

2.2 Cubic Stewart platform centered with the cube center - Jacobian not estimated at the cube center

+
+

+We create a cubic Stewart platform with center of the cube located at the center of the Stewart platform (figure 1). +The Jacobian matrix is not estimated at the location of the center of the cube. +

+ +
+
opts = struct(...
+    'H_tot', 100, ... % Total height of the Hexapod [mm]
+    'L',     200/sqrt(3), ... % Size of the Cube [mm]
+    'H',     60, ... % Height between base joints and platform joints [mm]
+    'H0',    200/2-60/2 ... % Height between the corner of the cube and the plane containing the base joints [mm]
+    );
+stewart = initializeCubicConfiguration(opts);
+opts = struct(...
+    'Jd_pos', [0, 0, 0], ... % Position of the Jacobian for displacement estimation from the top of the mobile platform [mm]
+    'Jf_pos', [0, 0, 0]  ... % Position of the Jacobian for force location from the top of the mobile platform [mm]
+    );
+stewart = computeGeometricalProperties(stewart, opts);
+
+
+ +
+
K = stewart.Jd'*stewart.Jd;
+
+
+ + + + +++ ++ ++ ++ ++ ++ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
21.9e-18-2.3e-171.5e-18-0.1-1.5e-17
1.9e-1826.8e-180.1-1.6e-184.8e-18
-2.3e-176.8e-182-5.1e-19-5.5e-185.3e-19
1.5e-180.1-5.1e-190.012-3e-193.1e-19
-0.1-1.6e-18-5.5e-18-3e-190.0121.9e-18
-1.5e-174.8e-185.3e-193.1e-191.9e-180.027
+
+
+ +
+

2.3 Cubic Stewart platform not centered with the cube center - Jacobian estimated at the cube center

+
+

+Here, the "center" of the Stewart platform is not at the cube center (figure 2). +The Jacobian is estimated at the cube center. +

+ + +
+

3d-cubic-stewart-misaligned.png +

+

Figure 2: Not centered cubic configuration

+
+ +

+The center of the cube is at \(z = 110\). +The Stewart platform is from \(z = H_0 = 75\) to \(z = H_0 + H_{tot} = 175\). +The center height of the Stewart platform is then at \(z = \frac{175-75}{2} = 50\). +The center of the cube from the top platform is at \(z = 110 - 175 = -65\). +

+ +
+
opts = struct(...
+    'H_tot', 100,         ... % Total height of the Hexapod [mm]
+    'L',     220/sqrt(3), ... % Size of the Cube [mm]
+    'H',     60,          ... % Height between base joints and platform joints [mm]
+    'H0',    75           ... % Height between the corner of the cube and the plane containing the base joints [mm]
+    );
+stewart = initializeCubicConfiguration(opts);
+opts = struct(...
+    'Jd_pos', [0, 0, -65], ... % Position of the Jacobian for displacement estimation from the top of the mobile platform [mm]
+    'Jf_pos', [0, 0, -65]  ... % Position of the Jacobian for force location from the top of the mobile platform [mm]
+    );
+stewart = computeGeometricalProperties(stewart, opts);
+
+
+ +
+
K = stewart.Jd'*stewart.Jd;
+
+
+ + + + +++ ++ ++ ++ ++ ++ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
2-1.8e-172.6e-173.3e-180.041.7e-19
-1.8e-1721.9e-16-0.042.2e-19-5.3e-19
2.6e-171.9e-162-8.9e-186.5e-19-5.8e-19
3.3e-18-0.04-8.9e-180.0089-9.3e-209.8e-20
0.042.2e-196.5e-19-9.3e-200.0089-2.4e-18
1.7e-19-5.3e-19-5.8e-199.8e-20-2.4e-180.032
+ +

+We obtain \(k_x = k_y = k_z\) and \(k_{\theta_x} = k_{\theta_y}\), but the Stiffness matrix is not diagonal. +

+
+
+ +
+

2.4 Cubic Stewart platform not centered with the cube center - Jacobian estimated at the Stewart platform center

+
+

+Here, the "center" of the Stewart platform is not at the cube center. +The Jacobian is estimated at the center of the Stewart platform. +

+ +

+The center of the cube is at \(z = 110\). +The Stewart platform is from \(z = H_0 = 75\) to \(z = H_0 + H_{tot} = 175\). +The center height of the Stewart platform is then at \(z = \frac{175-75}{2} = 50\). +The center of the cube from the top platform is at \(z = 110 - 175 = -65\). +

+ +
+
opts = struct(...
+    'H_tot', 100, ... % Total height of the Hexapod [mm]
+    'L',     220/sqrt(3), ... % Size of the Cube [mm]
+    'H',     60, ... % Height between base joints and platform joints [mm]
+    'H0',    75 ... % Height between the corner of the cube and the plane containing the base joints [mm]
+    );
+stewart = initializeCubicConfiguration(opts);
+opts = struct(...
+    'Jd_pos', [0, 0, -60], ... % Position of the Jacobian for displacement estimation from the top of the mobile platform [mm]
+    'Jf_pos', [0, 0, -60]  ... % Position of the Jacobian for force location from the top of the mobile platform [mm]
+    );
+stewart = computeGeometricalProperties(stewart, opts);
+
+
+ +
+
K = stewart.Jd'*stewart.Jd;
+
+
+ + + + +++ ++ ++ ++ ++ ++ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
2-1.8e-172.6e-17-5.7e-190.031.7e-19
-1.8e-1721.9e-16-0.032.2e-19-5.3e-19
2.6e-171.9e-162-1.5e-176.5e-19-5.8e-19
-5.7e-19-0.03-1.5e-170.00854.9e-201.7e-19
0.032.2e-196.5e-194.9e-200.0085-1.1e-18
1.7e-19-5.3e-19-5.8e-191.7e-19-1.1e-180.032
+ +

+We obtain \(k_x = k_y = k_z\) and \(k_{\theta_x} = k_{\theta_y}\), but the Stiffness matrix is not diagonal. +

+
+
+ +
+

2.5 Conclusion

+
+
+
    +
  • The cubic configuration permits to have \(k_x = k_y = k_z\) and \(k_{\theta\x} = k_{\theta_y}\)
  • +
  • The stiffness matrix \(K\) is diagonal for the cubic configuration if the Stewart platform and the cube are centered and the Jacobian is estimated at the cube center
  • +
+ +
+
+
+
+ +
+

3 Cubic size analysis

+
+

+We here study the effect of the size of the cube used for the Stewart configuration. +

+ +

+We fix the height of the Stewart platform, the center of the cube is at the center of the Stewart platform. +

+ +

+We only vary the size of the cube. +

+ +
+
H_cubes = 250:20:350;
+stewarts = {zeros(length(H_cubes), 1)};
+
+
+ +
+
for i = 1:length(H_cubes)
+  H_cube = H_cubes(i);
+  H_tot = 100;
+  H = 80;
+
+  opts = struct(...
+      'H_tot', H_tot, ... % Total height of the Hexapod [mm]
+      'L',     H_cube/sqrt(3), ... % Size of the Cube [mm]
+      'H',     H, ... % Height between base joints and platform joints [mm]
+      'H0',    H_cube/2-H/2 ... % Height between the corner of the cube and the plane containing the base joints [mm]
+      );
+  stewart = initializeCubicConfiguration(opts);
+
+  opts = struct(...
+      'Jd_pos', [0, 0, H_cube/2-opts.H0-opts.H_tot], ... % Position of the Jacobian for displacement estimation from the top of the mobile platform [mm]
+      'Jf_pos', [0, 0, H_cube/2-opts.H0-opts.H_tot]  ... % Position of the Jacobian for force location from the top of the mobile platform [mm]
+      );
+  stewart = computeGeometricalProperties(stewart, opts);
+  stewarts(i) = {stewart};
+end
+
+
+ + +

+The Stiffness matrix is computed for all generated Stewart platforms. +

+
+
Ks = zeros(6, 6, length(H_cube));
+for i = 1:length(H_cubes)
+  Ks(:, :, i) = stewarts{i}.Jd'*stewarts{i}.Jd;
+end
+
+
+ +

+The only elements of \(K\) that vary are \(k_{\theta_x} = k_{\theta_y}\) and \(k_{\theta_z}\). +

+ +

+Finally, we plot \(k_{\theta_x} = k_{\theta_y}\) and \(k_{\theta_z}\) +

+
+
figure;
+hold on;
+plot(H_cubes, squeeze(Ks(4, 4, :)), 'DisplayName', '$k_{\theta_x}$');
+plot(H_cubes, squeeze(Ks(6, 6, :)), 'DisplayName', '$k_{\theta_z}$');
+hold off;
+legend('location', 'northwest');
+xlabel('Cube Size [mm]'); ylabel('Rotational stiffnes [normalized]');
+
+
+ + +
+

stiffness_cube_size.png +

+

Figure 3: \(k_{\theta_x} = k_{\theta_y}\) and \(k_{\theta_z}\) function of the size of the cube

+
+ + +

+We observe that \(k_{\theta_x} = k_{\theta_y}\) and \(k_{\theta_z}\) increase linearly with the cube size. +

+ +
+

+In order to maximize the rotational stiffness of the Stewart platform, the size of the cube should be the highest possible. +In that case, the legs will the further separated. Size of the cube is then limited by allowed space. +

+ +
+
+
+ +
+

4 initializeCubicConfiguration

+
+

+ +

+
+ +
+

4.1 Function description

+
+
+
function [stewart] = initializeCubicConfiguration(opts_param)
+
+
+
+
+ +
+

4.2 Optional Parameters

+
+

+Default values for opts. +

+
+
opts = struct(...
+    'H_tot', 90,  ... % Total height of the Hexapod [mm]
+    'L',     110, ... % Size of the Cube [mm]
+    'H',     40,  ... % Height between base joints and platform joints [mm]
+    'H0',    75   ... % Height between the corner of the cube and the plane containing the base joints [mm]
+    );
+
+
+ +

+Populate opts with input parameters +

+
+
if exist('opts_param','var')
+    for opt = fieldnames(opts_param)'
+        opts.(opt{1}) = opts_param.(opt{1});
+    end
+end
+
+
+
+
+ +
+

4.3 Cube Creation

+
+
+
points = [0, 0, 0; ...
+          0, 0, 1; ...
+          0, 1, 0; ...
+          0, 1, 1; ...
+          1, 0, 0; ...
+          1, 0, 1; ...
+          1, 1, 0; ...
+          1, 1, 1];
+points = opts.L*points;
+
+
+ +

+We create the rotation matrix to rotate the cube +

+
+
sx = cross([1, 1, 1], [1 0 0]);
+sx = sx/norm(sx);
+
+sy = -cross(sx, [1, 1, 1]);
+sy = sy/norm(sy);
+
+sz = [1, 1, 1];
+sz = sz/norm(sz);
+
+R = [sx', sy', sz']';
+
+
+ +

+We use to rotation matrix to rotate the cube +

+
+
cube = zeros(size(points));
+for i = 1:size(points, 1)
+  cube(i, :) = R * points(i, :)';
+end
+
+
+
+
+ +
+

4.4 Vectors of each leg

+
+
+
leg_indices = [3, 4; ...
+               2, 4; ...
+               2, 6; ...
+               5, 6; ...
+               5, 7; ...
+               3, 7];
+
+
+ +

+Vectors are: +

+
+
legs = zeros(6, 3);
+legs_start = zeros(6, 3);
+
+for i = 1:6
+  legs(i, :) = cube(leg_indices(i, 2), :) - cube(leg_indices(i, 1), :);
+  legs_start(i, :) = cube(leg_indices(i, 1), :);
+end
+
+
+
+
+ +
+

4.5 Verification of Height of the Stewart Platform

+
+

+If the Stewart platform is not contained in the cube, throw an error. +

+ +
+
Hmax = cube(4, 3) - cube(2, 3);
+if opts.H0 < cube(2, 3)
+  error(sprintf('H0 is not high enought. Minimum H0 = %.1f', cube(2, 3)));
+else if opts.H0 + opts.H > cube(4, 3)
+  error(sprintf('H0+H is too high. Maximum H0+H = %.1f', cube(4, 3)));
+  error('H0+H is too high');
+end
+
+
+
+
+ +
+

4.6 Determinate the location of the joints

+
+

+We now determine the location of the joints on the fixed platform w.r.t the fixed frame \(\{A\}\). +\(\{A\}\) is fixed to the bottom of the base. +

+
+
Aa = zeros(6, 3);
+for i = 1:6
+  t = (opts.H0-legs_start(i, 3))/(legs(i, 3));
+  Aa(i, :) = legs_start(i, :) + t*legs(i, :);
+end
+
+
+ +

+And the location of the joints on the mobile platform with respect to \(\{A\}\). +

+
+
Ab = zeros(6, 3);
+for i = 1:6
+  t = (opts.H0+opts.H-legs_start(i, 3))/(legs(i, 3));
+  Ab(i, :) = legs_start(i, :) + t*legs(i, :);
+end
+
+
+ +

+And the location of the joints on the mobile platform with respect to \(\{B\}\). +

+
+
Bb = zeros(6, 3);
+Bb = Ab - (opts.H0 + opts.H_tot/2 + opts.H/2)*[0, 0, 1];
+
+
+ +
+
h = opts.H0 + opts.H/2 - opts.H_tot/2;
+Aa = Aa - h*[0, 0, 1];
+Ab = Ab - h*[0, 0, 1];
+
+
+
+
+ +
+

4.7 Returns Stewart Structure

+
+
+
  stewart = struct();
+  stewart.Aa = Aa;
+  stewart.Ab = Ab;
+  stewart.Bb = Bb;
+  stewart.H_tot = opts.H_tot;
+end
+
+
+
+
+
+ +
+

5 Tests

+
+
+
+

5.1 First attempt to parametrisation

+
+ +
+

stewart_bottom_plate.png +

+

Figure 4: Schematic of the bottom plates with all the parameters

+
+ +

+The goal is to choose \(\alpha\), \(\beta\), \(R_\text{leg, t}\) and \(R_\text{leg, b}\) in such a way that the configuration is cubic. +

+ + +

+The configuration is cubic if: +\[ \overrightarrow{a_i b_i} \cdot \overrightarrow{a_j b_j} = 0, \ \forall i, j = [1, \hdots, 6], i \ne j \] +

+ +

+Lets express \(a_i\), \(b_i\) and \(a_j\): +

+\begin{equation*} + a_1 = \begin{bmatrix}R_{\text{leg,b}} \cos(120 - \alpha) \\ R_{\text{leg,b}} \cos(120 - \alpha) \\ 0\end{bmatrix} ; \quad + a_2 = \begin{bmatrix}R_{\text{leg,b}} \cos(120 + \alpha) \\ R_{\text{leg,b}} \cos(120 + \alpha) \\ 0\end{bmatrix} ; \quad +\end{equation*} + +\begin{equation*} + b_1 = \begin{bmatrix}R_{\text{leg,t}} \cos(120 - \beta) \\ R_{\text{leg,t}} \cos(120 - \beta\\ H\end{bmatrix} ; \quad + b_2 = \begin{bmatrix}R_{\text{leg,t}} \cos(120 + \beta) \\ R_{\text{leg,t}} \cos(120 + \beta\\ H\end{bmatrix} ; \quad +\end{equation*} + +

+\[ \overrightarrow{a_1 b_1} = b_1 - a_1 = \begin{bmatrix}R_{\text{leg}} \cos(120 - \alpha) \\ R_{\text{leg}} \cos(120 - \alpha) \\ 0\end{bmatrix}\] +

+
+
+ +
+

5.2 Second attempt

+
+

+We start with the point of a cube in space: +

+\begin{align*} + [0, 0, 0] ; \ [0, 0, 1]; \ ... +\end{align*} + +

+We also want the cube to point upward: +\[ [1, 1, 1] \Rightarrow [0, 0, 1] \] +

+ +

+Then we have the direction of all the vectors expressed in the frame of the hexapod. +

+ +
+
points = [0, 0, 0; ...
+          0, 0, 1; ...
+          0, 1, 0; ...
+          0, 1, 1; ...
+          1, 0, 0; ...
+          1, 0, 1; ...
+          1, 1, 0; ...
+          1, 1, 1];
+
+
+ +
+
figure;
+plot3(points(:,1), points(:,2), points(:,3), 'ko')
+
+
+ +
+
sx = cross([1, 1, 1], [1 0 0]);
+sx = sx/norm(sx);
+
+sy = -cross(sx, [1, 1, 1]);
+sy = sy/norm(sy);
+
+sz = [1, 1, 1];
+sz = sz/norm(sz);
+
+R = [sx', sy', sz']';
+
+
+ +
+
cube = zeros(size(points));
+for i = 1:size(points, 1)
+  cube(i, :) = R * points(i, :)';
+end
+
+
+ +
+
figure;
+hold on;
+plot3(points(:,1), points(:,2), points(:,3), 'ko');
+plot3(cube(:,1), cube(:,2), cube(:,3), 'ro');
+hold off;
+
+
+ +

+Now we plot the legs of the hexapod. +

+
+
leg_indices = [3, 4; ...
+               2, 4; ...
+               2, 6; ...
+               5, 6; ...
+               5, 7; ...
+               3, 7]
+
+figure;
+hold on;
+for i = 1:6
+  plot3(cube(leg_indices(i, :),1), cube(leg_indices(i, :),2), cube(leg_indices(i, :),3), '-');
+end
+hold off;
+
+
+ +

+Vectors are: +

+
+
legs = zeros(6, 3);
+legs_start = zeros(6, 3);
+
+for i = 1:6
+  legs(i, :) = cube(leg_indices(i, 2), :) - cube(leg_indices(i, 1), :);
+  legs_start(i, :) = cube(leg_indices(i, 1), :)
+end
+
+
+ +

+We now have the orientation of each leg. +

+ +

+We here want to see if the position of the "slice" changes something. +

+ +

+Let's first estimate the maximum height of the Stewart platform. +

+
+
Hmax = cube(4, 3) - cube(2, 3);
+
+
+ +

+Let's then estimate the middle position of the platform +

+
+
Hmid = cube(8, 3)/2;
+
+
+
+
+ +
+

5.3 Generate the Stewart platform for a Cubic configuration

+
+

+First we defined the height of the Hexapod. +

+
+
H = Hmax/2;
+
+
+ +
+
Zs = 1.2*cube(2, 3); % Height of the fixed platform
+Ze = Zs + H; % Height of the mobile platform
+
+
+ +

+We now determine the location of the joints on the fixed platform. +

+
+
Aa = zeros(6, 3);
+for i = 1:6
+  t = (Zs-legs_start(i, 3))/(legs(i, 3));
+  Aa(i, :) = legs_start(i, :) + t*legs(i, :);
+end
+
+
+ +

+And the location of the joints on the mobile platform +

+
+
Ab = zeros(6, 3);
+for i = 1:6
+  t = (Ze-legs_start(i, 3))/(legs(i, 3));
+  Ab(i, :) = legs_start(i, :) + t*legs(i, :);
+end
+
+
+ +

+And we plot the legs. +

+
+
figure;
+hold on;
+for i = 1:6
+  plot3([Ab(i, 1),Aa(i, 1)], [Ab(i, 2),Aa(i, 2)], [Ab(i, 3),Aa(i, 3)], 'k-');
+end
+hold off;
+xlim([-1, 1]);
+ylim([-1, 1]);
+zlim([0, 2]);
+
+
+
+
+
+ +
    +
  1. Z.J. Geng, and L.S. Haynes, , Six Degree-Of-Freedom Active Vibration Control Using the Stewart Platforms, IEEE Transactions on Control Systems Technology, 2(1), pp. 45-53 (1994). http://dx.doi.org/10.1109/87.273110.
  2. +
+
+
+

Author: Thomas Dehaeze

+

Created: 2019-03-25 lun. 18:11

+

Validate

+
+ + diff --git a/cubic-configuration.org b/cubic-configuration.org new file mode 100644 index 0000000..2ac21cf --- /dev/null +++ b/cubic-configuration.org @@ -0,0 +1,607 @@ +#+TITLE: Cubic configuration for the Stewart Platform +:DRAWER: +#+STARTUP: overview + +#+HTML_HEAD: +#+HTML_HEAD: +#+HTML_HEAD: +#+HTML_HEAD: +#+HTML_HEAD: +#+HTML_HEAD: + +#+LATEX_CLASS: cleanreport +#+LaTeX_CLASS_OPTIONS: [tocnp, secbreak, minted] +#+LaTeX_HEADER: \usepackage{svg} +#+LaTeX_HEADER: \newcommand{\authorFirstName}{Thomas} +#+LaTeX_HEADER: \newcommand{\authorLastName}{Dehaeze} +#+LaTeX_HEADER: \newcommand{\authorEmail}{dehaeze.thomas@gmail.com} + +#+PROPERTY: header-args:matlab :session *MATLAB* +#+PROPERTY: header-args:matlab+ :comments org +#+PROPERTY: header-args:matlab+ :exports both +#+PROPERTY: header-args:matlab+ :eval no-export +#+PROPERTY: header-args:matlab+ :output-dir figs +#+PROPERTY: header-args:matlab+ :mkdirp yes +:END: + +#+begin_src matlab :results none :exports none :noweb yes + <> + addpath('src'); + addpath('library'); +#+end_src + +The discovery of the Cubic configuration is done in citenum:geng94_six_degree_of_freed_activ. +The specificity of the Cubic configuration is that each actuator is orthogonal with the others. + +To generate and study the Cubic configuration, =initializeCubicConfiguration= is used (description in section [[sec:initializeCubicConfiguration]]). + +* Questions we wish to answer with this analysis +The goal is to study the benefits of using a cubic configuration: +- Equal stiffness in all the degrees of freedom? +- No coupling between the actuators? +- Is the center of the cube an important point? + +* Configuration Analysis - Stiffness Matrix +** Cubic Stewart platform centered with the cube center - Jacobian estimated at the cube center +We create a cubic Stewart platform (figure [[fig:3d-cubic-stewart-aligned]]) in such a way that the center of the cube (black dot) is located at the center of the Stewart platform (blue dot). +The Jacobian matrix is estimated at the location of the center of the cube. + +#+name: fig:3d-cubic-stewart-aligned +#+caption: Centered cubic configuration +[[file:./figs/3d-cubic-stewart-aligned.png]] + +#+begin_src matlab :results silent + opts = struct(... + 'H_tot', 100, ... % Total height of the Hexapod [mm] + 'L', 200/sqrt(3), ... % Size of the Cube [mm] + 'H', 60, ... % Height between base joints and platform joints [mm] + 'H0', 200/2-60/2 ... % Height between the corner of the cube and the plane containing the base joints [mm] + ); + stewart = initializeCubicConfiguration(opts); + opts = struct(... + 'Jd_pos', [0, 0, -50], ... % Position of the Jacobian for displacement estimation from the top of the mobile platform [mm] + 'Jf_pos', [0, 0, -50] ... % Position of the Jacobian for force location from the top of the mobile platform [mm] + ); + stewart = computeGeometricalProperties(stewart, opts); + + save('./mat/stewart.mat', 'stewart'); +#+end_src + +#+begin_src matlab :results none :exports code + K = stewart.Jd'*stewart.Jd; +#+end_src + +#+begin_src matlab :results value table :exports results + data = K; + data2orgtable(data, {}, {}, ' %.2g '); +#+end_src + +#+RESULTS: +| 2 | 1.9e-18 | -2.3e-17 | 1.8e-18 | 5.5e-17 | -1.5e-17 | +| 1.9e-18 | 2 | 6.8e-18 | -6.1e-17 | -1.6e-18 | 4.8e-18 | +| -2.3e-17 | 6.8e-18 | 2 | -6.7e-18 | 4.9e-18 | 5.3e-19 | +| 1.8e-18 | -6.1e-17 | -6.7e-18 | 0.0067 | -2.3e-20 | -6.1e-20 | +| 5.5e-17 | -1.6e-18 | 4.9e-18 | -2.3e-20 | 0.0067 | 1e-18 | +| -1.5e-17 | 4.8e-18 | 5.3e-19 | -6.1e-20 | 1e-18 | 0.027 | + +** Cubic Stewart platform centered with the cube center - Jacobian not estimated at the cube center +We create a cubic Stewart platform with center of the cube located at the center of the Stewart platform (figure [[fig:3d-cubic-stewart-aligned]]). +The Jacobian matrix is not estimated at the location of the center of the cube. + +#+begin_src matlab :results silent + opts = struct(... + 'H_tot', 100, ... % Total height of the Hexapod [mm] + 'L', 200/sqrt(3), ... % Size of the Cube [mm] + 'H', 60, ... % Height between base joints and platform joints [mm] + 'H0', 200/2-60/2 ... % Height between the corner of the cube and the plane containing the base joints [mm] + ); + stewart = initializeCubicConfiguration(opts); + opts = struct(... + 'Jd_pos', [0, 0, 0], ... % Position of the Jacobian for displacement estimation from the top of the mobile platform [mm] + 'Jf_pos', [0, 0, 0] ... % Position of the Jacobian for force location from the top of the mobile platform [mm] + ); + stewart = computeGeometricalProperties(stewart, opts); +#+end_src + +#+begin_src matlab :results none :exports code + K = stewart.Jd'*stewart.Jd; +#+end_src + +#+begin_src matlab :results value table :exports results + data = K; + data2orgtable(data', {}, {}, ' %.2g '); +#+end_src + +#+RESULTS: +| 2 | 1.9e-18 | -2.3e-17 | 1.5e-18 | -0.1 | -1.5e-17 | +| 1.9e-18 | 2 | 6.8e-18 | 0.1 | -1.6e-18 | 4.8e-18 | +| -2.3e-17 | 6.8e-18 | 2 | -5.1e-19 | -5.5e-18 | 5.3e-19 | +| 1.5e-18 | 0.1 | -5.1e-19 | 0.012 | -3e-19 | 3.1e-19 | +| -0.1 | -1.6e-18 | -5.5e-18 | -3e-19 | 0.012 | 1.9e-18 | +| -1.5e-17 | 4.8e-18 | 5.3e-19 | 3.1e-19 | 1.9e-18 | 0.027 | + +** Cubic Stewart platform not centered with the cube center - Jacobian estimated at the cube center +Here, the "center" of the Stewart platform is not at the cube center (figure [[fig:3d-cubic-stewart-misaligned]]). +The Jacobian is estimated at the cube center. + +#+name: fig:3d-cubic-stewart-misaligned +#+caption: Not centered cubic configuration +[[file:./figs/3d-cubic-stewart-misaligned.png]] + +The center of the cube is at $z = 110$. +The Stewart platform is from $z = H_0 = 75$ to $z = H_0 + H_{tot} = 175$. +The center height of the Stewart platform is then at $z = \frac{175-75}{2} = 50$. +The center of the cube from the top platform is at $z = 110 - 175 = -65$. + +#+begin_src matlab :results silent + opts = struct(... + 'H_tot', 100, ... % Total height of the Hexapod [mm] + 'L', 220/sqrt(3), ... % Size of the Cube [mm] + 'H', 60, ... % Height between base joints and platform joints [mm] + 'H0', 75 ... % Height between the corner of the cube and the plane containing the base joints [mm] + ); + stewart = initializeCubicConfiguration(opts); + opts = struct(... + 'Jd_pos', [0, 0, -65], ... % Position of the Jacobian for displacement estimation from the top of the mobile platform [mm] + 'Jf_pos', [0, 0, -65] ... % Position of the Jacobian for force location from the top of the mobile platform [mm] + ); + stewart = computeGeometricalProperties(stewart, opts); +#+end_src + +#+begin_src matlab :results none :exports code + K = stewart.Jd'*stewart.Jd; +#+end_src + +#+begin_src matlab :results value table :exports results + data = K; + data2orgtable(data', {}, {}, ' %.2g '); +#+end_src + +#+RESULTS: +| 2 | -1.8e-17 | 2.6e-17 | 3.3e-18 | 0.04 | 1.7e-19 | +| -1.8e-17 | 2 | 1.9e-16 | -0.04 | 2.2e-19 | -5.3e-19 | +| 2.6e-17 | 1.9e-16 | 2 | -8.9e-18 | 6.5e-19 | -5.8e-19 | +| 3.3e-18 | -0.04 | -8.9e-18 | 0.0089 | -9.3e-20 | 9.8e-20 | +| 0.04 | 2.2e-19 | 6.5e-19 | -9.3e-20 | 0.0089 | -2.4e-18 | +| 1.7e-19 | -5.3e-19 | -5.8e-19 | 9.8e-20 | -2.4e-18 | 0.032 | + +We obtain $k_x = k_y = k_z$ and $k_{\theta_x} = k_{\theta_y}$, but the Stiffness matrix is not diagonal. + +** Cubic Stewart platform not centered with the cube center - Jacobian estimated at the Stewart platform center +Here, the "center" of the Stewart platform is not at the cube center. +The Jacobian is estimated at the center of the Stewart platform. + +The center of the cube is at $z = 110$. +The Stewart platform is from $z = H_0 = 75$ to $z = H_0 + H_{tot} = 175$. +The center height of the Stewart platform is then at $z = \frac{175-75}{2} = 50$. +The center of the cube from the top platform is at $z = 110 - 175 = -65$. + +#+begin_src matlab :results silent + opts = struct(... + 'H_tot', 100, ... % Total height of the Hexapod [mm] + 'L', 220/sqrt(3), ... % Size of the Cube [mm] + 'H', 60, ... % Height between base joints and platform joints [mm] + 'H0', 75 ... % Height between the corner of the cube and the plane containing the base joints [mm] + ); + stewart = initializeCubicConfiguration(opts); + opts = struct(... + 'Jd_pos', [0, 0, -60], ... % Position of the Jacobian for displacement estimation from the top of the mobile platform [mm] + 'Jf_pos', [0, 0, -60] ... % Position of the Jacobian for force location from the top of the mobile platform [mm] + ); + stewart = computeGeometricalProperties(stewart, opts); +#+end_src + +#+begin_src matlab :results none :exports code + K = stewart.Jd'*stewart.Jd; +#+end_src + +#+begin_src matlab :results value table :exports results + data = K; + data2orgtable(data', {}, {}, ' %.2g '); +#+end_src + +#+RESULTS: +| 2 | -1.8e-17 | 2.6e-17 | -5.7e-19 | 0.03 | 1.7e-19 | +| -1.8e-17 | 2 | 1.9e-16 | -0.03 | 2.2e-19 | -5.3e-19 | +| 2.6e-17 | 1.9e-16 | 2 | -1.5e-17 | 6.5e-19 | -5.8e-19 | +| -5.7e-19 | -0.03 | -1.5e-17 | 0.0085 | 4.9e-20 | 1.7e-19 | +| 0.03 | 2.2e-19 | 6.5e-19 | 4.9e-20 | 0.0085 | -1.1e-18 | +| 1.7e-19 | -5.3e-19 | -5.8e-19 | 1.7e-19 | -1.1e-18 | 0.032 | + +We obtain $k_x = k_y = k_z$ and $k_{\theta_x} = k_{\theta_y}$, but the Stiffness matrix is not diagonal. + +** Conclusion +#+begin_important + - The cubic configuration permits to have $k_x = k_y = k_z$ and $k_{\theta\x} = k_{\theta_y}$ + - The stiffness matrix $K$ is diagonal for the cubic configuration if the Stewart platform and the cube are centered *and* the Jacobian is estimated at the cube center +#+end_important + +* Cubic size analysis +We here study the effect of the size of the cube used for the Stewart configuration. + +We fix the height of the Stewart platform, the center of the cube is at the center of the Stewart platform. + +We only vary the size of the cube. + +#+begin_src matlab :results silent + H_cubes = 250:20:350; + stewarts = {zeros(length(H_cubes), 1)}; +#+end_src + +#+begin_src matlab :results silent + for i = 1:length(H_cubes) + H_cube = H_cubes(i); + H_tot = 100; + H = 80; + + opts = struct(... + 'H_tot', H_tot, ... % Total height of the Hexapod [mm] + 'L', H_cube/sqrt(3), ... % Size of the Cube [mm] + 'H', H, ... % Height between base joints and platform joints [mm] + 'H0', H_cube/2-H/2 ... % Height between the corner of the cube and the plane containing the base joints [mm] + ); + stewart = initializeCubicConfiguration(opts); + + opts = struct(... + 'Jd_pos', [0, 0, H_cube/2-opts.H0-opts.H_tot], ... % Position of the Jacobian for displacement estimation from the top of the mobile platform [mm] + 'Jf_pos', [0, 0, H_cube/2-opts.H0-opts.H_tot] ... % Position of the Jacobian for force location from the top of the mobile platform [mm] + ); + stewart = computeGeometricalProperties(stewart, opts); + stewarts(i) = {stewart}; + end +#+end_src + + +The Stiffness matrix is computed for all generated Stewart platforms. +#+begin_src matlab :results none :exports code + Ks = zeros(6, 6, length(H_cube)); + for i = 1:length(H_cubes) + Ks(:, :, i) = stewarts{i}.Jd'*stewarts{i}.Jd; + end +#+end_src + +The only elements of $K$ that vary are $k_{\theta_x} = k_{\theta_y}$ and $k_{\theta_z}$. + +Finally, we plot $k_{\theta_x} = k_{\theta_y}$ and $k_{\theta_z}$ +#+begin_src matlab :results none :exports code + figure; + hold on; + plot(H_cubes, squeeze(Ks(4, 4, :)), 'DisplayName', '$k_{\theta_x}$'); + plot(H_cubes, squeeze(Ks(6, 6, :)), 'DisplayName', '$k_{\theta_z}$'); + hold off; + legend('location', 'northwest'); + xlabel('Cube Size [mm]'); ylabel('Rotational stiffnes [normalized]'); +#+end_src + +#+NAME: fig:stiffness_cube_size +#+HEADER: :tangle no :exports results :results raw :noweb yes +#+begin_src matlab :var filepath="figs/stiffness_cube_size.pdf" :var figsize="normal-normal" :post pdf2svg(file=*this*, ext="png") + <> +#+end_src + +#+NAME: fig:stiffness_cube_size +#+CAPTION: $k_{\theta_x} = k_{\theta_y}$ and $k_{\theta_z}$ function of the size of the cube +#+RESULTS: fig:stiffness_cube_size +[[file:figs/stiffness_cube_size.png]] + + +We observe that $k_{\theta_x} = k_{\theta_y}$ and $k_{\theta_z}$ increase linearly with the cube size. + +#+begin_important + In order to maximize the rotational stiffness of the Stewart platform, the size of the cube should be the highest possible. + In that case, the legs will the further separated. Size of the cube is then limited by allowed space. +#+end_important + +* initializeCubicConfiguration + :PROPERTIES: + :HEADER-ARGS:matlab+: :exports code + :HEADER-ARGS:matlab+: :comments no + :HEADER-ARGS:matlab+: :eval no + :HEADER-ARGS:matlab+: :tangle src/initializeCubicConfiguration.m + :END: + <> + +** Function description +#+begin_src matlab + function [stewart] = initializeCubicConfiguration(opts_param) +#+end_src + +** Optional Parameters +Default values for opts. +#+begin_src matlab + opts = struct(... + 'H_tot', 90, ... % Total height of the Hexapod [mm] + 'L', 110, ... % Size of the Cube [mm] + 'H', 40, ... % Height between base joints and platform joints [mm] + 'H0', 75 ... % Height between the corner of the cube and the plane containing the base joints [mm] + ); +#+end_src + +Populate opts with input parameters +#+begin_src matlab + if exist('opts_param','var') + for opt = fieldnames(opts_param)' + opts.(opt{1}) = opts_param.(opt{1}); + end + end +#+end_src + +** Cube Creation +#+begin_src matlab :results none + points = [0, 0, 0; ... + 0, 0, 1; ... + 0, 1, 0; ... + 0, 1, 1; ... + 1, 0, 0; ... + 1, 0, 1; ... + 1, 1, 0; ... + 1, 1, 1]; + points = opts.L*points; +#+end_src + +We create the rotation matrix to rotate the cube +#+begin_src matlab :results none + sx = cross([1, 1, 1], [1 0 0]); + sx = sx/norm(sx); + + sy = -cross(sx, [1, 1, 1]); + sy = sy/norm(sy); + + sz = [1, 1, 1]; + sz = sz/norm(sz); + + R = [sx', sy', sz']'; +#+end_src + +We use to rotation matrix to rotate the cube +#+begin_src matlab :results none + cube = zeros(size(points)); + for i = 1:size(points, 1) + cube(i, :) = R * points(i, :)'; + end +#+end_src + +** Vectors of each leg +#+begin_src matlab :results none + leg_indices = [3, 4; ... + 2, 4; ... + 2, 6; ... + 5, 6; ... + 5, 7; ... + 3, 7]; +#+end_src + +Vectors are: +#+begin_src matlab :results none + legs = zeros(6, 3); + legs_start = zeros(6, 3); + + for i = 1:6 + legs(i, :) = cube(leg_indices(i, 2), :) - cube(leg_indices(i, 1), :); + legs_start(i, :) = cube(leg_indices(i, 1), :); + end +#+end_src + +** Verification of Height of the Stewart Platform +If the Stewart platform is not contained in the cube, throw an error. + +#+begin_src matlab :results none + Hmax = cube(4, 3) - cube(2, 3); + if opts.H0 < cube(2, 3) + error(sprintf('H0 is not high enought. Minimum H0 = %.1f', cube(2, 3))); + else if opts.H0 + opts.H > cube(4, 3) + error(sprintf('H0+H is too high. Maximum H0+H = %.1f', cube(4, 3))); + error('H0+H is too high'); + end +#+end_src + +** Determinate the location of the joints +We now determine the location of the joints on the fixed platform w.r.t the fixed frame $\{A\}$. +$\{A\}$ is fixed to the bottom of the base. +#+begin_src matlab :results none + Aa = zeros(6, 3); + for i = 1:6 + t = (opts.H0-legs_start(i, 3))/(legs(i, 3)); + Aa(i, :) = legs_start(i, :) + t*legs(i, :); + end +#+end_src + +And the location of the joints on the mobile platform with respect to $\{A\}$. +#+begin_src matlab :results none + Ab = zeros(6, 3); + for i = 1:6 + t = (opts.H0+opts.H-legs_start(i, 3))/(legs(i, 3)); + Ab(i, :) = legs_start(i, :) + t*legs(i, :); + end +#+end_src + +And the location of the joints on the mobile platform with respect to $\{B\}$. +#+begin_src matlab :results none + Bb = zeros(6, 3); + Bb = Ab - (opts.H0 + opts.H_tot/2 + opts.H/2)*[0, 0, 1]; +#+end_src + +#+begin_src matlab :results none + h = opts.H0 + opts.H/2 - opts.H_tot/2; + Aa = Aa - h*[0, 0, 1]; + Ab = Ab - h*[0, 0, 1]; +#+end_src + +** Returns Stewart Structure +#+begin_src matlab :results none + stewart = struct(); + stewart.Aa = Aa; + stewart.Ab = Ab; + stewart.Bb = Bb; + stewart.H_tot = opts.H_tot; +end +#+end_src + +* Tests +** First attempt to parametrisation +#+name: fig:stewart_bottom_plate +#+caption: Schematic of the bottom plates with all the parameters +[[file:./figs/stewart_bottom_plate.png]] + +The goal is to choose $\alpha$, $\beta$, $R_\text{leg, t}$ and $R_\text{leg, b}$ in such a way that the configuration is cubic. + + +The configuration is cubic if: +\[ \overrightarrow{a_i b_i} \cdot \overrightarrow{a_j b_j} = 0, \ \forall i, j = [1, \hdots, 6], i \ne j \] + +Lets express $a_i$, $b_i$ and $a_j$: +\begin{equation*} + a_1 = \begin{bmatrix}R_{\text{leg,b}} \cos(120 - \alpha) \\ R_{\text{leg,b}} \cos(120 - \alpha) \\ 0\end{bmatrix} ; \quad + a_2 = \begin{bmatrix}R_{\text{leg,b}} \cos(120 + \alpha) \\ R_{\text{leg,b}} \cos(120 + \alpha) \\ 0\end{bmatrix} ; \quad +\end{equation*} + +\begin{equation*} + b_1 = \begin{bmatrix}R_{\text{leg,t}} \cos(120 - \beta) \\ R_{\text{leg,t}} \cos(120 - \beta\\ H\end{bmatrix} ; \quad + b_2 = \begin{bmatrix}R_{\text{leg,t}} \cos(120 + \beta) \\ R_{\text{leg,t}} \cos(120 + \beta\\ H\end{bmatrix} ; \quad +\end{equation*} + +\[ \overrightarrow{a_1 b_1} = b_1 - a_1 = \begin{bmatrix}R_{\text{leg}} \cos(120 - \alpha) \\ R_{\text{leg}} \cos(120 - \alpha) \\ 0\end{bmatrix}\] + +** Second attempt +We start with the point of a cube in space: +\begin{align*} + [0, 0, 0] ; \ [0, 0, 1]; \ ... +\end{align*} + +We also want the cube to point upward: +\[ [1, 1, 1] \Rightarrow [0, 0, 1] \] + +Then we have the direction of all the vectors expressed in the frame of the hexapod. + +#+begin_src matlab :results none + points = [0, 0, 0; ... + 0, 0, 1; ... + 0, 1, 0; ... + 0, 1, 1; ... + 1, 0, 0; ... + 1, 0, 1; ... + 1, 1, 0; ... + 1, 1, 1]; +#+end_src + +#+begin_src matlab :results none + figure; + plot3(points(:,1), points(:,2), points(:,3), 'ko') +#+end_src + +#+begin_src matlab :results none + sx = cross([1, 1, 1], [1 0 0]); + sx = sx/norm(sx); + + sy = -cross(sx, [1, 1, 1]); + sy = sy/norm(sy); + + sz = [1, 1, 1]; + sz = sz/norm(sz); + + R = [sx', sy', sz']'; +#+end_src + +#+begin_src matlab :results none + cube = zeros(size(points)); + for i = 1:size(points, 1) + cube(i, :) = R * points(i, :)'; + end +#+end_src + +#+begin_src matlab :results none + figure; + hold on; + plot3(points(:,1), points(:,2), points(:,3), 'ko'); + plot3(cube(:,1), cube(:,2), cube(:,3), 'ro'); + hold off; +#+end_src + +Now we plot the legs of the hexapod. +#+begin_src matlab :results none + leg_indices = [3, 4; ... + 2, 4; ... + 2, 6; ... + 5, 6; ... + 5, 7; ... + 3, 7] + + figure; + hold on; + for i = 1:6 + plot3(cube(leg_indices(i, :),1), cube(leg_indices(i, :),2), cube(leg_indices(i, :),3), '-'); + end + hold off; +#+end_src + +Vectors are: +#+begin_src matlab :results none + legs = zeros(6, 3); + legs_start = zeros(6, 3); + + for i = 1:6 + legs(i, :) = cube(leg_indices(i, 2), :) - cube(leg_indices(i, 1), :); + legs_start(i, :) = cube(leg_indices(i, 1), :) + end +#+end_src + +We now have the orientation of each leg. + +We here want to see if the position of the "slice" changes something. + +Let's first estimate the maximum height of the Stewart platform. +#+begin_src matlab :results none + Hmax = cube(4, 3) - cube(2, 3); +#+end_src + +Let's then estimate the middle position of the platform +#+begin_src matlab :results none + Hmid = cube(8, 3)/2; +#+end_src + +** Generate the Stewart platform for a Cubic configuration + +First we defined the height of the Hexapod. +#+begin_src matlab :results none + H = Hmax/2; +#+end_src + +#+begin_src matlab :results none + Zs = 1.2*cube(2, 3); % Height of the fixed platform + Ze = Zs + H; % Height of the mobile platform +#+end_src + +We now determine the location of the joints on the fixed platform. +#+begin_src matlab :results none + Aa = zeros(6, 3); + for i = 1:6 + t = (Zs-legs_start(i, 3))/(legs(i, 3)); + Aa(i, :) = legs_start(i, :) + t*legs(i, :); + end +#+end_src + +And the location of the joints on the mobile platform +#+begin_src matlab :results none + Ab = zeros(6, 3); + for i = 1:6 + t = (Ze-legs_start(i, 3))/(legs(i, 3)); + Ab(i, :) = legs_start(i, :) + t*legs(i, :); + end +#+end_src + +And we plot the legs. +#+begin_src matlab :results none + figure; + hold on; + for i = 1:6 + plot3([Ab(i, 1),Aa(i, 1)], [Ab(i, 2),Aa(i, 2)], [Ab(i, 3),Aa(i, 3)], 'k-'); + end + hold off; + xlim([-1, 1]); + ylim([-1, 1]); + zlim([0, 2]); +#+end_src + +* Bibliography :ignore: +bibliographystyle:unsrt +bibliography:references.bib diff --git a/figs/3d-cubic-stewart-aligned.png b/figs/3d-cubic-stewart-aligned.png new file mode 100644 index 0000000000000000000000000000000000000000..f8d4d7b3c75a57dbe7c41b9e03c6cfbf810e1a6f GIT binary patch literal 22156 zcmZU*byQp36E=!NaDsbr_u>VL6qmM82sA)|;uLpxDc<5P1xoSa9-N{r?gTGVoZ@f~ z@9(>Jt-HQI5>`&mnZ0Mv?3rgjGa>4=rV<`D6*dwQ5}t~(!doOHArWDA8ZA`(!{k;kspPLGB z3C&g3F(Mg*sq+ppackYDukYV1{}M8k8j)`IUD-)jD&4ExdOy8W;j-sDj?55BD2D~S zRYaE&V*R#IM{hws;v$h#Hjw)uksU}L#E1M2jt$p_0JnYMbU+e$Xr#NM&x`103?*bF zZe~_7i0X7k=)reL=l~(<3M3F>MqagFI#*)+1}0!RtV9lIs-nTqfapNJ!pjk0B#AV8 z_?TkkF!=m=8`YokYEYu80s~>e=sf5yE)U07@O{wxz-c%>%x5CNgUb$hz#xPPB=J`L zW48weim;0Ccf6BFe_Wcc3D^vwR$LwMmCM%}YvU>tE%=_I50CUn?WDR4|6&UPUF=7c zZyw_VwSznYo6$7F08t9j95x>`%Cwmpg!vwpqfP=Ykz(YyLkSCn|Im<+jxaaVVBeu# zSxoHUvw6z69ZENNXhIE?xayu}@db=XZu-!G5<-1-V0beAZot-bmmf_dc+VHmyI|TD zl9GpW<8*t~hVvqcxiZ`as)w|E$(woNcULN{wY7?;hb=d72ZzU^ZFDG-` zL4(7;VJ(2*3|SYYUMu_9{dch7Zr)Ig5z+#*KXUwKjz0V(km=BI2Q*D2UqeoY=P_Rf z9VAe-P#@7S>UtjRpIL27Hb$*}sSZu33$=l?A;qA2Py9ojp@N~w?!OI-!M=BWR zoI>m3@o&rqFbQLP=moZ{Wdu&`W?CysRn1WpGcfEXVa4x?b_PxK6qEp~t-lQxbb7&z z%lN?9o!!9=wET_2eHX^?+i!aLfVVQg31*d5J7aYmL9=G*y>R^8lyPQMiR6jN@(hPT zK~X5SL5s#dzElM)T!^y){3djy{S_>*>vnz}y$=sWNl<&Iu9BE)wCH)#Mcvp!3? z0$-QR_Ixuvo=!g62Zqo=>;)zQt}oVq(KZ=jf%aSsp$XN3hR`thFe()_GqM)PF{{*#TFxmCDudWFN<+p$@A85CxOh`up+fFoR98GxRq znrpi)@?^O|@iCUC%PPR-Wh7UdE)l^uP}IPDI5Ir%N`Mw@%nO)bUIy_3K@wJg{}VKL z1def@NQ9!@(R}+vKe=%dkXxY!H~{0D4R7Kr({LIs@;tJuRNh!Z#u#v3Nq2$}&99iF z4{uLTc25ju;@vpH2rpF5!BCX*w_-nXxUe#2euyJq&otF(PH&OOO;wq&u;ItQR{oKr zP}Oax`SL*z+V-j?OD^(8m|Fvp_P)*n#hD&qy&xK27K-qjd10u^pdgL2?}Enk63Xl( zoWW-Oh_=~#TTZ`g$r-Bri`p~#F2hM|_OyueY$g4Iz_c1JKhF<;|7jJ^M58kyfe@+=RR1I{(4zXI3I^l3c z?(+H7!04pD`}LypI|okUZP+9in$+N_-$6so3CfYE7hS}d%B2G9mJ?<0n5@ZB?I$c& zcsZK)A4?vELo&^w9`J?r-zesM^N@o>%sWa?p4~J$ou^$LVKsd zPT5+=aVlqk4`jSzaEq{zFkm3E?oEENIY|lZGc*X@YX7Yj#s>xkp=Nzy?%$zQvjgx1 z3;V+MGavwqf3ol6hjKtAghM-Q`5oD{TgZ-C`KP-qqQny8fB_a) zoHS1nR~E`dg2CV%4@L+eUWdtjc!rS{b_ysur9op9rzlI5J}^7KSoV4y%ozWMPIr+X zw~013cGjTI9p#khn`9dyIAt#6v`$bD+7lSd9CY5R9Hg?UrD2DBCkXZ+h)pr zrnbV$U22XK2+LoF5WG;~XABu!y7gs}720smQ(Plv6jDA1-v!ArIH$>;7)&+;8EIba zY4Zn{QUikggTM)4gHco|r_~D5zZO7)tFk~eQijNV2x_YQ;7}zOr55Rq;D*ab^)Slx zB`d$o(K_4SeoL21NDF5H>qfl6I!EAdc&)yo42_>Qo{V;c#xX-Lo_13EiN6GaVk*^ml?4Kg;^B`F`dzfq_ zS=9c>|MsjJ5QZ59vmemTiuDm*Ve){pibU>PpW|y|sRj}Q=3j_qgq3$cQ#b?iZ8bGT zmE#9eC8D-JkBM@L??}MUPdEU>vKH9?osT`O`|)KaM_I5&1Bjpu)=@F!vpXOOYanM0 z>Px)wuwvaZQ86em`!Cau+4PIhz(BxE#p933rM*Ci>;@MP)v4QAPQhP z;n}Q-Ja<;agg*cMaG-&?2R&%_Dw4*eqD$Xr0u7=-mB+3NHRc_o!3 z8w*!FQ*Il7z3%8Q7!IR~cAfCf+1@#gJRk);#EV>3&`BG}(!VW| zkOESxPmLh8K}X2rC^$iEf!~1`$x_)yGJ9Wlu$%&5Q!8SVb|jK8-)+~tx9eb@XNd#J z6sOjKa*Ux?I3_C4f_mktCL>m>d7^^fV%R~U(`f%)97^$VB5 zX68*)cL;tl=0b}7JB67I-vPOWiy5pd)WF~rl?$Mu-}u7ZfZsrPNP%(lE{GF4pZq

ngMxkv!{%RYe{OJXyFMPpEw4(}A z>$Wim=E2BNnTsL?Y}+T8xA5vo3=d#lJ=AOxFavXWg94yX5nnY;(|4j=p4UyzAz-O| zWeDvv?kKg;-zAi*)(7`DhGC+&Kq|gtqhfv4Z4>Y$HT^7Txy}&f)F9bq-nd7V8Q%dt zoCDAVlPa z^hfUd1E@}rf?{X|q{{a?tu{IYYr#EPjN8OK<7v?dpLTUIkb3;-X1!D1jNGRS6RHJ*>k@L- zH%DcNJ}0m$%#J}alTAip_{XmhTNq#Kss9vJTclJ^RTy>;q5rqw72B>6GMo?X3xrO~ zU#kJ=_%vv76b|Ag%woc!2Zh@C;4(3}Ta_+D1wdkBbzbdF4}JMC4LYnc6Q`nnxy?!- zV}NJpHSYXH5#GVR?{Iv%GDA$95vD6zzedl_;AJhHF7I?*!q+ly1$>ND9o7o<0!E2N zjZj^YEe3Ms%AB90ln}eV=Ph_7s=XefT^88BlB$8LoArlAxE2E2n+|CVSrgUBwqK;+ zWOZ;JzJ*p>uVz5&DnP(Y(V?)(I6J-{vD1lnuB?A~H*WGuzY@o`s!8I~_fyqlM?wKF zL#Krg$0Xamim19~bXon71aXy{Ijtr>R9UNg$jS5}HoqH%;&FNJ1rZq>Co5p_4ES7q z_f}L*b27s`dvxa6Hy-E*>B%876Y)~yGCYg^&3c~)aknw8nsdDCbm_rzm1yl0t#lVb zN9(<+9^avuC>hZ5)|9vhtY;-x+(Xc%dyyl$D$|E7=P@k7uN>CjtIsj4M$ZGYjBk~b zetd-`-soCG$T%?QYJGvyf?5WWF!UvD(o5yZ4He!I^UWDZ%dwVT+ekMNYk09+=}$@V znUg1gQ!KvNyB``{-&o|oQi&!c&=%WW4quq!jIT*u&%9T-Uwx4xj6 z_UC)Clq7X@O#q4z!Rq^wa+RatnwBW%91}Fu5E<&X_S;JrqLjWwhn5bkS2I_u3~;T$ zx638s{iIstF010CKUw&->9~T82FwobFgmU!YUYyN!q&4QHe5A6LZf(ke@H02j6gJ% z3X88E!Y?1_czG^OX^1sQl@3^5NNe1;34sSFlUw5FynT&uugw)5nNmX|ca>vk$$5F) zP5ykYi>-h&`uY!#L}~4_4y)iJJJ*-=j=V zca4X-*eiU^E^gdH?U}zzSCq@%QpjVDj&Vqf939(=LtKa7Z(kDz@W0mJUQ{{fyt6^g zZ6+B^$CpTFuh54JThDxCNK4fIz@@$8k9uH;W>(BXo@X27wNvElzx)x?Got$W{w(S}OGSej(ev|( z>@GAFXGZOG!6O*AfJN-1)j07z>9}iwtt`mDYp3gxDf}-afO3YrZ=qm8tQc%rB>L<9DBf7Rmnx8Ay<$>euD*P{Ts;%brmv*!0P=4jzW6hhb(_#|e3 zvzu1Nzp;Nq#aJ(OiaAADhLhvT@W3t6o-+uvJo zKH{ZWM)mp6v~}xs+lV?%bKpTS2k`qYWqQDoKfR^nO5q&r12tc&w`KY1gAK8`yKiv* zG#r0aRr5pdly9bL5~3d(Rj2Vi6Gf9x&U)j}jP76MQ=8pvahNaW{(R<tz%TomYq^raX56j*QrUn9|(zj0$Jfn!CqWt;AN8dDkk~J?neg*zbQ?F5Q6>sx>5`u*88ctM;uKNoeX-GWDGsKLUt{L>iIDs8pfTk+zLpW! z4$v4&-<*UYLs!|31wGXkB;kn^4T$L_g^JQ|i(j$SGjG*=&oGMrk;dlFeJ~+P)zzG> z`=Ma~*3)jfX_mvrevHz<-8bdz;>Bzw*-u`p`7R$1WE6TQ;o|;nvVT1$4#ailwD>rI zuhQo3m!!QKc|U}758+swZ%i%QaB}mw&3O&2iNzo*ZY=(8s;SW-(RmHkZUdYx4U0}| z<5>0C_k~M?ipkK>WWzcoZIfuaTtiGgvaYBH&>ayBe}JEGI3P%hzG^+bCGwU;*C-)Y zxZQDP2YD`-9Gl$E^d;z0_)*jfI^vR|cX-EPkdS-rhDz0ehbM znih>uliSj9HTyN({T}28v|%g`VMW_rxGB1apKOP4q|&@@8YE_|hYDX!owFDJYQvz3 ztS64%fQ4;KKi`5>*+U!28c<+^es@qZlEgsJq$!%@wG;&$3Lz+pICjqA4W zox$E~X?L*>P{s|v8T?=041U1^7g8fy>KFy_^DT+76AJhB%y$sJRz-${YUawB%2@Gj zg&10Ncjh>8Ts34Q{|^)v8%iT>)jtl8J{pBioYc^erhH9inHVy1GL$@eNfW^F+T)Nd z8nZ@CvaJw+pibt*aqk09!euvMZIA@|6sxzcS=j33S;}476qA^?m-bz!>l)|q0k71R|U=QH-#2ca>(m<=) zG{3A*H8TaF@>>v14mem_J_$WXd7wZ3h#*$RB}ht~uxV~89=oTSlVJ`kBfIkm5{>fm z_#XNNaE}+ggk3caV}AsrSo}2Wg5YdP+=U$zcK*8oy%Y{w4x~SwnO$uf#Ti? z;f(R!Cuq%%N@K0!ZN~_7 z?aefWXI;ID6YDV>1W7s;`Y62+-8Q#rv)xy>XJ_V~ZqnJX;jQH85@4#fVCDz!zxZS< zMa^cAGxe3i?AIGUfz4j+D_1XJ;dkU`CuLf7j^p30!yGvgs5pyvesfA|do3l{-*9-h=v@1dgI*k^; z^44Sh5Rsuw6@AX5$Sfjy+4NZr7z0+I`3a zDo}7rLeqjVq+iDgelqL4u4f#b+Mg|Om`I@*Xc)UQ-gi~+lR?6T&FR?Qr7&_&K^CGP zNUz^pu011Kx-=qWeSt25G zKQPyHemdQ1|**Vm|4<4!q8d)ws1%nMRehNd%=_peLrm}b$>yuU$C!>;b3<`zBE zF)&7cz{N$IVdGiFSVF%Ov!3UGBOwx5|C%ghiPl)?EL<3k?m{fp?ojZ13o-u(K>G2R zom3!l>qGb^$P|s3;buWFcFy6~xb|%*Z$3Xn*L01fwTY0+%}(;v<2w& z@|)gJx;`HEp4g?JeSg$hDU4N;dUdFU3{;3>HLdO8FNl zH*^S1i2L8i6=BVx{X2qRz$p%9LMBr)ACmD7J_iu!Al) z>c3B1{m2Z8*Z@nS&CPEXa`L!c!4Ndww9j)EzEdO?v^ttKI^S+;nn2wT3B>4i+FE`=||MzMMynlDg*}v%i00n!eoNhwRNSJd532k&znl?+(4?6&I4W8XqwKG1Q_nVwca*79{4gH= z+`LAUGv_AFOu=ZT@s4mjuEw*SGH(E&MO~NEIH*HmW&qL086c^XG?hL+L0ifUArDvgUBgEn-X&<=n5YWHjr?RBI1ocHid5~`p2wg zd8=`CJ)}^6skA;lQE$4rjgh$2ZKx>S>>7@~JlUl~+f@xa382SpOW9>`*o&ml4l)Km z$J9hy^1Kjq3h5w!%p@Xze>>K3I~PVLi$4!W9D3UhUq*TZP$n%$C{X(u3U6!8p`fZa z&qmh7>JO)_E)rKN!b-0lszG9F6-a@==Gh=+_^@0Uy5o5&j}$>uvOL>4rX=CGafBI9 zQ?i)9cyj%g0!~iP&47u1s2Le-)O4t|g|;&0|Lp~68}l2OY3TWFoW;x?IPCJqfGhB9 zL-;%S=MTy1$j9%3EqV{(_|LwCgKGd>^O?itA;^gno`dGvllFx_OQGcRD2?N}Nbuo} z$$7W1nSdt$m(u#yV569e+`RJWsL;;YvPwVt*;0`Bj|YWidyZk-zwR-e44bE<;2L?k z%e5Nte$iO?K}Ht^TYW@v?8h#lO!=_-jY-3U*`r%GZ+nCNjccw+(NwXp(w#1hm`171 z&#o+BmDol%n`4_ErG9tHPfprL#;cV*m)gb>)Qy<-_sp*FM$)T?fwfNj%i~{L^)>MV ztQSGtRJ$SdQrhE8qf(}kh!*)w*Z8LMf#+*g4cN# zFzqPl}?r{ z_plx0Rkiz*S1rWC0l4@6Q(3WEd-2bx?pf#f!hIhEOdqtg13s+49D6Qh4|?;`8Mf3W z0|iQD9{#iwwqgbfJ3t5X5`(Ix7hjM0-?t)lmg@b{2@de}G+A50rJ-_eyr(xBq_L~? zK}nkeUC^}R#|w2=$!_unmpbo}>u4X}PkE%_f9X=k;c!gtrT@|G{(1Z6Rfp=xd+_Nm zCx*0Pxefu$H1J#7qtEX2_UE|Aath?l!LaJRoA^%w`6;E;rv5Z(KD(KltA`=ph+Bf!xAQekEW!+zgX2LV@^mEra@_wKr_Q3Y6z0B3 zhR4fq5H0C>nC;Rz8+Ky)&nfSfgrtL={T&du##+lA8=*P!%YN@nuSMe?d27e+xXs;m zuOOJoflOH5A#9VhVyUpa)2z=k9i9YN6ixVP*(cMth|-;ktJQW{CaZZNw4+_Qk1u~Q zusCT~?u`8`1?P%XkvcE_x>r2-kXv2JzO`3Rp>0Nxe*KWV@cxL+amxyd> zWY;2({7XQw#;axJvt06c%v>vZOt8u~x&Op-{wF|OHg)bsCzMXxkuDR<0`=RY>%GYz zkKz$p43UF2(URqXx*rt~IaWknSFqHUh8?L!hitRc zcE*@R(13v5&DD{ekx0@tfo|9mlS%!=vCjvC`NXx$mgUd?ZZtR+!8bE2=EAjd0b2BC z@@Dl6uJlg_hH6Xn@aIQyBm1txZ0>n!RO_c0HpY}Z6%Bj++28(&1{{`dyY^a1C5j)s zxTaLUFY(2p=k17Pb7)C~G84{7k+@=q)<4wej|4bk$~{j8={+W_S+1ymMVjF?BjXJj6f^iMy62uF7FG0sTgDIl7Tak?|m|p`v*1{H$H6+;qwORr5t= zb6%+ZK&O()j@%uE&R+v$?ruS1Hj%dFuxZb+O15&X{VDmi{dAgtk^Y8wkz7{1Z64!z z3mzk!7&P^r$& zLo&up>6=}ZK;TRSgomP7!>m?SRTBEN_qu51>j&A!uW?-imGt&vlcWFIy6)(c25>Lnp5qZ1R!=Q`j0N^&S&K7N1)nPOQ zIXpxoNmm8xc?R;vni+^1cI2owoEXA%dL>y=INr64)H4%5G~adr+g@Tbabp%vPDWey z)UF{@ca066defQd;~y*#20$}Rl1s;G>GCu`T5}I&$j6?!CYc-509^gmu)Gq)-ONhO zinTejAD?+Avf-ul+L3WE&t1y;MAyO92m1xLOx+_y^6d6>6VF$8laGN*g=klYB(I(~)uo2{&#;qNb}8ZAwV7mg1mXF0j$2T!q1d`B|+2=goJ z97h3cIrs5+`O)HPxAXhtZt$`|Io^sBUgitbeMt?vQ@R6`diF%!N$(>rODA^=ye|nT{kKPPX#~>h-QB)K_=52gJ#&Q# zzG-MvN`#4c<^o(!PIb2rsG%PcR&deVcNa|(8AGJ&+4ygUqKsb#LSMz>_bc>>dBt*6 ztJWXwS9YF@Qd!}4mpVCF-6QUx+=tp~aNQ2>;QVk8`~*I#5#?X-!DicAg{uUp3W9*% zFBRy=Fyt|m@5+zT`!QDm#@5lOK-Y#WP*5e*AW!L?&N#rl#p;zM~r zYD3CGJNWc?yFDXK*#1=TVu@Be0_wTbb&0&^ab-mZNW9iCKhmymhacl?4CbF04dBbW z{B)g-ArNzg9WfB4n9H~0S=gO`UIJ8rgad)fu9cxb)tS<)uRK1dSiJ}4^;BOp7(lka z)0zN(y&lzMs)FYLrOHakrCqArD*`WEU1o~8r1|lLrWu*e#A}N~<9=qLEMfbKZ=NkP^ZX}8R|Le>*lQl>6J#~Nw}qW0gcl0SA2 z0o*5ZTF})shRqv$sNE{cN>bgAMC&ter~7F6u8gdwLNZXdCepkA!6?*BpN4fuO!3;m z5Ohp{=nPu5+yg0`N2{`xiT50j-a{VIUXT}$Eq52MN)7wpccff&tCG!%g`<>FIDU|c z6Wee{8am9Vq<*Ok!HdL!U8Rc(S#7>72%~rUTVz}P;N&xey{-9FHWfVnvx8(Cln6IP z)LflvIwjKLO(6vgO&ymNllEVn-I$DWQD`a~EJRCV`bk-a7Eu8UV_>v#YLmZe;^#Et zSnbzjjov%zAiA~GwwZCt{|sf5-sJ9J zoaNrWl}hQoNq{2q@EGOc%%ZYSKe$<4=EV=)8aQhH%CTR7uVg&M^2$Ja+bBkRr+Yxg zVfbpR_fk8>SkysmCQdWCV0i>60fry?7|b`qze-y*)mUEj?Z{}{-(_vU#W~&RAE=(F z)>qIS+80^b?JFgV56fbw2aA+qdkWsP=U}89uO$5q?N?IfhoxdPRHxB?sk_9+n)<#Q zT+5{u?a$8dTI{?MCU9)!#%^)>L*#Ovt$euos;5o1dTbidHaO3)^H;#-t>^puy5=2B ztwE0QBAj&bwZBtmIUf9R*@Vt3t!dIHiNE~Rvt2m)IW+a{ZH(9d{iH8G+$dslTKXb4 z=0iNmCPms2|HHvdeNU2f;4Z{CZZ*N1eoP8^crby-Z{!?QtDTZE#$}p%Z{TUYexJOk zxtPva9(%OX^LyuL`_Ea`HxDUYewPWZ(w%!bf~;V^h(j~IS*_C2?Qmz=i4``kQ-b-2{0g*E@)>%5an{L%Jp zGC8d}G5K$%j;;povP+33bztyRRd2`3cYlMEw!->kdTX@hd2j7Fxp-BjSX;~_+HJ`yx|2Bm2g0AoAOTV|VUYvzR1QS2F?#PVrVGq4o6YB@H@i+Qj);2G&y?@W+(L<+o zX$OigMPbXcyB-jF)9K^GJ9_8MO{Qun$xW}Ze!6!685wSm6Zuzb49cw2MO1dq8|r>_ ztY!j-!tbXI31@T>Yf%Z~davJ!^J~}{V}y&Aa*T;RMw?4-85$8Jf3y`^+dC54TY5j= zQ2ZH_kIx?QC6(B9Ncmo)>!KMlxd-yanEG4+J^nVFaLBUczOW+qV@kpmyz4T~#%&MMCAwbq|`FAKuoR^thKe+{Zl zZs%xQ2=+b8S5T9= zc9lsG*(#!%1ri5!zSZ|a%`RZ^^cU!N?H3I<*P4AN}3`Z#de5k>y?c$12B z@l)x;0mz$viHkijWy}=uhJZ<-<+iB!?x$3@L9HumNZgI~SZ?D9ZC0>8#h%E8-cj&0 z&Z_y`F0}xS%BiHYS#HsAFyCu~Jr9@$4!}&LvfSUwB>Xdx;<7c^85n(maV6GqK#5St z`eUgkcO>S3_44NC}O#zWvEVgR9-x`t3V?ZSU20CJ>J-bN3-i1{u9<(eKuK< zv@DP^G>&ifYF=WjZ5LOI`~lGAJAQeEq2; z{Bex`JLfPvw`Sd=1M(N?qkLDRP}&D9#|8o0J0-V_n{Vv-c~@#;4^`FWsI4Rr?6J3Z zdjvIOD<#=4As#08rq~jE+h?Ncg+mVKOqHc?zVvE`zvjCP$1HDpGpXL$>*{s9ls(B)OwN?O?!>-=R`cDUE&@&9ov6I% zH-v4&s@1`HB`Sl%{vGIcjDywoFaFmhqyb5FG2=78`6}ad;bO?aE&-y5tv6eLw*W@C zM=nPlB_VEo%KAGv828-!qd#i28vhRlD191s!dw$$GyBV4%_P8j;(zI8Q^xk|OlHeE zlZ0B^KKx7`vF*9Fz7G9v?T5mRI`&QP)_}mb=BKGmB!_wJ#JL5^fwzVF-uP5AK}f}_ z*9S#~r)Fv@;0t$!~o%BYjx$bW~EOGnZF z9AY0XM0mw+)XaMHiRGD=$F_!_NBE7ELiXx;Ff{No!&l+IjwO!2 z-hA$y{Zh1MyvQlRog}NgJsUlUg8yM5X9Xx8k<&n6bDg`J-FgoYwJON%cQeP#G=z z;Tu_#*|YgJZybAMT);~KTj~TQR+FS*P@KiS!hNwP5mTCPGs~RQdTlwS)5Nn-yic~_ z#dX|XW%Adx9AHOkXCPUh_b?hngx-fvL##hyq@cEcNy$c6|HK#Ztk#>u5$jl@>$b== zi6M+5IwN`XkBbRUy4C6ZHm0g*+g>Ps`7yOi8 z$=eIu5WubQ_}$POZ$g>Ev*ffePT}>J?7*^>!_~G+07Bj8)ETj#g_OwXdq&x>s{*M| zuhZt42?!pa$(2_*GHp4RPIOb_{L}I%h_2KPwx;l%GH|ztbXDRJN4+E1>ItCjP56E0 zScumMezio8Xc9F`3tYqEm+GR3@k*6slYy5Jyc6^qw9VgQwdX`bIU}9&J&|dUpVlvNrG#YF-~YJ%paV0vz%StfvA7F2W|>vmdyk z<#bZz=EVs4^Jv!5%yO}jHB&?^^0&naN7uL`cNq54ei127${hY=VRB!#yW}F;PS8TBR+ELigieFIgmRaczIgrAX%dsi;k*hxF-ZDMYuuG40O?0kO0Yty zKfG>pHYT6x@UQyc*`cTU+;Xy&{B`p^*xPR`|9wDo7h;~Cc*EY?VeuVX>D5yuqvdLZ z#&ABeA{V2LqDq*yJ$~FBMVcjTlmg)xobn^4m`BkoARg8mvmZGB*IT43Fo|H`5pm1s zR@k2vx{=lEw_{)8J3#Nq*hi8wvZXd_q%ynmCgvGvQd z(6meS<}w18!rwQ0Nd7v-kmRT_y_Ky*WMf&{%Y&NsXX@urbXnd*g0q@pblFRfz&$d% z!d>Bt^B4x@;6pI^ZZjGsg1_jXeaaoyO19cco=bj#^F&vCuBI}^b8I!G2y#<|{WU%@ zeGjx!`RQtFrfSZbj;2$zMm8FKLnN;*D{sZg1xX#(r)ON3Kz&BoZd|jP^Y(c#*TzE+J%*2o=j2-6T zO}&CQCQ`F(L3R)bl1Ekp#+Az*9|c}V!woa`eSphiFKpp6mr?Y(J$t@(9a@1Nc;r!(DkcQDHyYP;@I17@%L zX^7+v0vhiG*el3wXfQGx&c`}xyTN2t+C;@v;q+2|=j1WaNALo?WqJl%#Ku98Z_FYG z#6EVtI}4tdIifViN9!ql+5v})(NXDqu+jKxbh^3Az#@nPrTqs`eT|0r?S`IqerWPf zirFr2HzoB(k#Gl5xevHA{}?H{4{6H{Bb~_JQW~z{E6vbpgr&0GKT-i)VO}$4f2v{1 z&xxV>4BbVXvQqWzTd8X8&-RfDf5^dQ?cq=*fC}RhQf;A2`;(X^HR*p|*q^Jw`~xS| z`EIl|-OJ<`Sn%T*3&c_q{deDzx3iM)7vaYK`l<|F^5A)K;I|OSRVXs34=?!(-k4^T zGR;e>=h_(PzwfcZ7h+ukE&asf`^UD8p)wx+8*)UslzsGivXJ7t8l0y~_?6gsSJMtS zX6uS9M=$^B%$X6jf#01b$&b4t$**;%zwBoFPn{}L{ieBO;Y-7JCqoMI8Hb>9%jSR}FkA`g4Tbb3LuYprxtc-w^u7ig89f(c3VBp^{97@y~@5^{-Q(lYqzLnYb ztRJ97%RWZe$k8lft}aSmgge=m#=ax0&va5ZhWDI`#2E&f3v{#wO3H;M>(_-f@uK>p zBo*rikXMWFR?`2G}3n0!YBG-!6re=s_$#?=gX z5_Iix%4(pJx42n@E-Gri{PeJUmZ_;RxSOEEOV|?$8{zONQbGv{;Z=oMlw_<{QHoTR z)!l6xqaRf>T=Ud}+J8ybiwPQZ1Ac5)jJuJP{K57tFEsg?!7*#cZEBb|{gT3>-yQK+a-rwEOL z$d}#7L?OXAyK5=8cfmjuWI?Db9S-xr{Udo8ikJs$kjMOuOPL7>BKU>!)zOxm@9A-X4ad^71baW zy}~X8eKmyw7Pxc2;U+IxQsm)e#m_lf#$KA%Qw!KHx&|aS0T!(E!A${)Sum&M%WBgH zo-x-alRM3(Pq*-Ygyrppm0_Mz0M)D4EtUqej5i6+x(99aSCSI)N zt3Y0?(I=b<+su~V*l!?Y#+8|ZUuvO`u~JZOyiqChI!9f>@D441kDc|>Vstin5qb~R zD+oJ6pZNY>VeR&jVD(XJ|C8;`mvcHQlDhqru@8a8eO7|4jjqM+mtW3rpz#P~M8z&H z&AgyVlf6LKFKMQbZRs=i2Jf+)pLjs4Oq1o3eesACe$Ok4R>CS6L#?KM70$$V7TybF zg~{?x66H(D7P>3+<7aLI%t>__aPDWzX};8f_ipj-NZQ-9F*SuX4{3S&i9O#cq!Z*C zF~)gHC%;le(ZsSSYK*pO96DD~=~+xyGak;aYn@?+sAL5ETp5i~S$zi=3TFcuh zY9(3K|73i|nilTEakz`$$@%TSbJhMz-FGM9+Hm1N-~48)q5JDfcG+*nX*bqtspkkr z7*2}Hx_Gtd)DoHzuZOqUbhuGCp;SQFgFKqoq z#axjRwLj!3+dwaydO42D>&VrWaLuTfX5dblHd*728y=*hm=SdJNVNLEmpGU@>Fa}2 zGq>wST&Dbi%JI#W>b{9OPYNTH)yzz7@4rBG`|P`9vdb(-rrX9A8YXfT(RqUr(hJQ5 zSR4KEk*8O>w$Rs1ZiyKj(6(o~didBk4uc?DBdVB|J@)mPHo~YpI|PfF6Nm+7j-a1^_`f{jrRcQ%bC~d>fFzP#V@Zr8;$`AK&o^mm;`u{28I-{Cu zqAes4S^(+269o)Kq=SHfN(i7LC1Q|70qF!3qy#Am@F`6q1W<}7MS7G#=!UKoMWxpO zVxc1~N_%0w_wTKBf7~+ntTVG_W}lfo`&7Ig`|!5kV3B*;G7QJs%Jl%C@@Ed8T-ER) zw3t}5o^zwthcymzG5LeAef;SfBGF()G6MB$ugUM$mEUot4Q}6l?6mLM#m$E=P8sVv zm^w8x^c*P{3-%F|)w|M7gYZg+Prnn*e-5d4hG=YU56z&8ww{b#zpr5Xy~nFiJ3m{X zdpVwuKs+S{^D6E5^en$^XgTLb1Mn!^4>CED$K5}GvlK-2FXZfR)#xihaswHhH{;Ax zp1){XU%ftt=XJC)ON*<8nr2k%;yXW8)Q>et;=U-B$)v~E76IyGR6Ij;V&{?wafwj)a6 zX&X)k9P^L&E5-6ns$Qh*s-5t@C)_SWBB@x(^MgM&+fa4GCeECJW){R778)NaS#L92 zO`v25j-daR)!m$qvY#^8-n0}BmS=`U@|RtRs@%!{ZrqH9I-z{u#rso#M$a%bwS} z`oyj!;#H)jqUMTJdUlR=1M6+ zujT!pFYGWl`$>fv#87@&V`B#+uqJwPH8Qv(?ccUf$4VGF+flsESSvnbHVL4^?3zio z@Y!Tdk3Kk_Y}!|9D*KbNFzconrV6vR=2%f0-q!wPL5&Am_7KaBVK57vzDnM6n+fig%C@m+Gq+57ZYbR0FA>iW;VsK;0h z=Oc^jqY@$!n)T@x7%_w&C^8t78B@AG!S~}+yM3WhC6T7{g~m+1orZmU-Ah6Pgd z*|#rGR0DW#mVIR%;Y1l}aEji6rR(knW=!6_ko2xB;I@d;Ec@9VW9U_0qG@evA0)r` zXG9Cj2#>F(V`RSU8D=$frZVa*grlV=_ASA{y5D+Lg_OW`)~#RvqxUQ4|D! z5h@;{l-ova(Y}0BB3hYPV$V}7n%uF9Uk)^nv?`hhjV7O~&;i0RJAyE~lw48sWfN%J z(1BC3xSk(XUr*m$<%un-*!|k|>69AIKAI;j0e=Ih5`t=B@ntE##Uqp!iL^UcFGB>Y z!9b3mazIcvwH+^YiZAd_Ez#Vn+wI9Wy(y88+9FMkj(4GnuPdvWXX_;GG#_31)fFM4 z!&8p$MgWxc&Dpsr?lenyQ)m~z;BM-KWxF!1lK2`k^CX~G?hJ?J&I=LOrxheYLV?4B z8!>0!roz2zZE0MP>NXYHddzyL-Wy^XHQd+KHn&etNP$#V!=g@>wEMiWph+Hb*5QGJ zG7BI;xXL?*TW3@g3X0+-Ses45#1o3*lj>V}!4yH*IF}wc%T1YZUL=&t=h&FTE(=@K zPSbe(mqIn@lY{lve0S``0HPI@#ncwkujYezSdTczyz~njgPC+s)y;&q1%c}iWB91M zbloy3QP2TFqsEeh!wVrg8;Y1qQm!{z@`k^$dufo;7^O$} zi+i28fjVD?(<=Zqsc`p`cG4#O`-ViWe*TA5|9qqJsNyXilIs!Dba<0C)Oz&u_BX3h zsm()8+5vq%5mRXOEp_hxl4q82DZR+T7R`q&1B|DWkuAU~JV=q6FyYFx=?9ofqs}^R2qA zZy39v$}W9IexI<_E4}-7v3&B{#DOlACm#L)eXZ8P2v^GF?8~1;FD1QTgrnKR!1OH> z8~Xb?pb1m4$L$Rp`F<_zREgOs9l`@El0xN>^)72LdX;U8EeCvXuHfFXXrFxaUXRl? z+XP**on7w8(famOeHpoyuTC}03?uR)wHXZHRpY8i*V*FYB#R>H;zO`p~e#+Uep}ED@Y+)AF*Rl+%(}- zNLl469o7fVO@+)7fh}fZ%s1mlOvN~-7TMu;3Q09A@s7CIK0YGI;sxYd_cHP2Rggd( zHj2fmd@WH5&&>pZ5fmMySdb}^$cYwPRDru?@0l2GsuMKs2}-n}q}a^ULZ^P{7K(ue zd0zU2w5iyJuWMsHMbmG2`vwVMH3m453y*qrWTP6t*NU?BpZ2|t@OaHJYVIqkLoS?3 zsdxP6Jz=bx%3%(-ihFhrteX0GK2#T@iLp>IAsLF4-xh)o26S+o*L3|jr4zgTqVdA% zuRHcwc)Z9^(GNYG1_TSlI5)3)(jLGS^uOBOkCdb2l6q2k6(R8`S6F$amK5A6;H6!V#k z5j{U20-S=m8t3$*l2XwNm@nfc5F8iXzD;HUy(toTQ^w?&9mV%Ps%3p7$K+Gw!e>vE zm@|RDPVwkf0BiT!kNdnVBY-H8*%a0kwl&bFcj=mBMQuAnm*rK5=)~~9Q*BfmY8HJn zbAGg$2kD{g?g{&=opi@K!9-sGAw=tG;;1|~?QfWc{Uj;5Cg<%5{{*0KT?}9xsmCy@EQ107)obD zqTK)&cK+jRu#gu*X|c_k7D)S%BbBMZQC<`EP&c0vM{@2a~%0P#8JW)%d znCW%QR*XcD*8GIkSbU*+9kBeq{Wn`0Gs=h*#RGI85QtVXqvMF#Ekm7n(+I5zyo%wfYt{mJyB%pER zdmd@CkAYz_UKi{0+!sikJ!!;0OV{C~DbJwi#M+h&rbrI!-) zsr>E#o)g4nc_WdP(q7{UMKSZS4R*L`<{aRPEcEXKmygoNT8%`Ha6vtueUiPrZJ5&& zV%L|E_e^K4cE|FWj}l2KG^2L27D538qA?#X8v52PHR3D=Fb91c17QqJ%W{CvWvoeU zTpJ{VFiI}`=Rl!*QUtB0)T0eKBF16fF&tD8FJBp_ni1(0mQP#C8HIPe*&f+0NIZSP z=RDj!mrK18=?y8(dj6$n_}Ab&Mo$7)DVi~Y*g}2-9O?TFR{9E4)cXB}Jr`Z->_g;f z(j)vn8fN$VGSY{={0g}6vf9Ff+u#bLB+~BIDV65y)K)42F1Ki|5MtuLJ%Ov7dHWYd zyH9n%bEw{A0~~X#tQI)1S6xtA?B|L4(dfd0G)Jf{K|^xm!sIo?#=aLYDrHw5+{x$0 zswYhMI(RrN+0K%ttC|5;E!8&$9SBrTTfP&Z^UOUr%QNDhx`dctRiIwT-Ul()#AHaD z5r!n$m;y-mxIc(=Rv&jsvy8wuBcLC>a({H?ue)SV7I#gi>}seaeXsI@xsyvGkr7`@ zGOT1q_-P;gDXOv+&~>v(uL(BM>7GGxv#h5IrA%$Zvx8Qpf%Mz7*~aNzKU#vc!AEgU zBhk+~_Q@cgJEL_^uT!V-*{=veij&bsl(qux|1>1jGrH$)#RRw+=Yg7e4r&u@zE-h4 zl5jO0)?}u0VDgIyeQ>pM$YPpPH!1jLbc21b8BzkZ9^pKM_lKJh!u0P9K&6o0;P z_gH%)qrYdAFN7lX9etgBp()OOkMjD@LB}K#I?PjH82w`Zui;nb0|F`B;z_HOUfcsC z4A&g_3pT_>%=~xwW0x1*H6wh&*~Ijxyo1{1Bu8LSfI_A3!bS_nC`x|rRb*3wx!k}q zIz70wDDCUeEg7e)1&g2*t4k83)?26+Sk@o4QdFD6S@Iuggp6Fy+Wp=9GU10@l})OT z(_6iPe?X0n{BMMuN1v^C&!MU2`0lS=cw=bBq+t6>o404KFRbtmT~y=3)~3*A=0Qfk zAC6he z1ddydQ)0)Y(kx;As*hGGFKyc=d~f{zQN)AQX10E}^&4 zC>SBg-5y-r!kFCcW?cAjznOq=Li#;F>bG+_Jh~)BSXhXP%Rp@nH{*NW1tLdf90NU+ zt3BQ>heuS4BkY_fpfOh8!)b&4J?1exRNWX{G>mGDcNo0Vd2P~bToE>~>)&1{5jlRv z8-fA&Ur>jYeKVeJzYA@t_W1HlB1FJG05HombN6G>LC^)wMTavRXqp&}p(sG9piSO< zJoiC(dov=LEich^a@vC-&MBwX5M2oN)sZpp2e4SR4I>QtfUbY&rkr(t&G11WOBa&tp8aoS@4VFb_#ak?}I*$oRj&(D~tm^EbTa|Th^ zP;f;9)#Q{T<*8!nVmwm)6WwD$k5!bks1u+kqbG%$wYjEu5OuuHZURc5Hz F{{dBqH5dQ@ literal 0 HcmV?d00001 diff --git a/figs/3d-cubic-stewart-misaligned.png b/figs/3d-cubic-stewart-misaligned.png new file mode 100644 index 0000000000000000000000000000000000000000..e87def8d5a1b3799a29d6041c74d69cac33bbcba GIT binary patch literal 22010 zcmY&=Wk6I>*Dl>1GIV!~NHNyE?xNOz8;2-4DVkG}8s z-Ftrw%$#%fT6^u4dp~Oi`udd;J`NQQ5)u-=in5|M5)$$k;B}9M0bHqAV1@(#klnPE znqci2uHjhuO|#kdPRVR21djcrP8~`ecyJE;b$M%u3=G$Ap;+GhBD*nQ3H7|>`NaI{yga|U3lUYqR z^MCqOHT)Dl>aL%Al<+GuZ|@f*EicnF@Y2Htd3Lo?QrF{9ynM`!0E;o4NFMkz#8)lP zpx7pe{}Z{r_%#-zEq2oWM^sG|8`MU)eQ-JK?<2aVC=MIr>~O-6HJlhC`Do*2k$oCflY1MY}sg3wt+x})-@UcmBCJH6D4&;SNJ7mY4p?r(TaLdm{Tw-0JF}zKu#Dn$NcVqns<(^EB(KD`?2x}7Zru5E__1FiY zYc4IPQwT^oX+4}}FwNyO(E6FQEBE77kQ1Dv4-mdiZa(~-b=i=W48jI3qSNVx)O}ka zbTI^#~Mz=#C@)&{QKB*ZS3$sT{aLM zzl=MasEEA5Q!#dKuGticjq5=E9o(3aEBHNHJ&qSzZ*Y_0@x3rSDY!<5H9XRVq+dfH z0YR+83kVk0X3@U;+cX?|k)#nNr@h9HVGp(pk#2YlZo~k+m=N1E&3YyK1Q3jB24kziFUhF%N@g>B;d!;f1_`j1`Xy`(>&4E0Eeg}+9{p!EU~Y;J+Q>PH zHn%G=x%E`Iz%V8VFT>9R=l6LBZeHftZF$Ptz(dGMaqoX?ocNfFIV+{jXMdNhX0d9e z0hYl#0{ypy`TOVnf2ieE9WI+CPvaMi4QT zXTG{+C-CZBH&C1V|5;fNbj&nD6)=lvPbRZd z7#p!WaTkA-z2Ty|tTdWO6a^qEnOez!ht)-~t?4$nY=k19XTFpwm(?g&$q1qs;V+Gc z*3Tvq3chJ!F@6Yr%iq0!dIgGS2i^Qkl9Z0@z#@T;Pq1=^6a6S*BXC0U9GTu6`m?pM zBS6Z^fXmp&XAh1@jMBxL8ummvP5tLv5EVlohU$ug16>XmY{t_(66j5W2Db)|a zRPVt5F{ZJH0Zl6ik8Uxdb41s6D1#w=WYLh0K zv4gftgsyRpWn>*K@*k3}9xKFk0nw6$t4rY&u5W`{kp&TAxm1jbAaYsyh(hy)dh)Js zrCXb%q>WYizuw?5Ql%WQHsk%Qbl#GpAb$2`+YRN^1KT#hv|I;kvNVPg+nvsQv(WUW) zu?=y%<&?iM5RSD}dkZrOw3HPwTuKS9-L<*rh>=ZIsy1n#q1F)$Iy z)ux6$Tw2hWP2Fey&Xr~p@==t>)+47GFtWi03)=hO`MoPjAc%?efI=rR-}Ks1b_CbL zl_QFDg{zm}1+c@$GJrUfqyXgA$?lD(j>b{{@<+`=Zb5~!lz`z6AQdJNZcvp9U}<^3 zLApe}WBdTxhBOi~2UAZjcrP+7V-H~# z9UjXogDo(Jr-w~k;*jPFfIxp5Z&us~QQ>~<^Uxm-(;L^TQds>FF{Cpb?8m~R!cEx! zN6FlRdae-qHy=(7b8E9F`?H?}X(4@L&m<}$x(112cndSuXp$%Q$SPcsjrqiK2HYHiorJm3n(-fr#DjH^2w4eYHpuj!B467Yiio5G!T%@P zSPD!$PTQPe!l>})GnaeN&$UPoWk3Z*a^LzR%&iy{Z~CbQOtPc)sPS*(IJ)`alw;HSX1>ODkbDeEFO-(GTUa7+6`BDwG0T0Wu9Q zt)Y!pOdzUF@?a1*jBvYvqvv9Ph~@v{KM~6iPJ}Rzkc)l}-QRj%&8%yDq-G4nAJ^Pf z>>Z7I_$E#iP>A>w&G-JKEhBn^q{M|M?+&tpdjmt}uGWIHs z-v6jq)r*`~i1t{a7d6%2Vg5n^r`Tg@kvGZ^u+CJIP%hcyv<32bE z?;@MyUxO5FUdtUP>sewwp{Rd~HG)FVE%~BEgW_P@px$!19oW=n@7{SZ?eX!z_0z^OL$0XKD*#aHtIljs>mu)1Im1)`i@11qfzF3JsOb%8p3 z*tZWRZ0B}?vh1?(;jj{@ffq^A`dE`URM{A0H21}AN_Jd25&(k=jbY`%<{s%uZdTMb zmchIMDx$x2ihK0miSYtaa~)%toCNTr3q?R4E2Lu_XIr68qatT=402!jB$&7ym?Rym zIEXuNdS(Al8;;Whkch9Go~eHbpFR0YmCFX%$hHe@i%@rLI|!dUQ?wl!RG6p?&TZx= zNpH@*P?L>ko4c2a5bLrB1MwW@`j=qv0ULuC`k}cEoqkuJ@4AMAk}_ESFSW7g{qcjG zxwnMoAPII3DJ94l{{`E-W!()}c&hz>g!qQGWpC6HKj33*Q>MJ{6CwJzKmjTiPzH;& z*N~+5dFWBkCvjB^b57L(?h6Jya)YErma<#Y7?a5TCwNvF{KWe;gybJL8!Z%n%qs@P z*N`B|&`V>c!B0ppx$#K!@^FAbaZn_s=O;et;q7aHnLZRa?>qrwD|N^?C(VDKP%%cl z&zi5CK<-46oDOgJiV{FRw?dNE+NcJO_^V)+(%G!TV@r~*n26|o!wB6TlD|4~)i6f# zLl)9G#K*1TgWWRoN2H2BOF4zHRLQq9vhqRqtI1q)mwMJOk*b-7^c&$#WK&~OnO>hF zSs~=GzgjcgyulN#O5KkpiH&!`{E{ta@b={G;olW_;XF!`KHTb%>hbai*yXD@aO?^nsiL zsI@a6a>@l7`RlW=9>gP*gn1$qh53@$s^_yfL}c`$m(pLfdE0@Ch*ZGx8zlJPD%bim z@9?sy`J*x-a&$Wq2QfRYH!T&e^`y-uP=r3WBuQFgvm%wwoA;h{uZjxnXuRpKvU->y z*if}+1!UfmVX!%rUh<-N;(14CffLG_warmC6i2hW$P2uvaMb)Ej09oExoxR!DlAJr zVaE7NwDTj@!%83Yy1b9|FOj!ob7+X>zDF}{Z*hG?W#fPBQhIJP>yyQQ`xc)No`7a~=S{$I#(fRKjK4<~d=+yp0P1m6(x#85< z5SR=rOSJ{SR2S*LOvz(lEMHKP02>2js|1C!+L9;!msJG7suKP`tlk2w&;eGJyy`WF zBf6RdsP-&8Q0`t~MsZE>3r5~@EdDHCgfW7#0QVTy*T`+~owj?%XB=|x;eD8`p52vJ zUww;yEINUoftrIn!v#hkA%$l`-TVpK=&!JJb|1>Sg#{fSu5qUMBK~+Go|#iSbG`lo zQ#K^gf8O%hmtl?v?)-Lms`J3(DnZOVIb1h(f%A?@<>(S_0xv5(}*2HUf4X=`rtC$8WCi79VgEMX=LwzkQe5xz76JQ>GPlxFiRhZ zAIxHgQA%^~n+`WzlL}V-2>UbA{AkSoTSBMuvcFbpDy{8Av-!tW!gQM1y@N>m&5yl^ z!d)GYm8psQ=8Xze=T$!25sd?d_mU9D8)>OY>hiZo4cndiHEj0GkgcTnoHLD&nCL9&jnj)G47odH=C`ylX_G$#w30uBAzNorbY3SeHzK_2B z@l^0a_SgP8wpdUQ%5*ZD48474sO653Wsfg*Wp9KB%`pp%OjJ>rceWWPoio9syySqx zoM++BXvVYbm^4L*rEsE(p@-~i0iVM_(AS8MksffRy_npmu@X-meMXmaqe)K#bm(vH zgLw;=;qJJPansZeH(w~2a#Z~`U77)%%=nX_;GcoLx5j_`)OrF^M z`ke0O-tmtV2h^Xeb+1{3Y%?utk>@S7NysrKmc7}aGyj}n*>^wG119Gu7NbnoG`BA; z0!Y$;9lvn(+)UAD!rl|UK9Nm98mwlhrfK<_48V2+_Ejoblrhr;SBI zcWQE@iXRf9tn~u18bSWxw#*Nm`+{Sp_;zt=9-}#;1fbV4~W$+(E;fcjgej!Vc9nKjx;th6t;F zd0>ryL>Vw5yCKl-A^B`e?j5)P;a8rhC(i&~gww$0RYHB~uKLO>`9~%0<6Ip7F5H2= zn9Ur_HCO+(qL6SsUWsfuOcRBM8Q4Qd+(%EDuv0qWRx8Dqdc5~+3Iv^KA~^PIh6>{k zHXEK_#;*bfy+KVfkz$;}bxqErOtA4ftL4>@1s0y!hBwn(qg3J`jAO#tgE`{#=AH>j+0=D+#tyvP5)-HNE&}^)JS~u??!~rIr-LGn*+t> zItULyv8$Mtk&xd4Ff+(y;3W`-r-r>;Od42l@)fBiL-O46N8lf-ukiW=NMK++i+gfV zJ>H$w_aMVGm?Gwfku&{}AcdmUa_(1e$s)DDttWeB5aS1LJoY7+ipx@aTW!@qM#NRp zi&60%QtV3a*JtKud_!aQTsb$2PU>%Y1fBpDu(N-s=ITWo)w4gyU>gR4-da!eg*aZP zHDK~-?`(A-ZZ3E4MOn|NQ%#O645FzYIYsi0O_Ojd5!slut0v#8T|DlFD5rPVIVYzSpf``(H=Ch- zD{po35~v7&(o4m>jOr7q+ei<96E z=c*Aaw_AZfossfwt-b>3diq<1un#D+4RyMkpQ}v!(ykz28=BSJ>`ytbM_x23?g=;G z8ae9Iv~Ii%jDtM88tFEOr!b3er1uz`t_f%T@M&PSVCHOu(U+mmv`0M9VsVVE|Fmuq zJcg!+G;Z;mspznNMF8SRho$yCELpFte6VS(%Gk6vB?j=poMqG zIQ6-tn{%j25P^K=at6ZX5_@Ium`D_`O~)f9Qj(-~JcblL5XdmOAU;K>NXn!gtjQ3sc1>Fv%n z_@b~Qud`)TBi2HpeSoH3TLhxT_B&%Oyh~hzK!$T91pU5Pw`mHXC6mTR(ItFGGyi$T z;l$fcU@tR%%Rh?dstMFnuj48`dOlZ*VOZKNo<-;OpukK&M(>3PyC6{U{E&)kt)Dq_ zx*R=0NQf`y8cnO7V#pD;R^k?w>Dtmh=lQ9?azPwv?rAte6>EaQ!#8^GmGz5MeZaCi?F_wkBfb+?{@CqMNlB9C)i0dx9aR`N9sr+~T@D zy5gTbQd@ zs{L5z@`7DnLKf@?T}OJ)oyUq?<=Zu;xQ>1 z6%VGKtUqPvEy3K`@^#OV@xMxVSPD`~(Jke|Tnu~Y2Axrv-f1=h zu86@~kPra~mj;~&a(hwFnV^TbHW4V}?!=BC5gkN$*Zj!z$UX0y6Z=vjF#I?eKbkS9te!1OnEe{nxaCg!q`EvK@o;Bd_f&RjahD2(%Jpq9oe{cMfUc!<;Zn4SMx z*yqwBbuK-)Eu>raSD$@8N_|Lv8IJ@82yJD$h*v$o32Q_vv&&qje`y!agK8rdxaubn zY4Poaxc0w|1&$i{hn2ZkQIeMT+~7cduggU@^bTVLG1>(^lAFb*f6`MrIfd+&zzRy> z)&<`Oo62qyGen{q8MP~Q-n&!e{e}wOhAq#)cCj(EsTm00w z&M#~jNPS$BmQR?{Lfv6y^jhMXf?!UBpiHk|(C9TsQ`5h_4S5-?DCq%Iel$iRVR7QX zYw9o6d4|zFq?nC;L-m$Jw|>BmiU_AjWx`c%9U_@B`8R3a%w#k8jF z#8xR*Lbp!Far zr-vxbg*Io%ndz`aam9=zPBL^`FjkCIq%O;K*HL;2mb0FJWfmATeETs?GTKsUIzW!U zm0y&@t!2+_rBAObhiG2pbUXRop2Qbkv}qR>c4;2;HIc?ug+g{rxnnj}vlU2RT=DhIFr8TnMmEEV!w}lx$gFI&@V-28x^n*=auK18_c;u3t zICO3%!xU>1zjzt9825fq3`EIUduNN+o1Y=Lmu#JyeT09F8E_#U=AD~hVzkkby-05#&!iVb{feD+^~FfQg=9lkDnA~x zX%~OCbe{V6n{-OaR;%eCHE>bJ&(39SJ>IjQbC1rge=5y;qsp}nPrY(T_?^P7azmOA zz5RozBY8!M)mAEdeW`0F8x=V)g`R71Hlx}Hj?Fo)Z+fvm)GuyZ=Sy8$ARbZ{uUvQ^ z{pJMQI7Fh@huHEv+}(AFAy`VPHQC*;VBapM689OjWmd}+3(ml$^Q zKfM6k-eF%@7vE%5xiq>bnqaGuF*{PeZ4wIKR*c+q#>&t#Cu9Sm5XRo>s2&Klw-rX- zj<0gA4&Odt)vT#oSt<_~qg%VlZDvJ^?W9%0GoW3!g}8fF^lnN$B&Wqs%Oxo706;GzXvp!&0! zg&BK2A1En1nz8gIZqB4kIdn*Oe3f$=Kp?#-E`4t<(PXwz%2|rS9m2>tvH^Xp8QY#d zYS<9@gO)4!)PyAkYt53E34|_fHqiMQ*-tw15#5vxG~}v@c&55Cd-dwVP0?^kOrd9( zRywehy+*1LGjN3il&iIAXT2MHL6RmI7Okksw($UjFHujM8tHKpl_L%QO=tedD8V}< z`-JYa%eMn1wZGY_(p==3A#xL^7qiAP_rC?*PO_m?!>RC`_7>s?fx^fF)Ndw8{*M)O zeYv$)o@lx$rfACc+U_~af*&E@N3PbMRvE8u!Y z)y~;08N?v8qU=|e7VZc(Q|qr~c&y41>9dG6eE96RXK&>_&1$|$b8!Vjqe{{cKc`?y z$b1MnxE^oaDCEz)2+@4bzEeT<&O4gjrUM^kvJ~&HKikr~PkkgcHMDZ&OumOu%A9p{ zwzqjBDI^#c%X+*uN}?P#jiT?UA80#5lD>7Ot92xft&i(SXwP9DGosRV;~M0=M<1X^ zFT0F?&W@@$GTaQ=u($21$T}ZHff{P73L=n0(Kgw!%5r{T`=e*Pnou*I;(8ZasGVmA zJDBUWfZM=r)U)R$h|iMX%CYxc)u_$7eU@J3(ff9$0UI^`hx-cDtF}@CcX;zBC;q}O zJiOb&muLD4rKK<(wGzdNM5Zu%9c6o$oN5?}2zh#qG)Je8&+zxqS&fAg?N^DtYOna`IyA~*F5h>byMt(OB)fqL4VAJ_aG zbP~nu()!VDdsL^qoPG*lH8oE<_8n*`cJMkR%nB6jr_l;%sj-n#=OSuITICs4=l8E;ap;@ub&H6V}S}Qe@3cC1{JW6kR-bP*Gpz zE7U1_z7_dVzvo-Gq}^QtC7eGMHcsdx&AuhcSUBF?%GV$XY*n-0XR zCYmNZwaRgxrF1aRSE%}0)NK=Uw9uCq^~lBYmBJzu?Y7FRg9+s}_$ zFSgZO17A{5_f)uS`uL0t91CpOnJ99IF!glp09%mt1k7F3p?otuooi@C>{df&3?fuHDZQF)Hl?m zVpQ_+y&ECZWdsKCCaX-4CqJ@Kw2kd@VuGevM)nQ!PDOF=kqE*o`H`x?KM@kSAt>GA-Ya7-L({Wn|sUlG3^a|>E5rG zXT4#Zk!DvwApR&;jqq%B(XXxZS{(lDwvXCl`1jwx3`UrJ zn%;T9QeQu>W2y^X94wbv1gy~sYxN~u28_5SM8f{$yFKpo9xORsn|g!M*F3Y zF4Q`^0kov9Qbtdr9;|=ewZS{d>dJ%**K4ZQ26pgjSKYSijf0GDoT@V}{b=&A7RxUc znp|xEEPu3Gz^Jmg__inITK@f3_&D9&#>XlAy`}G;7(_lblYO?}SN*XzjC|?6Wr2}Q z^3&|f%6v9DR~qR?$|m4|xYT@_UVLLm=ErW$4Wq*WLu|IK`)SbGDf1b~=ae7x)K}m* zt?z}}fJhvw)9!}c*8Ar{)w{M{Zo_ZMd(v>!BQ(m(CYoY z{~|<~aHj~CjMic*!v4VGv_OyOU$>Z$LlrwNL6mmb85e;g{+wD)e|lIQWeXAty5L8i zc>@N0Dod^G8Sb0DoQGNe5Rmru5l+&cZ4M8grFpZN+@Q#g1prngdLsZ-?-+G}4I( z4_jA7pi1wl$bm9~8vdbgw~Gx_&{S?`2p}B)eRR-`up8d0kBl2Ku&F2g@yZ{kTejV7 zcrH?RnhOn5F~ABO6E=(Ixj;XR=iuchFoGf;zd5{rGsQ&)z^Z?tEb*&Y)`#k`};8YVlH44_+#!2Lx8F@hV;%X?>n-i%+ry7{}HbcQAiLRKtuUc&JB}JUt7io~5#d zIYazNtg4G(JRrsPZ2swAEJPg{n_JiTSI*?ehOfx{&rW>i)@@V_`vIJg+s{~6ipc(n zx#&|XTQiuKK)|67&TC`75UtIRL&>eL!?sgWO{?`StE4GM4~^ zJgT`B)ej}W@Hl(xwyIpnUmEA<3yEj=s)qf4AsuS35#mglXKjLxV?^i`@NnI$jaCpC zdu1V6D3eFS@Ve#SO45cp$vFPfVKNcnQby;f+W6!mOo5t%GLw8AFsB0TqG%W-P&Vvm z8Pe~OvgQydJyFo$~SC8q&e1e}B;-sA}IlD{bN zUvT#SzWeW(4~D?d|7&h9WeQ3r>!w3)v0Vvu1mO%SYX7_ofT^AcqbczJQ8)NXfBXV* z{LzXywEB4Uf62`nY%CE}v1ee~C*ZADAU&YdV72r8mjz4p7}@+IGIMZ0ygN>s8ckA7 zK=t-_3)R?0>VGGB)z>Jh6}Cj{jRDF7uW_F&zBA``&i~(8xyl(oreC#DJ3}_s*^$4g zs6W0EXpH{f+u|n1UMMGhU8{ZT6&*NE?1%TGG z7`7&JcU~aR$@nW}_TTNj(YRBS_}%>*z?ajO<*RJ}AQy@GDC+AH_GO`i;?)h7(mVZv z6adu${S0FIo2M26&X35VJI5GSPc8_`#-(aSjjo9I-Px8n7h)wqiT34*bz>yaG^ zz)@4)SO2BEN%J5wR~v_NyHgSQCaHk6xP?STMSCZ!ovjwzjn;E}3hlN%xnbXrg1^qG zDW!kxf4uZ2Jz#&MLD2Q8?0Xl!!{xc7sEB}DPxAR@-Xl7IETIVR2wSV)*)E+9t44iS zdgOIquD)arbh|U!Th6$}kHxl?t{vABZsBq~5yth^G7D0>x{fg&IIx_Hpt-z+$7?=@ z_=J9j2E8)!-_GecVV;kAUtBimv*HWp*%A#56=YVh_#9(U4E9OR~o5F{;dNJdp3&Mz6iFq7}OW7%>zg)pK=fgIbR(hk6mGwjXPAKie zIi^;%hr5Bm=&vE-?QSCcG@e`;m1dQddc;b^Z?Wlkzj5r+67)X zF+3x2okk(C%2PAu((Y!3c;zocx&l*IaD>O)YTx8(g^Nl6t>uK{Dky~)h{z3BaIDW>`8X5sRu zRcREOr%u`7hxDh}^xFFAfhkIA z;{$?>NA;tAGmiO0opDp?@N)t&qjfgD+c(NpeBBvGQPS=+vw7K_bo<(-53jCLs)8{7 z{27t|>cTtVFSKGC) zA>3@K@m5R8WXQu?B(j!qP%!MKbrC;pHedz4>s-v2;1?aqr|&bfaX72)DvLUx$cPo1 z`PUR`L0}F}8461$ti=I|nOTitXIehgWug0(fi4vuX?{l^gKt*g-OuM58M~j>AGXf} zJ}3#2J4ML2JBtVY{*dT+N49Sa(w6YexLM+4)coG2V_5g;g;k;O6H9uGTPJ4*d6wpEb0Vqv)ZLd7v*MyUfU3oeqRhQqK zKd8=k%onpdYYriz5QS3jqm5dglHfzRncRXakL~?_G9M#=E?XB*WQ1u^2C@83YxLWm1lz$M#T{!DO(r>A) z6mwIAjJ-4wKFjhJ9-^WO@?TE~I=dvdJby#?)klv-FEp!m%jqNCo(-Jia^gS6>~_^| zb}dW)mJj$Ic22v5xgM6~;kNf2asAPc|K&=MXs^!wTL)#0#f9|fTW*C5Tg_OpXIoca z5&ii%POL7k`ZJQx_b2#zt}3T3_YW|4;E9+Sf50;LRDzvhq*Bax7sXVY0Z&c^Byb$g zYKZOIh@d$cosPRiFm~%^PrHyAzLVt;R?!{b_c>SZ_D8BI#!^Py@ffOr0znkBnju@Q%vW^bS zM($mCsdPixd8r|Ji(F*6aA8aF>$!|b3V|Q;z}!5)3X`e6e0qgoloy{V9_MEw9-frjQc;i zS;W1J-C6Cg@Aibu*dDnep!NX3u%Lf@zucSuDWVT3Gr>SBW_@sRx2NUwAa#bnU!M$uW_T8)TmWSwWuXphKF5hi*EIcB~jHbU9E@ysO z_wC2*%Mndgo@J~Y9Dghx%)sQtMU+sNFVBVjoXW;!$kvab-w@g{5z4gQnGsg^d>`FS zMiUjvH*f#6Qj2Hubu=N{)E@qpHCA|O)*Ypm1RTUC8GaR$HoZGSQ{a&6NBY@z1lHs2 zNLu1e@j0Mi>HCAcKoWZxun?^{0EsuzAjmK!l3H_M%J;xjx}PxQ`fv{7rI55ZZoG21%01L$xF zfyHyF+KN~jDbi95_&NbAd; zThVh*zv0WuU^@6;^`)i~WXA`xlyL8f!!|3j?yP??qpf#3@vYvJwdZ`z4>gDvPT1_< z*&iOS4b|3&AW3_d^{zxFPYMKzvwUg!+qqplN}?0p^nh`|)R|6mt-1beo?Mew_S;w8 zKCVMY)0V~HP3%bbR+Q$7#1i!G;19RNu^Op(V2aQ+u1czaBj!*7sv6>F^j{soi9jBv zXh~K6CbBo@L>dtJKq(SPE0Q;HWecJ4qq|{I7;uLiF-sS(OIykMY}6ZEJ$$(eq*z7& zTZo>bq(d^4eY0Lyc?x^^*HdKcr=whw;vExda*ODH{N8h;^K;3D`~IRsSfM3zcoprQ zG%ZECOK(lBvLy#?6ypLt5dW?qb^n^AduHMcD~oBGYaDI$cN=RS*;v7;bbee1VgC;f z*z6nHrjKriZj|6ja_S0rA$PSH>R<=jehpF^UOxHN!)>e4-^Mj}S?DtPCSACizJ+O` zne`p$RRhL+C8SUeHVSg zN+Etk19UW79+a3@(c%(Wfo+b3r|`(5b$&yV?-{b~_AZTzhUrKZ%mpRQ%L6 zP6@gvUezx%RF%E!fFY@>1x8xFLJxc)fcE&Dr$bxQ z87?wamCZhfM7RJ^%|s-w`^G54!&u;hqFsu`3{8y715SH_75W@s@0p(Y_hAMl`A-8t zZ)SO-I{I8}k6`h!LDbQGF+|5K0KfEo_`AJL(37x$G|?D^K`uwJOgrQ6UuhK6XuTvoo-5e&v&XV zu#bn-(n{Mcw3&9KY}MGqz>MJVCL?K3`eBm4)vHC2M?mwb$MJZSV8%D6k&V$jSGopUj{h{;T&I zQ2XhybLuB#4V7u*ZxeBrp458;=vx@kmmEoVgkc7!+X#4{OW~-KDy|%YUP5xUzOTYK?`sp}r&&}~RCCL->4h}`Ciw|zGnASoBE&>XqgvT`@*QCyj@g0)m@pTo8 zn_g<1BDb|?xwGn_E*6ZSz$5L@o$h;vw*=2;8=jtGWtySg$ZDFa$*riT&Oy#n!Wd2i zhg+^d;3wyA&UX>FMjz@5v~(aN5v6S1Z#gGX=dmMYdnn^hl!DLH{N31-ZX6}DZWuD~ zmttZ|*7!CqQ$)5-v_zU#a#RIq)`j8ta9wDZ6DA)EXm0NaEf>Kz+>aW!g^-q7Qaq+0 zi-jR^#f_7X_qkYfG5=%~RdZl029FI9{ef=Qvl1Q zn7iO`lU&n>zF&t%$!1@b{~oM@a!+>#ZDJqE4ZSV99z10OU{mek@BE~A%kEB*N7C5p zOx~Dt=nG|8bJZ>+n)vJy{+>ZhKO+`1e@p?z$Uzb~h-TnGW3~jh<(Uo$Zsixew`erKobV%-FZ%l_y25<@$JJC$$TaLSb z(F3$@Uln)94mcyFkqE5!Wd!}GSsosBYdX4mNOij*<*%@r3y*u@N`9arU~KAyFhI~l zv#d2kGox$5*y!!rh_*W4V?N*QMb4HK7uzLi7nKY-RzKV*IPE0)dM-_CKS2D9GoEpA z)c%gN;*Z{stU8RYlellUlM*b|8>CNysjt~1yW`X^up=uo1Pz1_3-BIk1+oe}?9>El zoTVpIbEk{2f@A0o0bO1f-eyf&GfUMNtM-S@ zIJk?FrKQ&fCE?~kbbnKbKB|cw$C(Xk6hefFK&89_0VX+kWLMx$LaWvw1NvA@`A#wh&wNNL})KV-Va&3VRg6N)04Rwq#sTFB4|fH$9#{$m(pAZZ}9n{&;vf~ zi&z21yWOG*b_oZ(;mj;&sze)~8?{@l4#2o8jEXBRKv1P^ z&F`OhlTq1ImzMx_P?o$-P{!IvMZD+HfgSp;DjRH?hnB3b!Q~N}2F91ieW<@>y%ilB8;|J5fAgC`Kbc5cDTDDxTui}(5#-=D%px{a0?H9kZb zZvNtd7%WFbyD>Bu3&x@pdH-2gwf`kF@YHebvb&mPgKsMmyVAWF_<~I`v={eVVAF;A zxBg^3OlLZ0OgWU(rnzbdG1eWEX$ZPM zBeW7|0mvW*?P8ioia7jYjwe0(7RS!9T4Kq`?0qko!QgVmQouH{JS1UDuC23V7UDz{ zTj3E^eM#_kU@QAm*0WIYWx|m?a5XB>S4L>jp?|!RstAtRM9Y;nwh@TGHKEyk=kNR0 ziXNw;0wxterJf%cjGhhSC9tl+6!kE6#U=t>73GVM3f*wK5rDy8RqY0h{sY-1$NS`Kkva z(Dc_u%u`+C#V2W-IUg(oQOaCmhTGm~EGbbGAxUcr4D92=1CrB-+BUM#JE8{%HUyto z>T3({CH#M_7d9Bg!Xlw2@kcy^XZq&tK#eOIuvfwv9~gkOl$>`m0)isn`H z4y@xVT1i$l(UzBBSYBXCP7IGHD^;+ai%&mK*8987oAgYq>^yBTj5pb1y!g(Wpk&0 z1^R^~iDyaNyXS*m37A4@=I;wokugWwz&0c&-Xb(zEMJ~%P}YPrKZV@epWF>D-;1s& z)8k!|vh=Z4mi&tmr}HO*~4uR-P;B}dusZ-a%Ql)w7rO@muj9gA%EfUmKLhc4szug&4FF~ z_5(I<>ra@Dmkg!D2Negx+Ap5{kz>B&B3RPV5_QW^iFpS0cJToU9sS{OHbO(M3{E*H|99Eu|5IIR@rNgG9AHi@^gXP;d zSr-2J0#-comv-NWz4j{Os4L%Rw*&e&`eYs0@l;LLsOUn{+6Au8nJ5aLe%f;4(0i!c za}8jyc0I4pujip3_h!|K6M*M{_MFDOgpC{T=f961!uCz|^dGi_lJXC*{2e#`Rc0Ko zd8I^WFb+5lSOz?#aO7WAT{X|*q6GLSK?=lHU}8IN=U*w?nV`@Y9X)b%zphGLm;a|z zlwb4$mH>Z5^KnUB5|+p=2Lo#f2EUcGL{>PRU?NEi{6RG?iA%x~S>h02L*g2EItL$$ zuT1RQpLMG8k8^=o;smP3C2>v6!uljE)v(qlu7PKPZVHKzxI`|BOTrQomgq3fBWNmo zncRJODsop`5|#k?ZsHnP08}U(qP_V7&|hJYxLPPK2}`8%WeH0Nk*ng8u!Imo* z0>cP;no3wgh@50J>JDG*;<}Jv^bDK$vyNcCHVLbEIRGfj(|!Lcuo(D}PGjM562U;b z>Qz|W;__33mHMYn!YWFVy#(g~<$1XOd6!(Q!ngT!BN(gkTfi-fT~Sd_kPh))6E*EE zK(#_ubizu`ht-v)rkxR@lTaR4akDr>Ei3tFh(c6!HLQHk!_qKLML;r-OG7>tACEL4 zEDt4+77M9EGv#|8mYN5PfWH#Fyo?h}+-4P$qT$gdK6?gDm0m2=5WL@BNHFtojY1;w zfzb*<(cu7(h19av0>c%aqGBHkBXRgJU^;MuPN@)uE3TUpvf2z(q0v)>5JKcIrzfPf zNTCp-stPQ}Yz(ER!C`6RU zB}8GM`LKkN6ESb1WS~6itWtJ^Kez)N;X{qgI08dbz!eOZ` zBd&h~rW%Su*$FrpSZF8;=Q!X_M_7_1Ns^?tITv^oxV$J&*a-lVR9&-yy@6d#S{jS@ z0oS^Jq*3c5W(UqU6jFN~$l$C(3y`JOWebO|GaMr-T*F-DlXYDAwm6N1KV&F!Il{6I z%cLa}molu=GGUptq+!$wkhcMUU^q-#8qr-?INYj(()-L2hC<_+xXv&PCN1sIT;TI2 zEJ-qHNx9(4#ge2}?Fmc+UIMlQJwPw;Q{s}wJmQ*S{q{$I7sv98CmH*~sx9}f&YPCL z?kBFFsPkqJ6P45*#{gDDF{|&rg_^SB_dk@Yk zR5kSx-P%tw6kWAb`rvTy2!o={z>f`;mSX|3swrDIe3!@mxO@P3H*nM_e)f%NKm2Wj z?XOAOuQbd8>$p_SH(2Yi#@ATtv{t5{UD{y#`_uL}8)lifWWrLnlh*yf7GO$)?Y9s$ zraK#EWz`Che@0vgmCEQsEF8{L()ykBf%*0Z+b06g0PDy52|MMz_*Mg3fd|qjQMKO; zV2>2{4Ths5Rsv4~Ujv>u99_3G<&WKgFAcMOCt}%?wT4RSK8uT0^^sQXde$E{*uH|s z*Ru`>K1wXXbc`b{Nm8>m0zUvAYw_ofB(7&YFv9ljyt0n*Sl~S16ymbR$5Imegu6lz z%`lx3>`1F<_VWXEuGOw*eY?T-iNMnge?4nGF;%{%7uW>MZ1$Hs+pN4^2du*tkX0;w zzTn?6nGn^}47MYI}v2XKueE)_sO za3|63XEz#8rB-(xnf_hd;`aU1`_NN$_irJ36-w4|wTY((+cUzl4lDmA06!vT&Ndne ze=F_B`ueQbrTgdC-TxEdBZgKcuJ)Ni)Wpp)6eg^Sm`#+|+)JF!+YGD$KA5&o1#SRt z1D;J^w*Vi{JjS7EA0Jfr*uMhaV~90e;<^@36DofWC9ZRru*&~oZ!52yCjT26w}MiI zEiqv!#};9yi*8s!TvPg7hkoC`0B2=xF9aSZW)U{UX{FV%&JZZa9x?=7(L+qw>g~|) zy8!rSqQ%pbz+VBU)55}#CM`))r~HywTIsNqEZ+`1*UAHUQNG$H0Dpm}4b?gQ!0#D` zO4|l}kLZ^1T&q89(yF%45Ho^SnYdcAgqRt1nW1PoVckwF-nhTv&}f*ns_kx~|JS>) zb4DxX0Vfc3Cu&X~(e`H!v5d|WhD6e6SjW{mi;G)NSk__X(*odVJY}nbsVyWq0Q{rj zFlmjW1BtdhF5oC>+(%rSfujtCNoyQU0d8`HC8-_e7y^@4n-Z5JERBmvhCmrx4M9^T z5=*{+hnTvnk!=HBG7OR=Nm9n%#FE(7acM{TiC%Upjz0n}0!}m(DuZ64re=UBL^g40 zq=Z$QC3w2wD2%^O`|JybLS+49Ra+}&`8ajYzQtpp(?5sAaAGqi%C8R{7DPn z-w#|`m+12TMsXh&4ws#ES~76~e_8U^cyRhdU)|*Q9|l~^E3fxmpYzwbdwPy0ER&X` z0=qK(p>F|Z@8El11*`}DK7Abx91q+KoM9+s(vs9pJq-5S8vx!p!uL)DKF?r5@yFB8 zYz01SC}q-;@~f9}Oou-)lduMW|J*^+s_%fY5BZ!q=!JNbRv|bwS)DKq_$F{|368n5 z>uxUr4r%bc+kwq>_dN`}kh9m+2RuU5pGi{X9mC+VCPgkl-i^UR>g?AQ1>QH=!r|LJ zR4Zo}Vq(!AhC&*u40T-ZA0}Z908dcNmT1;tNm7Xu*N++`tpVT!6P6^EPptrX1JQ%8 zC|)~4!Wsb96l_1#W-?khEJ-_XGO%yKp7Sb(&KMj>iFZ@_|BJw`1$#~Bo3JFQe5Ml1 zaSQ+}iN1riMIaAJ$!h>uVW=cY-F7N*O7r}5yME>3-HEOjKQvS-m}7`ilrs&5)Vh7h z=XCfr44r6EpR^!Ov)xMc8O)o7Sd*#YSzIiQ(&4}ZkTl~Z;Qk!Nv>&(=m<#Ng!-OhHg;tb0 zt~1kfd??4Uv<^$nuwkxLfy8xjdVbHEuw>HetjX>(<;;!g-__~Ob|TSuR?VAEETQsU z;5gtpL!t(L4BU`D+(;UOrQ~P)vj-(fCM~H= zPNMtM;a^Js{x%2kIE*MBmL%oOW#nTa$>BO;bVF?c$6o*oJUrw`OUjoA)9B`14oel{ly?=;>NMK=0&qvgUi+iK_lZ7&%ZWz4l1WP{z=-P};MWy<-CKxd zQYM(Dd&CT})h3C3#ItYF%xKj~+uINg9iJz(;9s9apD%5B3A+xJ%VW z(|}#DPo>lqJw(^)b{8ObB5BnMhqnW7b=OK#Id!6rtKCVQ>710X@-V{M!$U}tI;$P4 zAGf>rV7FIn-Us*)a49jNCF@nde*wFCXqCcAz%9Ugit>c5(^A=O^EtQdoxtTpyQni5 zIt%m7z<$6c53N$zm*}u^m`O`g5%r}J%nY5(NI0g7L-Cans zANW^bM$TgMFmMym;_WTOsiT?+z%pR1hma(7#$Ld07+V4Ix#{PBGKPfpRCG{1nbKjzL-w_^0rBS%`w4^E;YaQ2E>a>bdhjk_J!@B#eqRJmPxmcjaB|Qyz*NH|mB)wEANQ|I`uZ*bzLB{-9e5mgue-h!E=b4k z0I~GV7a5#UI{lB+pOY z;$ms|gmoiu?I{07`hcGj-6M+VQ^YBxnVm7jb}YXG?|uEAV)Dc zt8lmi!r`5X3+)4$qx#V82MD@0B{enWW}2F#-?&wL0prSR6_kkZ?@-Y+)l}-oQd&KG6kzT1sl$4VxsX)Al8n-DqYVskOifxb(avsYUbalE-XD?q<=* zH9JUDF9TlzUSr6m{IVaJ@~R&=7I+jm6Sx#OfLIS|zm&+%Z}PF`0*|Git@kW&9q=jO z7lvJu)T-TqzsuY{3wRtjFWvqbu&#y2`^YdOtH*#30J99YBxx)z0cK`yUra3fUc2v) ziHQ@<=mnn0B&!F3(|{hsEJ+#<_1CQK0`45;W1UUR0Q@HKdP6G}+hjwa9NJWOj4lB# z8|7oo1Qr4RV^}3g?RGeWEthI05;azmD#kh#<OA7q;5y)$%=TS@iwu)gO}24T-b@FM2L2s575ErYV7xdbtmA-B5Zx^#N$R@Ez`?|H z^_l}x(vl=ek|arzBuSDaNs=T B literal 0 HcmV?d00001 diff --git a/figs/stiffness_cube_size.pdf b/figs/stiffness_cube_size.pdf new file mode 100644 index 0000000000000000000000000000000000000000..3179062cbf4ee6256fc4db7b6f6b7041f3dca717 GIT binary patch literal 39000 zcmYg%V{|4wv~_LUwrzWA+qP|+Q@2k$wQbwx)V6KidB5-exPP*Cc6M-*tRySz9CAf5 z33_G*P8jmh%Y*_Lb|NMs2V-j(K0ZcSGkXhHOCpYcj54Eym949pGZCYNt&yvln3;)# zshNNPjEk$YnUNigCm^(2W`V4`hK!?D?GUCR#K9SyWwEX~v_ZXfyaB=*zR7QX3pnvj zEhkNn_l0pcCUzHeXb?L1=jFnybS31c@#p*d;iC6*2!YzMzoZ=U%7d{CckDil*Tzr0#^JN4w!boY*a zC1M%O#oVfvjkgydgx=i*w6h7j^&El$Tli z8PAazSB0W}MyqZ@HVeCagNLUN4Qd_vbKj%Kt_{|^_^m5l4iiBZW|)g^jsB7i-W9o( zlP#BZ*MM5ByXdSp(`~{H{8fdNm+NQR6N|-8WVhPNuJNt#)VGlDnvYU1#{SJ?f5RAg z>}-M?j`Na}PK3FOZWtY{6(0p8^{Y&K*_^( zZBLSWtH;KKI_PVE?o~A8h|kfCdgGsuh)Ry<3c-uim(aiJuQ8AIK1ePb_#1ffXxnqq z5WSCE-8gIzon10DE2utn%t#;btT#bp4{;nf3a4-ULN;zKz*{@Le(5C~0$6AC45{5^ zoi0(mtJS){0Q5Sq!zvhO1B^@jP2{H^xZgv$-(i$6=`dMK5hHd9eExOYsi3LbA%9ju z*|_K2VzQFW_D{S4Z2G+VcNYb-BOfoaHC2R~pwEWFEQLW>T^2bESaAkI9XFIr%-;P3 z)eT2TlOcb~K7~a{pQ)~}y{*088iYw-s`Q#X2CzG4&3bVdsZ>JPtdA+FY&*+C8tStH zugxRZL~!pr6TX6uf=T_)KrJyv^VX(U@ z`%{gW$$+hVQV?^atTcr&RFAVmgLjk`ZNqiBOm?}HX=`I_!A1}S!|_{Y}Zs2NDuJ3T$z|$?pqwaJgeJQ8-CMV`o!Ickale$*qr|*a~p~AVy#+pJ5z7 zq))%uQkKJ^9$D0eZN1w?jOcq5<~Srw9HsvKdvdz7TB9zx(ehXkAZo)$PnGl4S7eo^ zHE^Fb%b^ovPOG$Tam?7-*Yn^$H&MkVV8y@i<3c;+cKQ|bb-3@jiu$pkxo(8*vC-1L zQe*uFLLsCuEXIYSy&J^9M!-n11+K##x7R%d%Xgv0(Nl@;)G z)G!M2cgHIBVz+Aq74=59s6K^xCQ-1f9`R2U2SqQ8n#OT1GCRrBMCRlv*^<@~;z)xA z+gdvR%A5|9SxOu|DU)Jnx+SfDUAJ7ubT!LU$QR9N51>t5SWxtEFlu#Q;>Z?&$gMaz z16-XzCJ%GUhbsu&o$tXn=bxRNKi4Y7=%Q^{W8aYtg&XnScvl$#iXX2*u{f6j@5?4b zE@QCH0vy6&yx48Pv-#oX`fBOBz)cu`%`_MY9tb`7$^Pk*IbKeIOG^F){(H3av9LoN z55-*oY~~AlE=BJkFr50SWTiCo!o&|WWVZ5#h;|w^;+TTj-CG|}-EzN6i3k~wyK@?6 zU%*-wHt#vg5%oBV(k!_J`{qT_P1%v^Q+}{jr&(u+g?5VTDdUqgaIhl^AtPSPWW%i( z9~=Hks@?S`kq2mtJ0c_v+Mz1{d~A&tY`=>8LS>TWXqX(#C%rW(B6@^#HQElcRr*MS z9b&f+YP#R3kQ2_YbH!~RR;W=}U`%cBIA<BP-3h8N*KHm#JKg}xqL|;uUrO9Z31j9s_ACEHbhsNWCNHUJPhOHUSf!m|78mA(w&$*_S^3L$n3R%EyWOe= z?IvQrChX%$EZ?7E>(|8SFN&~TKHH&VxM{+#Q^|+t#m={G{@f0~K0rds=Ncd)soaGo z7B{C)auTvdMuh3CZ;5OL$|NXvx!aaV;FcgyGh|y(*3}R}GTdFE?buV2-BI&a!gD@S z$ux_0A7Gn=i-BdQW&#JI6DvV75$X?kEVbcCFI@u}?5r*8=k>>i5bH1eLwWA0gC@co zcne`DTxqUJ8+_m;pq;H1-BBh*ODCeQnrFQj55fcj#l>9c)>&ST_Kf-r5k64@N6%n6IrKGr@~xS(5eAJ2*ao|SEMtAY_orW_gMXnv{Aqv@=e+$5{PXncuDm& z!f)K^g9LP1)XpXnbBCsDE)@X&eur25ppxPL^G+z)m)6k$Zu>&ec#YR3e(jfbPiCsT z8XG~IwUd)<9p2bm3Zfvizo0LQo(Hn>w75BkjS71><3pfG?{$l|J1Do7y|88%dhEcQ-t>Xop=G3x)SU>aL@s1?M!kQo`b0nS305c)6B83YZpxS;-G zm_p4rd^XR;OvRIL1#+e~ZXczG#yP+2(BXtcx@Ji83z&6|(l1YA+7OJ|%}0WwVG1fK zY5IHxJUFaVIg1fepC&9}2>vRYh(=2psX>|0BT=MyPK05%7%Fh?TQLt)$i2145OqU& z;(puZg$e4=v9X}uv{3v8LX3Q(l(on2@?dyrY~I|a_0xqWJ5uaEsTwZTVm;>;NEcW? zm>EexDPU)bpE(wS_FypkT2(EgvDE4medN>`u%DU(d*!RjhAS@wizjsg3FwCLapdS` zcPqvpv{>_K&s`3G38F}J(e8w>nV2aqpSKea+^fU(N*z(U$hr78sOa!b902thr@{K&Lw9u1aJnH|_xakuX^+0z`5- z#FN3_!9aLaCiOOozVrW+BlNpD~ccVG$8CQo??LBAehsd1y3*xZqzJHy zUiYK0oMzc0b1xiIvBrUL8R}3acBQ0SeolZm@s80DM1DmU@|Z4SJ^lhSl;|;X!Y586 z){=NoOF}bBFse`nnTo4!dDsN2D$|!wFe5? zaDfKkc~0feO1s5RgY6`;rK=f~rA`1%1pUEU0+3IR8Kc>rq3`RT+X}aYhgHfB zk31G!%P2UCc9L;zqm6Gt7Ma6ku)(@^G@{PIf(rmy_<-vP`cnm$eug&sd!s|9zLOE_ zN=034QBxtdltvUoK!J7IUO0Q^ushr&z*3y)Gsp>Nh0f}|Hz$$XK+4d-zpUDdYIn=$ zeSHq~m>P*k0yhdO<{O`3{%NSdlD}md2FGTm4@IR`1&?(iii*j+HPhd3X+rxFGc(QN zC8QhEzK08g1)kWi*D##ZZR+ES0|#1MA5S2XV;4S&-WzzP>GPW z4rLLqn0%bkDLI?Y7fwn+m^N1jrNlM>uKf|qYZ1}gn7APsc>-J%_?`mQL2;asSgN5U?(Vh76m?nPasWQ~OuWHe6l z0{y_&JHSmmWvc&VBujGq(>{(Uv$21;m?)Digc0#KXK7F6@EDo*GZy#QK`Nx=UjEOz z$f2iS=-50^*qF6`G?5lQ7NwLq;wbcQZjcMGaY-V6scjP8og?o&krYyiW0qznU1kgz>4{zqc1Rx2MsF+G;bF}CRdXd#V+Zz^$aB_IR~(SF3DW&g&m+A za(~e)`!LZQ$Xv;3|IB%-V2~{3&adpd#?$uLtx0#I?M&Ug7r(R>I-Yf}k*U?Z7{+|0 zZ-*@EF?P4UU)g#0GIp;ZFKjDlCLVj&4t8p_ZeNUxt)Lm~R8F+ml)b*YXCq04?_Y5L zV$IsWxb=Nk^39tMEqvwSEA~etJk^fhhvgah%U$z&JJTM&FN$l~EBfH(>GEVL;0ijE zY$fp6aHR9}6bheE_|Aj(PvhVV#7t1ut(=%-Y)|= zw)R3`ZdIJ8qt;=ig-1vVCTk$&PqKv;r4Rw!!=#J|g$8RyaSdcf=r{9yB6%{l#LS z908a)?iwIYeul3I%y`DHi0TjbvtGGY=QBY=+cTM;{v_S>Z=Em*&c_|=-(`hAY24m5 zKd*~A13jil?~ESt8(}EN+XUjMBG8NUzd3Kg(43_(noV>u@pfI?r#-)=7Q@**} zBQf#d8jJZD%WrH_NCW}+=bVUG?F241v0-`U`6@}^Wuc6PK`L-ZiwzvHJH#Cv(6a^)LUqAe!Ou>KA1?P zuyHad@h0F&9~h|tQ2`+^(a)46oHR6hk%T&+E<5Lao@pQtl#CCrAkDD-pN8dGdc zSUU*GInmiUG!Z}RLIjGPf)q(4e%!_PZ{6D7pfbl|S8gB2$|C~p*=t|Of)@F$a1FY> z01VNgHp#>p(BAQ!5Ux<$IL>JvGC~qIwJuWVrr}<&FXG~FJj^8;{UBIn#ta*vlNdWv z`_r~OUg49d5`MTr@bVZg;&@o+;slH~BFUnbKJZ_){(Hfyfo@<7RHGGOOrEEUb|+9c zWI5VGA+IB0uoX$mPQuT7B41rAkeHumaQ>%6EHO{g7~6oS7FVhcACrI{v6@>7s}+Ts z+hepV4^|D&WVIc&n%j~OpR{D!E^NiF@wj7(Lv&H#TqXf6PJ0D=)~F)>-aC zb$(v~&CXYvoX{B2mfm9&ZX?~L36|e4azUf`-jiy z64oC=+d2M@qaItPCSy*e&egIR!F)@vfFeC6Q^<0Mw@G9#yJ3vKeuJR!Uk8=+^oYWtVK7hk0g}LOaBVGUd+A6cj@{C?i-DK|9Pu;~B+0Mw0Ex zS*-U~EXrwWvA7mww%d&E9_6IwS+$Fo2 zK|9F%v|?)wWY@&f(aXHf@$>PWP|0LCjIlO^a&G$cg3a$7}0Ps+}#Q>&^2p?pzql9d*B&J zs?|F#WYMAsP{H^FIS$wUqM5g8G%-&aKk5r&)~8Q@2otY9+AxmZEK7rqH0f=0WcQrdmH$el!slj=W2n}Z4qIkJP z5`vBm0lmrfw$Zf($C9+A20peeAz2l1L;9UQRVWE6Mnz1kqF=|1ZK#uKL-A$+t|41D z0uzd~=U}yzkQ_9cZpEfOqe7GiRoV#+L(G_EO7*!{apOSOT+c{Zj-{!-9!ggynOCxS zo3C)yeKeN!6tA+_9xahdR1fdHX*;=QA9ljxfs$XVu+(_B7M$IF3bL=eOk{ws3#>7S zi*UkITiPGN=RVXFgMjJ#5DEr^M_A`X_h~jRAJBil8uRO%zZLmfpzWl_H1usl61jI_ ztWkNBlw09sFU*3|`uo>G}NiBcjs;X?~QM8r_5S-{Q2Z2%o?`Fo6TP8&26wREIB)NdEV#|Yg&-#40UA^#ZPhV-*rwce>m%!1UM<(Xprf5 z!c1KdI>I|5WZsrI{APmQo4XMnAlD|7qoPf0(6E8rHMHP0Z=I{0%p zoN5sX`>3nsbk2d)`9{oRa;zHot+3d3weY$~s8^lG=$t(blJCzX$=aSI-{v+4zV^#5 zs9@N>@q|?-z$8ad(WKE;lYZsz5zz=Smt-fZz6NnX%V>Ud+BeN@OV&o9i$M~YJsEEq z#{a1qfMxPJMVg>4o4nm>2^WWt_~m4FPPwhTl7G`|kGGVxw|WX*=9kx8sbKgZBoxMJ zOx33bTYoYMcqDXBZ{hN=4+im-6#J&+QiY`u*eCh|SaIaFp7(2k{jDEc6<|~ZiY8zSAVyG*jQGnb--ZE2 zC+N+!-58U+>1pqM0R~2WzC!fftiyVFh{)A>5-E`ZlPwvJhN@*T3mH>u%LCtN!WAsI zr;bJsV4hO&A^`jJqWj>r`UK$~dO=Ormm2+Lv6^`muqT#(vCe;fOZ}U1YxpQ(U5_gi z=aJ_I^CVZnX~vgf+F^>4PUt6VR@~3K#1&YHM}-IbWJ@I)uf<22@-Bh3xN%!$${^CE zq=`?qu)So7%W-CJ0AJojv56AuvA`rBn#MGUa!OrwEI-cJ^q9M84Nwr z&}l!ncUPD;FzgX`Qj|X=2dU-(j+!fzCp^ zPRNm_C_SAvc7DGXcaw;S! z5pOaaZlEO52Z6HE&8}l@U|j{a&?Y1~+IC-Loa(u;&U0n|?r6&hO?qQ+z=W6QzE8yJ z?MM<`Ny)ZG6B*hp$o&RzjHvi_>RrGrp}!e1M2Yi~uZUHm0c~@j)dBv9=Az5fYFg)f zMw>Eog?t#kcGkH7{HrH1P$Hi?hgXd*HINH>_@~9EX~o6+Fe#6(Uq6o3OET$vI`41~ z8KQKa1A`nEp#`^1mUpIYAw{ba=Qau9PrrGW$qP*TOyJ}iym&0swPID3@$a$&9u*Qab%eq_Gza z+I^GW9}fA}B;aNH={pl{zr^*Z7qZ8k!U%MT2ri|}y4K<>{J|aqT=jc=zD5f4h`}uV zyMa0(v_?kUVsD=n)Ugn&IXR9aEV=b@+kO|T=v#9r<56CtRzngh_vE18__0RxwOf@& z{jAY)R~qoPYE90kG7>{ZN2L=6L_=P3#~o-Nra^nzJwUiGs*&PEe4?bN@CM0v1J!v| zh^EmQ8F1^|nW$5u{rj4Tm@;MrltHg%r0moDoHjwSfgl}?o@g?-EqQivrT+XuhxtJs zFtGiPcE5&$#q4n834i;{Nk`ce(}ixq#Gws?MxlI%F?#Lo;i@@68->FOOK$GRg>;6% zhB5(5kBm8;MaL`Qf_uU!a{9Zg*KnnB%TRqZfdkE$doRHiExQhY@m0iG6Z%jDnJn~i z!~5>Y);cMc0=1KP4yK((<-yc&obO(8$Px6nI$V|yglbb#IPs{q7og61tD~FXKZMb# zoJtDgmiY{Foftt!4S}$5pYC9Bqp@`S=~D-1vo9a4`x7 z?^_x|73o`olMo_L7`B&Hj~70QhYO=s1wQ`9Adg(lFmi2Uu;*=6w9}aN30kH3eLaeK3kJNJ58S8ewA~Y)y!@o`3R8* zXWoemS|0t_I7V^yIH|B=LNu}zG01b5tYcRhCJ$CoFdG)n30&(pK91P33X^S9vr5;Q zyee>Gr_WW>^tFAbi$JgM$czJ5{woZ}I~tRjlqUT&v=1!+5Q z@j~%0V||9%y9kiIBv7fozg$#1&q#lV4O0XO~yQkSnv6YO^~duivsH?;oK0#mLa9Dh#6!{gaEjz!4a z@;ipG&kM)%kE)JZ6K|HTun*{8KUPoR$NemG>@d*|0S*M`337Mor%+4|tyxeVZcUkP zL3Mw_SvFz4YI6KWL?{BvkJjrhp?4U1?rTcNss1kx0@7TJfXZK70}Qi;=bE4_>L}|( zgt%(h5ac_B6uH(n{~n}#RmM^W-jzHNmXBi8M_ij-+*tY}u~p3XBxs3l(*8DBDaWja zWlpU)sCy2F^X8^f&gNd1x#rUekHjI>Mp{yC>c!7QfI=u^)fVtfErxyve7@}ta}szO zi|KDR9Zju(DunQAHqR7@yuLc-NqH3yisfn}{jMm&U78UFVGqXUeL&Gf!*3~IW0dfS z5|m8b$szJy>`TEa^->CQVMn^4ydmvS-SE}Bq2}8;lqReHQ9wF_Nsa@JDXqZTG zC%&`jDx?BGbw#Z({+>J|M|0jeM-}-gFUsil$B)V~pFprAQ1}p)Yxg3$-IY9}xdVyt zeoaU$`*JXv%O4J@3^M11^M!P=bE$ZJ*tx<~jiyP<3wrYvuD=^gwL3uh-3DHksR9Cc zMOCY)L;l(6Hkoic^)zq82ux?0~Vx$c`4erGMSTj=;eBuQ@ zZ$#NX_|6>miS}#QXIg13bH6z`SM}KRayztE)Mhdwecn5phy%osp|}Z~_M|ja^86lIEQZVn3hr z$`0q2vso!zy|pi;-q^c+8kgM?_GV$?itmxr?3U>-oOdX&lQRWc#Lcl0k4GJU`UPVY z(o_>d6-7zs!D2i9UM?M-zM7&5XJ+On-=C~D4TKYY_AxDk0woigSCh3wkesaQl8Doy zX@L)LceDuZ`8>jc?r15kp%8oB7#yL^;?R?qA_C)$iYw!eqcIQ>f15lQQ4+1_3M6U{ zq-kG0omi@zzy{;Hp`y}wlYXru4+vZ5qm)l|^i2K&c;4~~Kp(!JtxH23?`6L`BU6}Z zf2gbZ1H4G&Bu6z+D2@d0{0kLQe}d`{$%)d~f>*|S6OO>ANAIC8*U7_V zck%`2^`2?eQR}EEW7!?w5Ij83Xq^g_g*x2sDGd#WYeDt;py6g z`a+^L$7RkA!11$Qi!_++g*Bf*Q^fNgb^ozL8uUBh4Tm;2seMHG?FCc$3J}8il|i~M zmjR0NJq}kPh$*RKR#iA(PN{|j899_kp|-#->1g>p9*QshhVmR`9liwzg78Y4+*e^-#srCD<%UCpN$U%$Hryvq(>k8f>3wQd9u%>7 z1RQicf`i~Mzl=qcSbgr*8{m}#qA3u*PG?1uwF-FIu>2Mwb;+F@%i*-Ny>YO7EJPRJ z-k!KQTU53kM3bW%9@$bmNvvVa{V1Hlh~go>7mCYoO!*T-P+=GfN1eEy1+=!(t@Jk# zlQUdPMTf+$j^z|H;_cUr5qy&TVW<`no$EsTH6E0eo+XDo$1RonO^b7?MDRI|PZW_q zn=Q@}8%?^u3fG*K!nB=zjwBUuiB_11qdV=M7w4B>Hhu<=Jrd6s*r|h=G+;2vxV%>f zlkV8=XZP}kCxWsX^(lhHS6w48lk)IZN3tG$1tpD${}d{Px%YJR!kk``g0^DF-#(tq zL5U+BGBFR=qUr$_!1^q6 z36NVpj<&(MwfsGVGSN&nvzu7mhJSM}Rs=w;g{NT6uc+kR2dk(&6;Fb+wDxxUs>&P` zdkxi7mZ>nOqN5>?@~R|q^R}_#>-SIE31iU-r3|oaG`tl8tIGPB7!sRFVV_}5#r5Ky zg#OCYIub3#*HLW|*+3fm1yyx3;Xx%fW10u*6WK6&egJFvkn7?T+0W-tT89nVK1EY73##4@~W`Dp2Hf9A3dPZ zsc0n(cojvocv-+M{!u)~VGYj{4@f}`#?JSc6EN~;kY-23Qy~q(c$^b35XyJjvF!a3 zfwJ6N227RHBjAnezIwfTz7R9#kHFfU%EzFV#ff@Cv=HXLz}4MQcg}gum>68`XhZ2R zN_OdDWGE}il%mN`=`6eLk%5BMkG6yNJCRNUpVPn zJ#O3)Qjikh>;|fIh(MMqK$!w)!C2(U!1r=C4x);P=GwP@35S$&C@3SXhvhKIz=$+T zwkHRBnm6YbL!QCR{j9)1jv12dNW4_DA@26=PTL!tY+SJ2m z_GwoO%{Vff3sL;z$Y6@5Pn=7&c72697w9BTwgvAmGy`31IbETd>kq~8T&dxx(a#QK zMPyv{fOqY)h^E#sMwp>^0)t&fRZ;YOk-od;5 zN*(TQ=vIMFvIq_XXG0(ub>dBsqd}O8PLc?toYTO9Vyl3UVw{E>N1*b>WD=%G%sa)r z1tuUp^8YAwr;nE~^J!4o#2zH<5zTpEq`A}-hm&+&X3y3^x0e_kVR2+~#X5 zXw-@s$jISwb#&;na%M zd|4S5PS;)>2!dk`HDmd6#rVr;QBhyDn~3^~}QmtX9osfxQ^A_TLU2hvWx zCv9{xSIyiENc}ePaXrVH0H63c7hBlY+F7CUnSK5gkzX^0gOnXa0%beT{G%i7=8qfp z3u*Fr>fa5;Gu#gXs0)@1&HcQ}49&k&NW7>Cc12tDC#oz_zTDnryPOzwtO0e!c^hUj zt>wn=_w~iQDU)dhdRMCpBS`{%w*>0C*9u_bz7FWNB_0!*kMHyQ%+^PpU1>flIbB^UQg+ zDD`=OOHC@rd;0MRQJPP&*8azG)wqm?LMOc+cZb)4{`z#y1zw89Xw~0BGU88bm8*kS(2KD)p9V2kHlM;$UMcV@ewG@4QXeZ^AjlL>Mv$V%n7mwWJ@L2Ii3 zl-66)#zg#_yFc()#yXr?c9>~gSWAs@lDmH?RT3v^q?E}j-<5V^LpC4p6Ahb?`KO&~ zkz>?2I?hGzv~{_NT(510*}$lgRo=0)&Vu*5zdhLWV_A@ka#cTyIw!zIe)V$;N1y0} z(7~bi#`9qH?9w%9G-5ulcL`;VB#)qkio5liqoV(7Jpp1^|S z{43GvTNIHu^uF@!d(NtZ-?f!bfrb3vY67xdsaK1!lM&Uq2}e>kTZE-SRcah2jQ` zR$+cPEpWwsCMJQK~FWLILW zZRlEC=9%)v>u}{m3gt8v$>|fU`N>_4Sl7rm$Kt?5(y&0uB^!H6zxvIN zbTR@XcwkS>MuVU>>*7%KM}%H9(ZF#of6ioWBSS*N$uLdT=q6N$ApMeU}P=dt*JNB@|y2-srg0DHClxNG_nvsNd(Ws%pr) z3z}kDUe3fiI}MU(-qcakLheJwH1n2lcw>^#jJDB4;%;Te%+_MshnUK3p!jNj4xXf}QsFmKM zWut}gX)*91Lz}@-)h65Ojr`o-Ul>!MGgeTkutFje!N02PIXJX{t12%M8YULrsN@|) zg&S)0=D{Pmt`kVqHpPs!fbj%FFVd?(0yH??)~b~?l%SW-@klMV@B0fH=!W?-D59M! zml?D%uS9VH0QyrA{j}sad_X9fxtF+$n5M)vg0Gt!3tA4qP-J3nCz;2seiS^je zt7`x5w>}qN)hS4D8bzyh>+4YwZ=OL42D8XDXV-^0U@CjlP+9bDWx-+OMRsi2YLpmvk z5I0l{=JJyPk)zOGY#~2pv|gf>ODrGxG8-impmn9O>Z+|XlKXQ4su2&0&B+p1XiMNH zsamN#HLT4}>zq_CtNdzEBRI->@!}%&cO;G0&$NHy*8@v>>4E1d62ZiD~efTQX z?lPf+4D<;gKj!*noU&nu_X}g4zyWK*Yov4K#MG0S)6a zr2<_Xm_nro}>l$^Td!@D# zEnI5$sy0zOez#0Iyo_@2Y2_*5%ANNxuHP8yJAGLad^zoE2KK**T zoP_9|FY&l>2CH*Js2r|$5OG&e(1gA=VzTk<_oI*HvU*2B{H-SKoHX<%c{QND`Rhqs z_7l=z_9L2g1i$UVW0xD9;YBeX=Ue)dh)t4w$1<^5x{z^iMic9o@JeRku(gA(Gl@k} z^VQ>tC)*UD(Nm@pk7{HZ24%}<)A4aDx(N_>br1C2>_=V2_E=0@ZoOZaOr*#Msc|_? z#E=?>sL&M0$qqs`r&qwgHg zn2qb6b#GXV=Lp+3CE)rXw=LCePlI7FQy96G&3K&R;Y}8%n2l5_S!GwJ7Br3eO9oo& z3_Jc%!L44l-eu`Mm78|fjYf>L-#Nc)*6wD!HSBag4NN8+H86JW4TxgdaOzsVWwq{Q zF(jL}jW9)}Xu&|cc7~C_M>g*RYlbfm+8b%z``Nb;9RL(qb*L7B>`u*L*~DHms%?Mo z{zIVx5=5t1g}Y<6K@!$c+4Mb5Rg<=Rm1wT4I(f)^nQJ12PFRQk#DZ>(Vg3V^9-U!M zLZ0rI7#OS&TUQtpt$j=#s(v!~s=9k*O>>0-4Dsj2{ykh+5_1j6@n{)g5^enG>2&Rq z9XGzcAnY-7zh{Q0^MW*$DLYNKW&`_Gx&uNTxU6P3L^knlbD+I^0RZ zT`K3N5DZ)tNaWE%VgqKtrY#cCV-o!>*$eX#S_hV;jD8N=ct}g0twb>jO@LFdRK8pJ zoQIy9>dJ-D=4{1B3nJvZZv`Vmm`f#syX!{eS`;PhJjjZDXp&RFR%6{1Bu+<*5w$(xSu%9&IR0qvi=BAoiMFp&;-HI@w!sxawCV76fd zD>&&JE`<#0C}kq`t!qr`8q{l@cqBaTcuef%S@`_vt0Dd5gBa!Z5GT}r{+}oX%Xg%G zqc=Ho>|WzNS-FM$Ld+Sh%qPEpegT;e{hVwi=}OtsP=pU=m^PP4#Rs8{M9PoGOb`>{ zG>7&m%3&WMI-wloLcvwl`lm>z?|6Ygtdj#S{~Qb%T_J&Nuw7hr!6K`{)^Y=D*`GjW z2#6A^6tsI~N)0BApDa0QIDMDkLy5xPert38rAqO`{mo;V4&pf&X>@pNI%m-iQF<3& zDe@EsJu~3m@TQ!QLuHPRRN=bps6q@gcW)PXr7Gc;iS87tEZpA@)u(IHFWP$BLLW>X zqmJUiDZIR)$ejC^I&NUlvk4mL4G5xsYSKjfFH!TE)#GSAU%oUde|Pr5b_16xYplhg zMI#(+H|ERPJZct6j2ILMDQMUEGyL5BC}zL$XRvs_QFI=Cpm9NtoD*^>tkQ^U+xqA> z7a>B8V(zGY)4P?o0H$kGVrS}m7(VxCe<64m+lx>FM*JH!7`b-}LDgRZOC@iV7J+?+4c zhc>aR0<5paOERY(!Dr-#OyCDN(p9ZM@G!u3pfp6u^_Tc3o`_a0qM_a~tk8ffg!j-| zF6&$&Jv<+c+g#yvKC{ce(R@K{0|ZW$_>4}Iwi7}57dY)7rK-73=SyO0V3E9sU#wAY;MkCuDiQipc9-iP~7DnJg8P$cTE^rntg1TDZ=o!A|^;!uz} z#kg#6AbacelXhAt$d7!dNsEyDJPJ_!3+I(V1WD@k0ip@7YE=rN39D4LnmE4y!b+H= z-q){_*c>AVR~VdM$))?}5wZ#;HDkMq$LC06Yrs>&35@t)>xtGxsltpf@d^&)2_H}S z^7DBe6x&BHP;ovj|M%AUw-n4~2!!0Dx1_D62t@cY$3VX~SRx`e)9`uFuJ>*`*aj0e z)42W7TBi0$TmLEB>0LfgS6N0ArqZ~5(bA-IdSo;ECGP_JC5|Exfa6&NuxCOH@FrqMgRv_xj3}UI# zc?;G_bmb0o zmHk(2-|^3cq<0K%V5#wHxERyVcCM%=F@Ygr&k7iuTxvO}U!J};g8~$nf8(62)?{Pk@{(1LNl_m)wm~%&5*|Q&Hb33fKbdF zprmHw3w$D;QBX0pJ3M5f3iA^lV3PYpZ607^>5AuUf-cGv7$hZsrxsM=f(~QuGw^b{ z+~^LGp#sz+WD<4#3RjUKZ{AEeWTm<4CR9>&T8+amj`wKfI8E4LdyT;DFOi1y@bvf6it`euwDZj*%ph8bAk+=y>m_1bFxG2VfEG z=UiTnV;zeb06ft7p*d8#GM>iggCfA3D?kq0YRYjzR}%A z6he$JI{`k)$vlW+3_=V`6FpCnSV^+ZuA8HR>ln-=*RAb*e$>AxnNAZ?Y0Ya5+p*eM zH)GKvX@MlIJdSBzj-ie{@GT77;P8-x`uuqfTPy`lTd0m|RNP>B56j4eXIGIy8jJ#Q&gN> zO5ejzc#ftMRDtKek*u87hY4$)B7-JFd~B}qVd3_Jd~AFibRwdS#>lUk=)A6{>$|d@ z^_#~35xC*#F}rhBnqU#;!z5f)qkB#N<-{WF3#)cUBfVTt5j|Z`C8i1n>x>BSI^Z96 z=j<}TBSu5L9Hmgrlk#<#65tZRAI9eBGe-UF`w^}Raqt=q39viuqtT85_> zQ~Lvx{{R-n6v$v=ii1)I$e>9d8fM2=Lmks)`oO@Xub1xW@nkTocI}$Oq#1J#E(7A* zrZfJ!oQC6+`y1?(>)n-6%V(!~GarL%<&l$-W;OOcRppUU{#p@|0H-!G#ycnhM%Mg& z9h0qkXqb5;2_0KDx{=Xp6%_2Wx%k`(D3UAO{2o;DL*3ke0;B&gaLQk+ii90B7uU7q zm^={S)F!|rC_Hk?$EA;f)hp@&i&x5T2u=v5eS?O1oBG6Zn5OO`*{HnkZSt}0Kzcjd zOd_Bw)AL$rp}LEVt6dkfJGSFQfS#2avlCmxFQFXkZ>8<8dmwAa=exV58V`5YnUv$K zE+5QH`2BXF(|k@jS?jFQlI5WL6!nWJvBQPN19z0MtgP+hQas!#B!#0X{S)YXW;mx` z*St*Pn*6Vh7fF@+ma)$O3Q8GY1c;%UUdm{sfviudH4rI7PL09GZcDCoP{CMdiymt~ z>EF&79_@Mb(py=}Io;G{ea-&k%r43+>0kA*W!xgttnP{Dm2fzmr?mwM4* z2VTffeG{Dpn2S!!lGXxep3+5k6(;rL9(-@KSOjqV&@S3rU@^8^zXEsU{Ivb!@fn22u@O_HxOnRki6+ z(mvJ+$5uIEa)+fHbkmIJ-$WRtIPD2khL!_OuM+FTWb~0I0ezsepMw=Zu--MlgL_<{ zwJt{SUlgV3qn}f&SHD0V{x6!LkJh_!FfDpw8vW>)6r%`w1fCogoI1assNZDCKYzdz zoQ?{0ssGc2^0uV7;K*9z6qi7uHxCdNR>Y>nX!$}DQirtTGB6yg!nbi&tD2vr6iB-O zlyZ%J1OFZQlKZcPai7&n%(P24o@$)HQ@i%60#8M*mVg=IsmT7SSAxw*EMju#+_dp@ zIJgh$%D6!(t8!)Bpm53;oH}p~(>QSI(CuCUr;Zzy;n<+=OkM|0Md7LoWD$9RsbU0{ zI=W6pIF@QfYA!IuOX7-67)h{sG z=nGZ#CmdDf8`42l`Hg&|s%%9*s481|4s5X>%@0$lB9kpX$4qS`4(&sAaf%Xu3{{2H z<#|w5D1h~qax;?d`*l=x*ye_#s)K`gqpFziX9lVYxx8|2wtx&<@Q$i7OSvCZ)kN&4 z5PspRJS=m=s`w0M$e}%^PuIZy2E)M{R>k@OIOE_UXb6GBi$-6tYCK`EDpz1RuqtTn z`Z}(PueNhwi;bH7;HuEa%VAP#Y;cee;jk%3uO3?czHn6x=g0?F#j>yGz!nF$+^{M} z6C2A8t3oX>ame~@^aZQN6E<@31`X}`f(^Yl;mnnq_&s+ws2Y|mKvm;7sA`5RK-Dm0 z0jioQ3&_+=*`Y(@21lkWKvi2!0jjzw3ry8aSzxMW$^ugz2dptn)l6Ans%EOJ*I~&V zQMEripz4;)0M%p298q;c=7_2rGDB349dkt0?U;e8ZpIu`J!Z^7RWoCbn7SDYItKM{ zWX2p*bu;Fe>ak;nsk#|+P}R+tqpHV@IjZV*%u!Vrm2X+PQPpF`3|4g`=D4aGF~e1l z4Rc)8ZJ6PkZo*hZGR&7Dqi($%I5qQiNVi|XF$3nmH~Ynxhwbt&o9S|7)lHWptH*TB zkV=^@hgQung%G;s3TV|IaA?&mmqV*zxB^-=!xhk~8LogPyXmQy+n#V~h@` zDDB6fRWn=xt%l(WXw?i?K&xiB0$L5j70{{~u7Fm}as{*+mMfrDvs@0Xx>$XSouAnv z8oA})4s3}`yi%E`P^e;Xlb?#oB>GOeB^cnOjwMiL21#8TGCAvB- z05HHN)E2L`N3_NJ(4gpwPPwR>P_u0ghNc`Q+?3l1Y{?Q+aeA!edKJJKZ^QrY`v}aChL}2P7p_~@j5g=p~5xse9_Ht(8DQ0 zbXmo0G(7yIF z27!nF!OaNOC^m%=Bnu((2w<{tTT$qVe$g=GLVlA_K9rDI&0H~U=k#RWqMb2ZEMVg* z4LAg)rt6NfGicR7J^)R#p9e~Ef0A2ym>0&SJf+wTJSW)2Q@@sB*Q^h=hhX$D!1Zuw zl6bnyqhYKzmd&QxwEP4v4r&<;z>>5~=~--Sl&-tg;g(b{TBK+zg*XxNfh-enE3Csr ztFBLE^R%IPXSO6h#bcQ_wP18T*eVhqf?iy_px%Fe;YL`N z6EV)`;w&EJ^jmW>Z_(rBC#jfko}2a(RGHT~Nb%%BOJ`uiWAU?k<)QUac#*oG?KHzV zM3LvspbH1bUALL=TqP6lRrpltr8+>XD!EKK=Dw;fCxL{qS*$QtXglqA>*7`kV#R9r zKM`QvpCj@L6>9YFU%U{#=HQ@eHQ>@>wIXnJE9>u7xt70wwV`W9_(5GDUfQa*zms1) z8p;}I&CYPc3uP%doG-_TR@4)L;zw_1Bdm$(syde2R_Y0xlN zUe?5`ep$AU+mj1b!jp~GqbqW7%NGp24xc$arPYJc9(tg70pybVFopMV@UXW>GO#B+ zypK@7v%qwPEd`B}yVzvB>HUjGw<29nR89xhEN(P_m|)|gHR1LMpn>GGEaG=aYi<& z%vK3$Sw+W2pk^-(oJ5C^;@&)6f74WDZ>a=~ll`qbih_d(kJkD!ZH;FQDh`Jur8LCV;o| z(1<1)SytK~+Au_)L(3VxwOmqha_7JrS0-Y}(?it2qMmj>0H#t`diub-wr4&;JEV1k zdRiQKBRWDJoS~{Ak9`!`H?)TEtW}sn{uq4sqKKGFIH_zq9cUJXd_OF-h?{+rTmapc zRG968{#oS*4Y%7gr+@!7Aw0y6Gha9^F|{S|=i+2rEJ;OJai4DEbuPSI3>)*RZ;ulf z5MS(hLYYFuSW2M}#+mCey@fm6SVEsScc8P_)7;~QDhK!$vck}2ek!QFbfC_#E9`$y zx}u32maLqy^#(?}D-X$x2o^A|3g@loyci5kLXA#@(JalRK-r??*Zb^c|ENhecU~ z`v+4783`+_-C%d>BEO}u<{t#Gyp$A(k?l*%0clmx^w^k2$B}l0`kWeBr}j+Pb@0wX zTM+{C_k~xIvq(0+pyH*jK+p!viO)WhYWg_xfg5B-H+8|GRm>Oy2K&YHoZlh{FCNhw zMJB{DIJ~u2mnG79S}JY}Y?KxP=fwzb%_*JDtf;kg6%_|FaYgYyXk4vp^cJ(Cdkf=< zM}7m|fI(!%pE^nFqAZ9Ryc>Q41zL)R3mHT#)0cED0b2FYaVM@1cN<1d9#m%4SY8^* z3i@2d7%QeNz~zG6EmZ_*zI5oYumZXL{;_gIG~Lh~@KxK=WpdCHEWBSXI^;4ql@2&$ zpBe=!K=+3{^x@_sPX>0IN_R{N?lPBcs8nur8@uO}WGwU-(b52lPJY<#`fZb)8SL+^q%ab;_c3vtbJAZf-R1?my8!Wpb5JE4To3tQ3blI zm^Vi65kW(uO2S2_j4g2-maBCvJ6Yy3n(4m(lv#u;D5irEtywu)e=u}h9?tn34pU7( zF&lr;nP6*^ny;CAa+NhpwgBdCSIky(s4E<7pg=m#R{?rKZmPU9ry2Yhr*JE7f3eyZ z|K?c1z^m1NbK+Oi#N=?W^NCgJ928Z8tb*pTcx(yt%hjZLO$9}@=o%#(4 z$CZO49r6At?pOl2IE62PZ#S`Z%>?@G_Bv-~U3XfMo}`NycsoSxLejT77;>(0Jv!?% z!mY)3hDtKw9uVYZr%l?@ljr zl8mJN(^T5uyLEY}@_)A*j`4a)9PXxn^nF%sTvEbS+3bh(no_~R^(VN#(|+HTmY0h@ zvlbl1@zCI$1RUkrgC5G2cTl+r=Mzh=JvQFqj8;GbyZgAH4C7Om?meJyPtjX%LMpU% z?Get8#y1{FpvC14GN2`kMC92huD(->|a|0|QkEX=~mIY|ufBS2@-M7d5Ijgy=!6=C&@lZHlFNR9KVR zfS(X(fYrWMHiV3F-c^JU`7(@Na6QtX$TR>XSge^4Cih$t)@w!_jeRPi05UBWBop`*wVtj+({hEcSn@?H&z??+IP|Fb3*P!e zl~C!VJm_HMRrOQT127QA13M&G3RnV_X?46oNqTXqrmp;1h$+kwT&Mk@ycRQG6K8u6 z%!J7s2DBcN7aUyRww2=Oy80Lf3SSwrT$M)?k}xebi$$P$Gx?$iv44r!3*FUNyM39J zunopmml|V)W8i;G&Fw-rY%0}yxzNrzu4m(cjD9)I|KjLI7W1Q9HVbEtbi<9?6km6w z8*qDU+sTn`d9t90yUk7?N4haTY+i2jKR8tzkyqRQ=ESeu13esfq@ClAH0Yr#^&WjW z8`$rTbi>Bp_|b>sezbGkk8V|267ENXPBmSAG{#u#lWsIVtCCgpqR|ui_wGeEMEvSyh^bR88xF-`P!S+pVGI#?}YC3ed1Jj`%pey$xR)#`(Z)?C=|$ z(@YV7rq8qFUN^X91km9g>lamilS_Sjx!G|lJ{grTMx&3W1Q&i zXatI4JcftuF=A$MIGRx9xWLuvnN7B0PK@*UYnE76rV62KUHHSFUpNj|I3nU8jQ~*} zXu@HSk8!n|jIu#Rjh6)?7YesL$z)}W{XU?f4`po>8yWbaX-jkAQ4{qL( zvN31i=H1R`I4;^B$6g&dZ77&LXW-@y&UhVxo44h+m^p6VCiiw#`-*EGeEuU2bH}9~8 zU$}WkS`2QYG2Fakw+L5GaA=)6xVdv2H|Ot54%{4H=uFsl&D4u+Fx%{-jqol*KHz{1 z*DRDE9F01-Ifg+c0l!7?#?6md9?oRM?YMc*IhhH|ICz2;3Y~$kO=+Afr{-bUL_sM`5s112;!MXaar z5h%BYn)k=R5brdCJ??uEHE+xlSb>^@=2Z)Znm70sTw0ErH>=#}usLWbQ=d7f4{Yun zhs{AlIvh5~H?#KclYezF7vEv?ZpeV+=2-8Ihe8}T?<{?g!_mYzL1X-s+1t_4ttIJl zbe!|KI0`S_Y~xZJw8#xR3WEz8chirnQfS=GHQ24v8+?fxeHd=s1pRgq|W8JaqZt8lBN` z*9bSOKudgnIrMdL9_9bw?h9m9G**Jwr9X^~y25Wkpi3ifH9e9_Ie z3xk7$yPf-}4B>fE0o_yq7q|;Sm$YEKs@wb52-sl5mJLdy2W>SQ6cz7V`iA0s6iR>!?dE2_92K()W`kdG~uk}e5LP+@`a^Ot|W<%g&Y>fkenEKl2YnF|3 z&9ZS~sPMTf)WHP?s!|-I-K%4enhk_0ZC&(aUhy@{#`*lEn?Bbj2eOngf@hP%Iljrk ziz;&LaUhK~Go8ctICyXf7q8eJ$4DwE<9i%~l`+e;$1$=B6ZobE@?4Q55#&&LYnKaS zoE;8h_yz|KLv)%}Mf}W+CETM84kX;ufwm2f!OgrD8yq}e#xME?2ajU(V?@#7=i2em zajM&>B4s$yhxbt!?6q%bV3by0*A@r!mTT;A_z!%C1H))K-F7&TgN$o_g#YlsNm{W% z;Plz!h$n1^fxpKhvONfVL2$2aQVd>D+GAG(NzGhTL05WyXP1MgVz~J21<9^h^DjJx zO+_0X-J2C{d@QTddtvn1=Wvd1bTETF<=E(8g1D@ZZFDdU_n&#~aZsa;?t2_mU{8rX4jv2$n~oI+g~h@V7GvRr zknT}&y3l1mz#q=#t+U4gWuT(bG8Q~#VFRW9;Go8oJ4{oH#Z4U0_Be3#W2S!Xalmvu zIrcc*vi!6?_a29<$+O4d9NXidPD-)GfweBX=X)H3RZ?P01FL^3%ggAhvqXo{89(_B z2ebilczuThhp)yOXNQB4N_684x_2Szb=)z)A8sFZa&4r;fR1=epN%!rIV_a-|1I7qfA=&;$4Em30xkDWs z&Pyyx?oNnvJ{KoP5KndAb(5MqIs+EH-=WU%987bS1~H!#>NrghjHtPDKEIH|&lPAK z9+pXZg7=XdID~Huojyp)NCzkJxRsLX(Jm$*S(5AM%~FZWqZ1712~)l;Zx%h}rRzaI z7J~RGiZeQ}KnOm@=&B_ioePHdUW^!=F?3Ug4-tNqUsV&=2EQ)5F^8u%7?@Sz4&>EtltPed|XXN*$I5M&4${I4B=v3lI;uOlp`GaXbY&q6*Hy z(9(0YV>p-`*)gO^Llt8Ji%{5p%{SICH-L;L48#aHo-kk-FMv@29-u})c3EaaIFleN ziIam7LiB-VKT1KN=Y(zzE<}vjq@?IBTlePXHphs<5A6bQI7>lf5d=D$A#zRV^u#@{ z3`|=V9zD@u?%QVh?#75W0>8b#3CM&d;BXc-k~m&`i7%K~$y7 zua6o{Az0A$@xfKLo=s?aq-*CJ*>x~6oUO44{=)&2 zOikz!egKgq#|>72Z$vOTsF^xIz}a{PJcTT)BFWq!=NOPc_A^Z2aI3to? zne=V?@~73k(@G|;-2KYTcFsw}nAjb9>Xk(D56)0MNlPo4W8CT4b3U(=Q8K531QXz` zpn0_2(npLu`6LtdQRqN;2>mx_A#i!x)#$%D=U1MIaX6k&;vCN>0gVOj`6LrN0^QQ# zCDYh1;vHyal$Nf@JanO=JqaZfft!M7;!AU>+^lDm%oUN3`v^RL7YQZnQ6&fOhSMjZ z#5tdfQwX-4gp$MYgc9d?LJ8<3=b5hYvh{HiN-)T}>P8tQ_^zT~rIes6J<A9|T zgcm>cqObV(?(U zd&LV#S2=$3A~M#luw&t@!Wt2FtjrVL?wA{S_E(H?@<@!~X(V_bbe5-)EL`O^%mV2L zNhK0O{IOZwZ@StEoLDl(IeR6GSKwX >4~$cS!QNs$-`xLf&(9~RPq=E0d4Vyav& zdYB1`$uQ36=k(lJB#T$Ol`D(HIi5wbth}aYkzl}{qFVsuXD_>-+ml2v;_&AWT`j}q zaCFVKr;+R!nYPQ*NLIGJRL>$=NR8tOMWvB|<{=$RBf)5vX(uk#G5i#VaFj-Z@nsz8 z{Wkifk;D^9;lS^4V%AbT@Ije2PXb{Zd4x+F(C8B!;6r<_4@cv2-k@m`5#m^RPDl1wjOyMoT21~*2rsa^e62#Ge;=D+oXd*T zVmEfhviX}6zd|LSi{$b9>j9J*r?b;^?u#xT6@N8<0ze$WpT^1tkQ^RZUrIB1sTeYL zdi?Yf%03aGgyY0};}DnOiN=hTY#8%`W2viLnk|{3s1W&gOo+sGIm*rj-EC{;aFp7^ z0@*l@Gam+`_y*3s&P@Ljb+V8h0}H1VBNXDvycilsx*+wu(Q^*lC&^tn6YfWYbjAk( zik%kfrqX=1h<7&PBEqKlp7-gYWMNk|LEMjMWz@EzAPkEm$}0wT(^@fDfOM5a)B9lL z8&5Rhaino_Ry7v*LKQI?IyKFUB_Z#K+J&;RxYk8it15puyy@q9LuQ@n^Npk;mRBQG zT+14Xdq{O|T-|V*025tv=ST%ry+JhLB;9@~f$BDPJd=`bUyeV(#UDm5Rv6OV9L^cM z%Xa!?Hu{LFYoB;e;j*LNc9kkm_ZOjTix<5Vjx+HPY+W})=7>_@LQS6jU)q=f&HVYK zst-nmlTJPkKe{s6bGq|3_8P$2xK^6)!e_^BxCv`52bXg|n>AmNA zo)Pj~&!ah+k#`MQFhct-J4vIDc1>?It7l7GiiUTcmW_@f0cf_1)}0KO?_iwIUv>q~ z!%^3Z_{^V6OuRc%;D-cY23OfQuz@^MnW-6}-znK}Lx-*C3E%*lk%eo3O<-t;itdHR zHyWjn&L5Mx4MQdWP$Plv{q)lS&{{kxiA05mnp7qgWhb=MOtTi-Fq8+9&o6wfx+)L4 z*@=?F$@D?+26{h3={ooZ#{|2wRx{AnV{aOzY(}fIYC6I=`mpeAn>jCXsJae*Vm}Lx zmCsBpXrq7sHFuxOchH@xcPS+2d@fE>62HloE(0DReY~Z)+>3%&xvmbKpP$R`*C^ll_2G$Wk>NE+&UvWYSSq39@$a6Hup}B+6>%C`#P^LyzJwmt<37- zROZoma@3}Gha)$Nm;EyB)N`YF;dGyo8^zm!SBu;zr%%?5bB;oC&Y5xMKwdJ@#=G3n z3~#4hm&PU*b<{(%1B&3F(?o25vW9B!<^) zlJogX8QryIcC^XLxqmLs+zVWrEO9eSyb<;CF5cdfXXELP8B^=}9XkS1C> zPvA)yWToh_EZ3%yP>x12e%*9e;bTLRH)AsW%P#RrkMg3LtZ_=|iTp9e2;g9+iy0rJ zaS=RrzL+E8H21~^ht{9y@@@HsmA+{P5y5$eUB8XII9{O?oXKNaIXE+n1HdoVRUl}z z`<35caGeD0V3m}^kuDl}GB;MaIY7?|uj>|dX_T1rHGT6TVT_{3d5iYmXdC^foj9c zgUT-!9(b~7;Ngc}>h|GiLO$P|J!SYR%RKO)`Q|=UlP5UA=y7c!~ioxcvT&$-Uq*UE|<-LSS=QvM}!RFvkkz=rF zE(y;uaQfsJILC7g_y%rnYj2R>psVUR2AjiMFD%DklQ^a2IRL5PchgeFZlBmgH4;$;VA|jxw<07fMbhPGD|Vw?C3;}r5JDquN(uPanCVu`s5hI z6OVr*EqX$hW591(#&?mn&%FH8Qw-Sbr$>qbyX6Jbm}0O;f|q!OjZ1~~f-l+x;BYF{ zk*64J8dqI;hQTJg){AfVZ_fHoF>ucHO7-ie=a=bCxWKqvIR@m+{yOi(_0T8DfONL5 zO5NiW$VoCFjcp7|GI07N893)8892u?2K13H`jJC?INte-1Ficy@2t#2IA0ZgvJB#h zCk7OrZ)6#8J-B~cY|Rx8hUE}w&hkYQ{(YS+1J3(1Bg=qtaitkha;BBBk@u76!g`j$ zCV9iFXBjwsvJB#hehFt9k!7%HoL7FGECXtzo+8VDjoLcUvkbV5?=%DUlXt*0W*z{rzjU<^+(;LqW2 zTap1kFwNhVt!})Z$CC^wV=F}aC1u;2TsacS=qr|I&nr{V1sckw81!M;zu`8G0_-Pn^#A8wr_M! z)@|A3-BuS}f4~jKx!{J3jDRns^B)`@F}q||*WI6n^=4sWG=1BPb;~RaAAq&8kPa?!<=c1$TbpT88-7pBC!Ny?2W z@ur}cADU0RX}!m>`b}GUpdY;7-uFbyt?EL`+HCcz3kkLViH~{Jg_K!iHOemFoHKC{ zhT~41vJ3HdE4#qo*AZnG67DPOciDx6%faR;SDbL27<@k~yRhkQzVvVf1EV~m>;k*l zPPyX58o(;my1;Jq6p#qV z%BpA+5#epVDT*#|7+7=2f3LwjWfv0fUhfAp;pHFsrd=uzCt(V`>;l(+&rx@Qa^CK0 z#Z(E9TdTW}PzZhA{eH663hOR#DdGIN)m_;19^xpwuvgx)K)}i_kkd}JV$$Ulns)k> zU2u+ZQl!|HwcdhZm$5XlGWS+Ac$d#5AuQszEx zSI{`0n?olo6n#Nj`Q-}YwuN!$Bk{uVa*_fQZfsyik*`tFmn&$T%M~o!{I?t zya)N?s`#y`4TCSwurP`>SCAE7P`kWNVd`jSgLIJSG9F$a`nzy#^zh3b1xFb(%wDIcKP{FbOn; zp5Ks>!Iemg<#XqgCJTLpCTB9(5DpQ%mv1JSHQ&E25O3#463oxHMMIi%(Lk*AJQfX9 zLp{t#@ZP_HyQqyY*Rf{cFY{P4B%f=BH0PQjO|BWJ8L*Bu1J8I{G8SiEt{IERqg*rA zBdjCW4ER>gHDXxXq!D*E3l$=t{JI`(<7=b)F)4msLRmv@Q5-FZ$vFG z&FklLg#f91EvFo--`2pZ!o#BGbA6b`qmyKPY)!I~r2gD|Y}PJZS?n&S4T#xk-@^k% z=M<>PVN2`>;!tvk&FjUX@h8X$Ua{j37N=s<*Jj@(YZPJX)_&1C8MZD#4oiwMFAg9Y zS58&gcYqv_3k>a(sjL%CEva2?7qLP(Pf!m-|WKN2ViS>0G5?+ z4GsaUV_8*Bw=EU6dC4|?aUBgTyhlHl+=}8p_c@l9J;+J+w zRq}J6fH9!waRRn{cC<8SM@y59MShf{IZ=jeymd5un@6AwC&fDDN9XRNTOXafQ=>!J z*{#28?g+^7b5S#Q9&d(9bMvjEZ@MA!+iu!A`Sp^|j+W-|bXc=J9gyoL6)GqOKpS>@ zI`A6LI{Nj#?Vqw-md<;JrZVaw`WdAL>(S4^x9_)pM$B%E_)`TlJeJz0fbb`%)04_2Yj1glU1C39b! zR;YkT`Z{Ta3OJqX+O$FiOyD>+npWr~dl?N{p+a`@vU!9G>CNjQzj|T4#Z_68%tE0F zY9Y#G0#xc(0m=GNJE4$dy>4ou0*dwL-qb<`oa*hYolwB3K9jGnfPfxDCFSdLp65nV z{r24oH@&YW5n?N8yV@GkPHbMGxMN$A1P;rBvIIp|Pbg#ouZKJhJ|CJvt2}-HY-`5@Kq13fzFz^*Qvb+ToGk5~A0at; zg+dd&Lj29SHm?xh=`kamB1Z5PM<^7??0fPIWyhuB`4s)9dIDoXRVt&WmyW){EA$#& zH&1fr6?(}+0n97(l81`CidX0*vjBAP3Y8}BO%Mx(oXkR@Not|c1h>#@{kmLFNYM|F zhj#~^W*Q$gf3#GP57LWSh%YqJaSsZ5Auw6Z?zBguvM zgh#?(B? zg}A1*7UV)4hKv*wxe$lxI?08&WIab*6U#niMFlR!?LI+B7XA?AC|ha~InQlmDGV*h zg*e|wk_&M**0srnit6HgB)L#Qy^^^$yHM;fKlh-MT_{$|WETpJ*@gICV$mkO5U0Fy zFHA3_wXbIIPnC!Jke9>CLW9;4UoHuTv@G;ZFjP=qq#p!B+_&1=1VikgQZ~U5_aLs| zK`_J~edZ<@id`%ihH~c%MxosKQUhDy-W)@GEig-oV~Aftu)x_u+JF0|7-E;VvMGjg zpE1P{+jh;M7}_oWqi^2adX4F)=Ly}K?^AWz15W%>Pa6^y0Y;|J6!7S` zJ8ekINih_fq!O>wlP>?3P-i!|TAb<~;Q&5pRwG6A891aHdo-U;4pw96d+0$JEqbtiPQ z*?T$Vu4C4r8Q6{^!TTixA&va*f+7fS3Er=dxtOTw1aHc-?*wl)s4}n-cf=;lX_H`$+kXxK2vFR|fsHHXE(0Eixv!*cx$jd~B9Q6Q( zqH;S=P@r7r+M60=X{~q7^GQE8zqS_?xPz!p2UCBkr|-O9!*;dyI#7L+*xd1EU_2M= zZ}Dyi&htr%Sy@$`WyD~43pyj6_|S=@(XM9Q1n@5#=<1}{z-d&;0G1h-CkZp?gsvKV_$C8*4G&8uH7&Yv@Q>PGKxy$5-66uo;l)&xqEbu?hnI zMcsDQWYSRwT5ZEd&USFRudJO` z$k<*p=?MJnM1XhFQAd>cok>T%vP$btI%6*b;|4WEL>Ya zrq48VryO;gSaCvS^ZNv{zbnR7%|{paJzIRX#=JkH)2>&l%xmyx%WBMgD(E$0aBO`q*fIc&%&*S8FX(d|PwUTU0Y z?ty5wyakDpR&Ugw_Re*kvqT^E;@7SaFLqf^&X8XLOq?z z*oNYigE>A(U=%)1j<)+&^2MHZ{DGenldiks9hqYm&VlO4M6ioLBydqs1m`N-hZCN4 z0-PC3@*|FE@wCe?2P*NWpYkxOyfsL^;A(t~@s-{|5O33E6YfI{Cl#;NelW(yIqY7CQp3@q9cpSk8K4nDRT{ZnvzH}dsTHe6!URd2Sjp*+9Kr7*&xtK6B_W5Mv4(%0mO4}1MDpc zhUEo1Hi$@7vF1o#8H~X=Q(pd{*>^?i%pWv;$pMs4|6LPzz1|T_jIU1opI_ISQYe^9_SY|rAx;Zek99S?%F8%g;JG>81=JMBiDPjUTt{2uA5k- zTISL3BHKRYs_5894v`MmGY!I0iQe?eP<4pl4FowDJ_s^uOTAJXD>U^?k}In|K5oqNqH(HD1A`9Mt>}K!nAE z9Ai58^Zqj$8PC7;ysj+2NuFZLq7zmHIV!+CeyMaH!(!uc1(4!h z|1S+}>YIsN5-Ir+Kd(*OqZdvwtM6fLC++7Z$0U{m4fr-Kq3#zC&Y^(tuzutyAvqwbZ~7 z#b2z;y$IH9_;)y8%lce?rN+^AU+RPYDN8-L2V88$vU&~N(CqnQo_qDfjU|P@$VW)l zM}WgNuPFY^o6cWWQi!2NPaFpqPoejvk;j2lh}~jjYL1q!Xpeb6(U}Y@nx@EQJA*jD zB)S~!a)FsBsImY}SBClY_d9jl(ZjYgtc zBNngMCoxi)B`EKdv3cF`(bf#oJRsSGJIG>|0c7sKbVNUX2K@o3Aq!#?6bWSv0?OLf zQ@*_ZZw-wN{-$7_$*4qhh1|K4HKGLN#uX1Ug&REw>}|ROUXS3_Jsj+)RKPjGgkroi zizW1PG6p_`KD$PUGP2ia)bh%_mqX9tZCAX zdXdtYnyNeO*q-d(Q@(24VU7OGhz6c4DARWUd3tRSP&65~#+iOoro)NlL7T{|IU>{K`7g#?T7(2X&tM|8SQF$tzOdzA8ElGUSEaOW2d@zKyAx$}=3#Ugt92}r>Wz@}tXJ%e1Cda1N zM7vr{8%C?oO9kF{XI&d}i|zynGtVn-mR`~?z!WOl4V&DvxTAaueV;t+9mXAfl0VHq zGVRlkY?N%0k*2A@ZD>%bK{#6xt3k}B5qlD>l4*1qgP^J?C$YRsGP73zSnAX0MmHjP zsbm2ce87nq6e(9<9->U+Lql#6{-B0BQ`e^Jm~q+a+RD2Me`8rev+hv6N3859wkkw;26+(nxkfm@i#Kt!F1W8$NQJFWKCLbLB$0}Xd>qA77M}XTcM_ny z9MZ?PE*?cUKhuK@Wf#;8jDMJ6&jAl@2F_tcbd{?nE{>1rRps`8f@@fI)i~GO=PFl!L zV59>gJ&GI0D;~;U;1n-QqWjGe%B*Ero@tg~)An?!KNJ!GNJ0^nH>=Wz=9|mkqdr{3 zP#RGKn=6v*EEEzKo#xgTzMwW0CV=1IXsFQ6A68@Cqpukyc8U zQ%TGFjC8j5T<`mPf7f~bn7QYBf0xhw-R^s?=bCxOQ8iy)?Wrs){-8b6eXlQ0@IFQ` z_FRdN}G1c~@MZkmK83q#L94h(9h>F`IcDbUWf+ zb7%5l?e&&9Ct-yTx8w0SyO*k7IoCZP2`pXA>SJ(=5Mc}9Oa zVCLr@jpbhQ8T(QLo+xLS%t}^Nln33o=@jPAe`J2l%7{fXjLayGQ9Qjq>$K#MLSo#- zmd4#B`?Ln~=U)HZsH%WJahJ1JK(6*kd|Z0KVE%Z)W62F8$Fc5r>2zznZebFXUHr?og0RSC8LKJK>X_KO6vAgZ z36YM~=$T5FA2BX_W^SuLR2EYGj}epiYRP{3kF!$opJJ|ej1H?nt0A@bspQT*t2}DG(;>EGU z7akv1$$aRzm)Z7{T;+vpH#_VSdwCZ|P_mN}d0gN5q}IHT8g6T^b>*nawoF|cX(%Zo zJl3;M!Cg&vuQ@hc(^^^ogmz<|?WaS@(VaMQ<#C3cpk61W-f5@PCFSd95_(sW;%B|@ zwwB(0f< zdlWdGKAe0!EXuqIk-UY_oMhW6wXVjuyP>JEuJ7z?|IE5^SKV!&YRnJ+ylM(KKwMqm zKAW=9hczX`w3d1?`LJNGW81o)-fDjI*>CE)y5(isxl04?^Cy zo-2Fzkqnp5sjrZucG^7$@}Eh_Q4>O_Ne0VTNvR}DW?NV!Wj{OIC6<)a?1zSsYu*QS z1gokf+o#5-2gyEp$>FUzHlV1+vhASwluG||f@(0OdXI+Bp6nlj2=u}v`z6ef+qTP! z8mq{UELk5F4&zPIXnNsY600@8Te;P(A?e^S6kWMu&)k;iO2nM9lsaoPm>%6Vy}c=E z9%xQ_FGHJaSmr&&8h8&D#BRs~yStw1a$Vl`R`wpXq@JqI$pJN{WeJT^o2;!&^em}k zYTf^=*TmhazD(MZ=2Q1})0XA=PrNe~c6{D)gtwD%B)h&#L8}FqykA8tS#sPZF_C`C zCw0AJQ*ZWJVRLf(@bMLjH9G2*5!6|3VM51T+}I|PWAL0_1XZ|n|E_n>WyiF+dCsHT zi<76Kl9DHG!`9XPlLtVCqVng~6?bx5YBCf@FLahuaoHLrWXn1i$^Byzz?n1Sjy`L8mp)mGir|){c>6Ua-w*t-B~R?J>k<}Dt28`4arEK7>w?cqS04P(?x~d|%G+{mziCZ%S%2Nk?&Ho0 zOwnC^ch$|TE9Hutt(&W@0X>7>WI#{NZfE-1Vq~S^QWqstggxUe1d8T?jiQetX<$k^ zCQ?$TT$Vi_eL-UK!&HxUoD>lHY&w34s88B?xqM&55)mlmb1v>_8bGk*Ef}w+zn6CQ zgm1JGojolJy%d$olTK|*^|`9^gG$PKH5JhYX%Ej=O3TZ$$+H99nTP<^&_qi@LbU?TUzTbqy64De2c{@I zX?zc2x>{lLn0Ib6Fy*^fB)Qr86p~k)2=rr}sG`X0Pqv;Ii9<9ehJAQ;<UalN{9*!@~6<5_%Cv{0u zulyE%fTv-$R(1M7tD>Lh)%V1{*}3B?uQqqnTCd@6mJd}w88q%WbB0s_jv&)#%UA>I z1`RJPiY!*N4Q~>xxja`eyM0exh0MiP;nwW=JLc6F4cQ(fe3Eyp?=OiE%?WwW4mw6Kx=&pqiAsM#0M~{>84qdi#Wc zH!;V(eAY)l+M%vGJwAiydMWK+?|n`31ub{7;rx>I`=l)%I#^iv7N{E^EIg|`49>O> zcD_pLa7>PS}3qv;j!@1;ii%DdTFF%t*+jOpP^HfElkJ>_K@XU*n|Mx`4}&*vY`biHIh zwVZe-J7t2m)R24V7wHq%<7IB=plLz(jC1eD{;IJp>*_Y) z49_c>#ge?Fd82M${P#yV*%E_mpBh~87}d%>cRKJbE=zE=CeBgM!+}L!d8qzjR@3($ zc^Vz$hVuq8b4SaYi^eKia^UamwsKVgWo;8Fw5kW8lYT1x(1-loz+1ip31>+$t!m!5 zzInvs8)~Yb`Wp3Bid)VW2ScW;JxOO*0`U`!d*8u?P|K1cZufh94NaF8+Y^V^Xq=DRhYxs zgA%WnpyAW#n?#H@hOlZyM>>a)Wc191ap=Ev7OUZbi|H8=+ zXt;w_dFru$1d%!0Y;864sQza6;1cDDJ9ixu+f|mZo@b6%Uj^shZ1{4(?Mi*Zrg>fdt%0J`)navd(-i(-jhWqnxd6VMd#1p`ELc zA%sAq1zs~V0A{H5h)!KGFb2oNdA*)(jVo2!wsOEoarFO%xuw+co|Icmk|;F)}9R(L4q-6cT~~ zP!OAAik!Ssj|AB)Q{;969Zlz1LBVYMSU%($>*&Ue4P}y9NOLp5#GC;K6f%fr@C*Xk zVM2&603iX>RMX0ZW~(V?h^9n`^TOd(gVEt(904WT6uBTmfyZJp3JET-2t!Sgo^)qW z$mNEGvV|blkZg!Cz~J=3Kt3ZJisJG^L5v|039IC@0x2%mwu=hkPo~IVp^!&Gp`xOq z45M&{Tz(J=Lnf0^XeTBieu?*a+KO0K)eCRg5DrT)6vRM=c22Ex#F=zuL64uB7g9*eNpy3NfO=J?G zKztw$8}Q8>?{_f&U=N;v4dP%wz#|Hry{t$k#5YCSInzM9V6H&;)jmiz#1fIH#pVB9 zsNmTAwHM%kF1o=4=AqEJEOuawHC#q!STu%gfW{eM32qny1&^WNFnVYV1&uaA{fQF} zJ}hbl7rqeszli>h^LL_Lz8jnpW;%3BH<~3?A9M?bKsrMhEY1jlKIp(<8iF2h-iZT5 zHpCmE4UJ&`6Y!vqjth*{h~cAa2s-f~K10an1c9zG0wEMm0cmVbWVG&A%nODW?Uncy#)I_IY@?xG2PY6l*RsG8}GI4%Yum%KhD0!eagkm>0R|AAVQePsa4rW0XEoBy1fCSKg<+7{LiJjP3BL})*y3uW zgfTclrpRam78J;c3=<;FP{ME?O2}j22@EWbf!#^Qk#IZlWGrDPnGnF*Nrae0yb+0n zMUw&yA)erC(8AbeUk3~7QNNk|i;ymm;3fh`7xin4G6TTB>H7N={nnS^{%?wm5_esA z^vC@a`&--p)b^7SSK-|Pxqw_!JgYK`pWi%fO1kfM`4TwAQ*9#;P2si>52!5sE zh$J+;JBu%n^NnT%A5H#DBNFldP9tFcEDP(wzz2&z>LbF*`)@Q75#GN4#Ak$tH~2r( zaKGad@)_(fh`(?~ab?Fs@Y+C>3zrKYN5p3V5aqxLXCtKiOZeYPJ literal 0 HcmV?d00001 diff --git a/figs/stiffness_cube_size.png b/figs/stiffness_cube_size.png new file mode 100644 index 0000000000000000000000000000000000000000..c302295743d6fb768df26b9fc12c920ce2eca5db GIT binary patch literal 23430 zcmag`bySq?7d8yf0K?GTASET;Azey$=O_pw-3>FK64D{kC?L{EH-mI5O4raJ4bt^p z+`s2p-@D#_Ue+2|Q`foAeeO8+vG+xkj@EO092y)D2!yYyqNE1`p{apDU~eo;;1$Zv zo*>{4*i-Mh0(fSCI}~_=?WSVt3A{!8@Bk08oydYfj38Adc>}-M-39+3gVVPAqbUh{ zwt-<5qBCU*Wl>^Xma;H7nzy2}b6a^`rrFNHtYf)ZdFq^5+GLxVdEFFm{i1oXy1TU; zBqh5l--#0oi)~kxE!}qX__IA=Ivgmaqd_p1M%3Y3dJbXgx!64lkCl8 z(nBQGW@OX~ExZ3_7@mm?NG_0ec@Qtf>1l`S##NxC$z!1 z8>-1Ux#w=jCCxqifyoD`0JSqu*E%?&Ky@ z3PDFNMo%5O_@QPWn{?7jR8H3XYuzo2a$lJa8Q>>wFui`6HTC%9?MaJ09@Qd~o0>T6 zZAeXt?b4F$6MAf?H)Ug_uW$5y>BCTCjO~B12!B$4!szX)t4{-c=)4wn`;@m9Olx8$ z!~&)|K=^X~d^8P4AW)|#iqoCuUa8K$h`?#v*(T4;;`c9nF7M7eB#qL_RZeQXcSP+* zvj#+_EP~@on8v-R{k-D#R=QV4{zbVk*-q^yr~i?zS;!E*#pJebzj+O1-67$B#?X22 z>Jh>d=_ogqCW2OlTu53Q89_G55$eSo{zdx--e8mH7=dF?a=6{$pHWoJB1A~DT-oEa zS1#DYPL`KPMagh_o_cK|gU@fD8CR(YiTLhA%Pg7{mim}A6E}71-Kl#{tUuc>?@V9g zBt?81CVKasDtq=Vt#^=nbe?St#z8%1kRd*nnw9l^T%K;yTC3WP`$8uvV-7P1MC)uW z!S;U8c@aBm${cz(ubmUqa44@r*r8d$Ws zI`Mue_9hE$Fjqg%8skayiJ`S`?qlR=3heYl&)O;Wzb+9nAw*nqMIKbvB||1-QRUF{ zy~nbwLSmXfqu9c1f8aNFKXLH|NOUh!Dk~LDqJildMk2y(_dc+P`R39T9`B-3j z^rPIbk=PWU@9f9zZp8W}c3uvCGjv^iSyF18B=F5=LQ`jxG8_jZ7 z(xWc*8}j0=y8)6{FEgo&&wMCgXrYJbNmGQazQ|VU`9ANN=*UPq>7yUcDcr#kUz+%I z?q)K`zIU?-!>DHRi^lDC3r(CQ>1$5ZMdHVY1{wnQ5PSrl!&99ZpwZ0dK5F|p-Ccgv zs*4&J1qE%&sT1?b{ra6Ou6FD)&s8TJccf7=ZdMoyM2){gUyl0Wm1!gWxfW*LcO~l0 z#hsK|FPPd~7pNwSpZ<}*A|P_WZ1&mv;oPt=xY!nGh?i)CT)1Xk=UOa$IV0IEYnu49 z;2(|B#@2^{;cFbbIW0dV7&_gO7J9qm-+psEM6<^;#7u?POM7CmbN$EsnPvN3iJT`( zjAazzEF1QlRQY25)4Ma?P#O+CK=W!b7`Qidt=>@y7&@3|&O}+@{T<|p+-x2ho>`pp zoYP`!Vei@P^*L#L-{}J5INsXY8o$r3=~WK7M8@*#P^KgDgO`<`-rde{9<~ zK_lx(&CY(^GgfIFWRrpJ1dc|qTnAc`qW6fgSmokMdAx49VCFwSTP=!^oZDY$IoO_S zs64+|jd$=+OSI#p_@Jw!BbUZ&X@HmbY%OJ%z1fMP2iK~|Yu!nT-T(c-*00T|j5Q@}hE9 zN|CcTiw<>*{BR)zVKGe#{$2i!sLss25qKD5RBczEr<$hg=A?$w2-0CIZ4Bz&M6x#z zD=R7e9gU^XO}f`&rW@(>OgjIADS6IpKWs3o(U=uOf19y8rN2a9c#0H3-J&->8Bk+a zM_#_^(jK~C_Y*^D%cM7sP*CAo5#|NB8a}U@yp$iVM8slK$d2UQ&o%;>|=MJI>FD z#~D3SJ{Urtl6+_k2yY>(Riq<&5Za@>I)4&HAbmoSrHs%!=%C7m@Q`3*(bjIfd~<3BVpMoDhuNVtF-|cteDmj z8L5)wM#fjO1b&OB>g;ZHb zux!E&Lpb_IXqdFDYD@b?!_*s1c9aD^q6R6!fW~x~1KB)PoNMw$AA|cdHQK|^A&s(V zK3j8gK+*~jFUj+ou#lzW@uzLzzEs>Y(voDh&r#1jT4D^EHHCc|Idha5&l5&kzv&*r zJReXpZO0yU%F9a}9l_ibLDebcss83&H$OpKI-Hf);?EcT{iy|9*4zD2D0U*GQuk&V zFKcD(_iK~HdZlBwWT61g<U5^+u`H#`BWw1cUW^#Is-Dy@Ir2~3*cBHQZ! zw)x2%@`PFtbHP7V2on=0ZahAlc@w?Snh$W~w24J!|G3|FYbEVB6Z+l@KwHzj-vUQe(%_ zGV!NKMt%ToQujpQsz3x0EzZB?=XBaCptuctP*@~0g z&ueY9ct@0I^tqT%W{xC`1XhN=BjNVdeQS3P9oY=o0+W||t3E_v>$8164yzjqR$S|R zr`z$a_xXV5V%PrGlL6AznKZ2JKzsOg5RMg9nUpM@J98Co)-TS|$jE+ooaccZ1wcXy z5uZ)S^*EXtJe`=0xqsTp+h*9;>AnT~~M>1?41&8{Uqv|kM&&dNobGcgEg>1w>aoo_;?9WOK4-1EBD26L-Bcaae+MFs(8m$%_CI=RuTIMt2 z8i#pq48K_Ej^cb9Sv%@xFx6u(>Ge2p4Km_$G($m>@*1}{G)#mz>)`5hc%lLu!b&&~ zWfG^I-$sqRMXth@!tU2-krb(hG(%Yuo?A0D?CiNgg1JG**uRUk?E&#E+Y3Y*3!WQK^NNuwLn@2{FR8^h`Uwtj^ZKQ6)K2sxXvZ@s^}cABe?&At0qw6?MF zSAisv?O~DmJTlNzv=;a+DhPde2kF<{LEdKwH}Y}LljXSyOEWrn<86IjJHS4PrB?5J zvK+x6=)R)#k=JstZpsQ5nes&cli;htP9F#aGViwXzpJjgtkl@>b>gjma~l!o*n_P4RE^0t=&CS%<6E-z9J*a2OIyAc|H-rYREqj|H>O8x}Op>_DX4M$G0;$v!-t_0JcU4rE0>T^=*arwu+9}eesQ!4#(Jj!D4Qhq8Tewv zHKYrjPznh+llD@3u>VeZ1L%{04Q4W%rrwd#+VuN;zJ?3w=KwGb8hT#b^$WSYmgOxV zk8i-z_)PJPG8&-iW}!U zpcR0lqob+#VIWEix6V#yLfIRBKnKE-KD(%|nJ#Fs>$ANq-$nm_+rJ}jZi1S{f7puY>*RwqCGeeuq88_IY1LsLUtM>xV%EiR&6&73J+@oc8tzQ6I=cI7xUoI z5ZH|_qFBGEq>5QjwnA~{st{N%d8Nno#lao(X(+r+iz)CA1XvfFn*E>Qo|&JHAcFlC zWy1s6-0mj#l%cxvw#KTXUZq*~+Qduu9 zauXK^imMGLWV_@%{?=UnQE20(V8H9;{YkPEi^C8|FO{2B`K;3}_~8ChAFbf26|8QM zvu|*(VQCbXuT>6El>gu2lA+_>nz3GYx*yB@(gFYSp2yR3evB+IXgYKns5VXE_NU!M z?yupKYL_Y>e@zhjs}N?XZE$4fpo2Eg^7v(2LuYpShM(x6Yo117s?BG`2m%Y=1@8!_ z(2M1WfuW&%?OYi$3X0?HqFlj%f3L|kluGWN1Ci5fq_vAz%3NYh_iU?pEhb$p&ytc{ zTmH!_zmhJJ{WIZI!?=cI06*z)bVm|Do^Eu1Y}5BH1zPeBj2Lk+od`+{En`zfl)5FY<84M@9-~x)~fwuwK@1m|mF8Vl$R!ohgk< zMP&Wb$0p2%zknD@6}#$qoQE|Lw?>GIN9bkSg5yidn3+Ae=`6f_Ivow1mOfQmR_PNm zcXcR?eky*8xrTUA;y0d<*KOr?kGcQ*RJOpoaF8>0eKlUzZf~}3ced^WU}W@J7J5o% zPsUj5{ds=fn39cUCi?j7!qOH2N!8xwFTFIt`f^5CSFzAE+cs0|}wJ(bcDtJ=pq^4wbMG%EQU)4vrx=MXuFPop}=suP(&0dI{;&Nr0ER1IV^8qyhQ8wbsLIK7Aunh zuWc1$%sQf}IGD*hfJ|f|SD-rAiw%$>;@Z&60dIYMo!hK7(y^lHSr3r|B5Mn*W*iEb z1_kSfr5~}%$@M~E)Ni$@Rc(Q4A8<7z7j|;(3|pPQgp&$+kM4fEG39xf{pP=$E;s;X z8UWY(K*{&DtSknblnr$F>p8>G4_rQ?4?UkmooQxfGKjPaX5Qtm1S_R=>}Z3U-Vo$u z1Css+-_$ig{`7Vn&wG-;(x;TQATNZb<3ZM8r_bFgDxZGzhWIT!fRh^gv9F=`cU}jJ z*~%X%zI&{zJ!HXmlve#fJZZdG`C!PBXop;E3*U-9e=?A(ygfKm%npyKWtCcUV)jq& zr}qcj87cK7Z;+*6A%Y$2rkdc`jd1)?S!65z7Jg90F@5?MLaQ$?cdm@iy(6?~)i3@X ziPVo|OQr!EI$R7q_#S#6Qqi*il!DJ{7>FQ7HuK{@-r<_oy&>P3s@(i&?(z%in#jgz z)tH)8D73>5wtWEHz+U|UTnlG|r)*HCaKr3JG<%J(G%&BTOPn_V`U8=l=k-?YW2@%C z7csNt392&Ul$YPBa4C7a>z#cL7DqyF`a(hc9&0Mk;^_RV7QSj``fYuV@Y^m-^IK0f z_WN60)VP@w=*1L82TdiFdv;<^eC_1@*Y!MZVSwIUX2xG1EBh%;7tS}o@!jwwbPU8I zEE|3F9_$JVMe7AYZ|wGGV57zkg`a^ z!UZ0+jv^b7`^Dq*P5s;UHtV&H-qya8086BwBONG;j){kA-l_`=t6T>S`u)#ERY}& zQ_5r%4I~}5 zGE6?cdv!_Ldw&!kx&{Em<-#No7=PdJvtg6+$lcaReJW#3^+ojIk|YKlEC1s?1qKIC71_#D7tr~xJU z^miL*Ti|&wKOP0Q335biY1q)%^4(6e)W4sK7Jkd`IP+8L$cKG zOP+z)B%WIZr2bp0N5O2ZLl=<$9i4WTI%GSp7Y^Py4Gj!@cATmJNuB=DpASA?fG!0B zwm97uD7M-cZ~x;h_FDxeaw8V(B3s#CuWA6vjmLUE7_&GV+o1I?TX*6$=pHG_KZzp3 zc!rn~7zmWVVbxHIi#i#Vj4wBDs1CaHz{IEVa&uwrbHA8uXzu~cgM*LHScRncQC##H zk>yc4L!1$ib@YbgvZ!Xke%Tt1gFKH}wU*!O>!90TCQRCUHV>$o@mo7(r z4Tv1P0Y3t$Lq5OM=)K}84nm)ORTkH1HaM9>cV6xNp=MU)vg|3F$Nay&IZ8PuRWs<+ zXQx{|HHr?^qm_m#-_XQr2fIpyZG0Ie}!>Es~|C4PX>bxF3mo|bO5;q!y*Q` zm_57w=ABh&%u%p!Tf=06A~Vt{}NWMy%hm=$E0zLYDhSgED53_Uxg0_`jKj-Na`e^D)}5 zU1B`V$ymplz70y6ktpq(!U^2M!wqw4#)Hjtby_$nHQNi%Je z|*i_-&J1!y?sSED=`q{%u*t(D2tx{aD4$eGeQ5k8Dbjdrr-(^CX zb2{Dvg@W7ZgmEbmbC@ylNgwU{Sb^=Yo#{Yaz52RpPwZULIF&^fP0*8Z;jknzP*yt< z@yEGr5vYFPJP ztFFSl1DU<3VY?XD?E!RRlxV*2DS}Y$RPd-PV&sXMyQtq3ntL9dAAXjYS5#zwqDS;O ziRE2RsJipI(|mPOigS2&AhFD?Q+0$U+XI^dcPWk%?#d&(p!TDNt%sjeQ&~^mSwWwP z{P6dNIx@LQiie(wnQFr?Wg2ZHZr*;Bud+is>1<;Aet&*z^V9}D_9ob}1M?uP+ctd; zp4=G#y&yBG90CZvk`11^SE#0k7-hv?*?01%zXPGIwD7p7a|NU; zVzWen1b)K!DHnd7!AneBJo04m`Sz?oKv6v?UGwWKE*EcJ|E5kltB zBtLKsns0KTX@s@oxu8!5;Km%g9yH~$_;c|^I!1HzI5&zI+> z?-#1{J+8yRR6VL8Xyn(~8l6@|+Qcbgw@8S}cUicx#ME!&n~q@~)B@IqD#{zf72K%p zzV$YPdEBg#;1zA!W!tk$q2lTGC$ID$KmPC&xeQ=hHv4}DXnQT+LYT{iI7}(Sefg*w z!cHc2pB52BbtFsECw+Q1;+VEkWPaTpUm<+0-xT^%f#f^_bw@BCD~D;~3ilQjUs7_c zj;y88`Ufg3l@+Ion}7Y+{Eg9EoYLqg)Hxl#G*pP|3tBV>hr1+IcqeUSN6dgO%#Nj6 zwK`-^i7-Abc>|P+4%%foV69J=2&qg?%iL<4g*s`}7K1{dt>8&@loViR1?$n2L0SXV z=TUqCAI3y^wc37iC;ZCqkR_6I6$Emlx4Nd1{5BB-;spN-eO;ovG?!_iU;hh7?FiZYDzo2%m%4F3Olf4%D zo7mFE0;M`Ki8z3S8EOx{e&bZ*oC#!kJAg~KmBK~jh6S^$_JP2St4D#haS6JgE*MoS z6DhT7XR-rA1Jf8hT5U@e+0JAyge_KFJsr!JRiadRV&wsHKlu9WmFq%ts_gwGpGduR z;2zo^t&+!g%-BvTZ|+ItFDg@FClVVl0i6zy zazw zeB*DsaT|1--|#-vZ@TG@dm{ENb@w02wc2$M?MC{2D2&rZWiL93f-EzUi@D>J9ZM z17}$)!URo1HOeMFLiQhrz&-AC%RfiSZq2FP6wlwAR`Ej5qm;yF5BMxsoFV6De`W1E zujs`O!cLt-iRY0Hs9U-VCWEqHtjy!J;{T<#IqTOxmw}Dzg-_-%TmG>LI+6VUs{w!; z5)MxaHh(lbKaI6nhr7EB3xSqJAl*6xIgh@DoVNc9j>=()&p6?gKw02TPBFPb{V4o) z0-{j4|92Ju*_K+;ltRKOgZ3VNsaQo1u19zh97gdHCVu_Ap-^-A#I^W^+1sn!?Ik_h zJ90s-t91uTT6U(;F= zFl&Yz69dGzp4zd!UiJTgetjLYGd7{bTu0%@bMj#oT5=twID4IHUdWx*=|vm(4!KC1X|O3F`dxGAiPa$ukf?eWZX>S-ge(O7)Da_@uf0m+<$Z9+kn((zX!dMV7upC0Hzbv(6E zYvfbfG9IMpApwYu$`V0<3dSCNooZOHezdZl65KkSOCH$c1W>CQ3)B4lPcOZI+I)as zG<`T36G-CYG+`vX;!6-uFqJI&YHjx!4obq!1?=;!jG0HV73B#K6e_^-Q59Lq^;7*= zb|g<Pl304K$i+V<@K zhP0djO~=PVO0VVUmznI7v&G&4-AiCeU7Zq!RVb1cM~zuC+1yHPCgU=NJ5$-KXSX(4 zMxlINL5n(ycvy#687O`rxWo5ot1t7|VQdmse1KLQiY+(`yiTEjX0XPz+UWAr$pQ39 zb$@jGd6Q^s+7d!W3@L0DaK%`azY$QqCJ0^{(%??wV(v@SZ%rGoJGqsg9$M^Kyngk! zH%gVEOR<-j-lLu(ot#+WIL}rC!=9*0#+%kLYLL?-ritJ?4+CqC&Nbt$(=fZiH48kyL7M$+F=ej+R!X9e@LP#b3C4sWF%MFYoRsY)#oKpVxY; zO|8u0N|M<61n3uXeu?b=g|BvY&>4W0m5Z+YBqVDI-2$RyXqEUriqfSJXp!ETjt(pXdKqQjp`>p210MSwc7R@ zS-Kt>^X&TID)obI#$9&+kie-2bpc`HtaXlEpqyzu+mIYij&V7WkJzS1GA`WS_GO8Q z%CAvwKNLsL0%HLX3szRj(9#h+gS!(>--EK&`f3(+O_j%Qnsu$7&Abl+;t`-1)mAt2 z*)za8X1dr&0n8l(`x?!`JT4qgvV**{hUsUB9-!B&ap|#I{l{rWK9HczJq~Hu0zzH3 z_*BmTQVp06c@EH(KoEPV2R3DQer~);H8hh1>gPg7l7`5e-Z>St733NK)9WXb)A$XvfD{?;2YDzELtP3(FwgM4@&GE-`;>3^CDZB4D zKhzrK*pSZEX1%`S4*k*B#Z5}mzo&8Wujbax>&kD~jh0*&XtzOG6DJFM-^O!oqCOT{ z{hs;H^WQ$GLRW{xA)S*wh}-fO3^?ky>2?9<>x`kd8r^uWN+X$>0k7nF{;E<}^^RN3 zcuZ4rIX{t_S(q{YFrj8(G*jVOdDAlGunyS~TMEzyo>Mx^LH{3# zQ;-B;2$+G!Y*K7PW7%OAaFe8GQcwi3D+>c)q14pvuMk#IL7qzdkYT7!`kB> z(=8o&UL#VWL}z~q-3WHIfT%a{)E_HRh>e8)X`)WYXP6n_5Rn`lszWHUgF>&pAb_7K zavF&+*qzU+Z=0xp41Dxrc`N3~L}JfSi5S>$(#OwNza8$fo;m&=eQPPPY~$B24n)!a zxg`@Y^&qcmCdXgB+AYc>>nF)m@1Q*U?iCoA_h1tC<4){ez0Nq)RZ_|@(|JRe@7US=MTPKpo+mtT858QMUqrighwyH zcrcp7&k6h}6<|`+zTav+8es;_KJ;2g?f)n(joy~s*&B_#EkFGY3=KqKvQox~b^1}P zT;8EIOdcStkmM*SC>896;V1rd@o{ubC}rUe#bxK~35%6?bK~`5g4I~~bXu=bSodSa z`TS*hI8T_FHDx%!ejzHy_uA+c7^2}qZGVGv(04T47Ipm18N?`9>)rk9z|-55spT>t zNr3ZJD2hR1*_9*!^LM*pN!SJqavp*|3H;cJ6F6t!cSVk@tSGtI1iN5}stO1 zV#XbY|4QE^+4`yJO-7tZL74*bCB)c=`qEN~p<9QYyj&S^foY;wBOY-&59zKB)J}N1 z=STPpmTN+P6vatQJCf~=n=1p~G$Kyfhn{pGN)eZ^Te_^5{H~a*_sj9-$Bg25D?1eFzI@j8L6|yabzsqHlm% zIS<_R_6BOJz12Cc{g_-#uR`PGT4WGt2Y$0l5V#jyJ`hiUlBg`ioTx?F#_-!;8-f?VM&m(N{S>sflkNL zaeB+MI|ZQEa+a%M{(qdDHl0ZU{kTLrU6cw>{~Z~i$b!5zkTe{YQDuv&y!J^}n`_Kk zY3ml{&Ub19F1%Yau^q0v$Nu|&dHuoR;`DUTT9sjKkY2t{D;*(5NN?D=P)R^e0l4*8 za8Pv3I8e};$IoRp7?9Nih-y_IF@a$iiT4job(uSA1X_wE1x4FLOyRcj-=Q_x7neOJ zig_cOUhg7c)%s<$lS9gn8yMgr*HcnjyMVBABAbYYbHk2o@+kfG4k?F%(Xu4rx15d( ze@tj>CoJa2ySVX_=AsUtS3s<{k_ENjsL9B zadVmMKz(j;I67hCUV{h!zj@j)J#TBa%Y$1ZpmDbQX0ONl?BI*n0<$btd6r_()LHFb zYz(&odc<{&H6fk+)*oG}kN@q+p+f#ix+~h4n1aqcb#R>%hC{3;?__)e%JH(?HEl4_^=~l z2Oja4B;_gf_c8(H(%ABb>;u{KjjyIe0O;HmNjP*^#me=e_$+TGqzObQ2!!>7jXwmp zm+deKuj&X5mi6=ScQrkT+buMC8W!&P*u?yXaaG3s(`_Y~E!^`9LlS8Iy7P+3pNix%xsPeh9|j;ilf7|$KR&( z0PGZ&8|1K|Bmo^si4;Vcq4?#a7|@0gf5XEpP^aC2vYnxNmA#bE$x7q}t>5pz0oCRU zZVrD2nOC}RD%<~y8%M51*&(8xqitTPfE(Aw<#nI^W5On3+K@xna!8S7Pi|lu$lO6* z(ErT&V-q_I@<-m&Uwv$#kKx9O0s2oF2kBE_KDcCmF06Im=ozM8nw3vFv5Yf!x-@j_ zA)X{se98F`OwD>BEwerA^kpBtBH8VlJucZv@AFF}9Hm-(PIz`Qr<1idPtxag{U=~m ziT@gLGMSilbgU9OYw3rd-iFD^@*vt`o~zvycGZ7~^|s~38WIfY+B zt1;(ys>&%*O`XA#nfmwL0wbb^Mb1`)y&XSeRvrwvDsSzUjw;FTmk{x5n)DV~foB{u z8Xr;{ZU^-aTz9pzjGJ$5qB^wEPL!(d-3si@&CD`@xk==YcOTw39ZZz6KYHr*lbmfF z&%nR{)y(_dL<4A$vWYrP%Q-lVh$mdgxcre|21ZKf=nwZX&bP^4uwqO`;7hXF7?)=CS;J)0 z&MDwBEueO@r0jF&;N~_EP|ApEIcQIdr4^f;rufhUyyo-=8%H0)id$A0RzveGgklGo zO|Yx-eMtsJfNyp_a`ESY_&5oF+U4M$d?{tax2qi1^DsENce}`GL;90+3wN@^QRHtL zN9WQl|CWVyDW=H3ZO`%1C;DvXfdGXg9Bp2Z9^LbjjEwAOY1-ElA_rcpprgzGF*T*e zmCqijB?A-D`{)N0RT~JQiZ?Bux66dv763n4O$o0fi~*}E{2_9iLJJ(H%cJ@PEtt;r zaHBxG?v&sfn7X6#6N8^fqx3DKfx{^`jxJhkC4focNm+0yNum8y4OQ83l$(3c!io}s z2__giUxN;{z;_nT<`}?KW>XA}O;T$pdN4x2q;3Sn3$kL_LpoPh+p9<`0awFOQ>BJ2 zK}Uz`6qM|f2$L%IJHB0B+!DKmKpKe}8w5WiPR&t@ZudGu9R9&bDy+AqqAl9!L&$(K zPN(#S<#V=$6lRnq2myt=vRK{I4_kvRz0v^#tkrtr(nfuc=7{ar0rh+}k)`AkSoJLY zm(XR1m8hHD ztjIP7G<8Ijfu^7YdFv%?SM$3*h2K;$Fq6SN{v(_Oek*erGT~SX6(>x-D{lDxKUuMd z14KjVrW4y^-Jw877MP$<+~C#e*f{F(eqGRG``@McY3~yj(dF0yA_kD6MOa!5aotG^ z9c_S*-8xU=<=JN>kb&L9J1QR%T(Fb5 zkW>U`o)h&4;0lcM^*<4{AOH8gq;L|{Fv#xD>;;+lhjE7SKuiuJhlkZ6(87Y{?bNOY z_gtO-lt_+QXizo;rxJIBmp@EcM%H4SX3-j}+ znuSn)RDI&dp9xqtbd(lghJZKhH+01pv2Kbs{-@Zke;g2cjDwgrw3y-EBsv)d?pRxd z25`?0|2q*Wju}~WW|$?`Jcbu!B}%rAO4N@b%oCbH4-EGznT6<}G2)D#ActT)pv^fX zW-2h7t7O)E6{A}M$^pIP%zO|M^EBJ-xRUcfW2UgXoi$tfcBLp5T62oepN6QzFS|!? zF8xn~vtdcNLFgCMKMAUs_^~f26R_v87D=k^zE%TUQc>4g!e%Fg3lVUfTL&~;fd|{D zF1Qohn2G3cj>!Md-cGl5tC7>jG zpKu3iW$=eSmjx9?ZY1CMJDxKb*mO3tE5%*n1Y7? zTOaLt;}Rp5S7p-xdMg1c8{FARWc~H{;iw#O)a0w~2!gmyyPSKWMAoI_53h3Js%^v~ z#Q}J;_y%>2w7xlS)q-iD+0*D${NML`l~H);IJZ-iWNud9CQ;h3TjDHQI8LfDu#1eE zE4+<*_^BZiHVC?9x^wDCB>wzAw*^MzvRL*u!@V8LolQ~7|5J}9z`sFu2w{)lC>1v= za61%Xjo!v6P8Ji0oc;EH*BeztzLFF5n?V8r0=&rAc||wBj{2zhE+>E#2nTkR?Z45T z&^DDADLD?snxg30DnM$TZK=JcRARVg2WUm%#OSV~;;w&Ir!h^^!URSM-!9U)<*;ru zo}hFND=_$=t+A*(-081Fih%s`#qEQo3VN)Yrl^@`Qk6s|K+Hlmu^wG11DyJ1pf|4i zE0B@|x+8Q^Ykn7-vxp)#okV8&695(ul!;9ze8~ zkhiy*i(kb|QNcl5 zfxTuhj0B+7MhxSoVt91*@jS7^6=wS~9K9BrZ#0&8q`VSt)%#dvto z&7A)JXZdJc8XvVqq>_n5!rBOWNF(mqyNl?xYv^^DBirmGfmxKZODIfKTo!#tv&w$r zX+&}-Xu9k{q5_AfL^YSy-@+DtiMM@=osH^P!5Oj8Cj_*N5Cq5^VP`d!Y=yr_9yK6*C%2~aVi<iQ>_v1la9HkNRgQz_}#fhm%*SE=y!x} zjy+$y$w(m;4EPN{Sdsl0iV-tNU&^9AYIsILeXW1sy013Ri_7jW^c^$1MfNgqk_#n` zHJa}&JqL^}dYM>sM`tz3dT_ombYVbCg!)+4`Eil9!^ZT==2JU~x*tuZiymWb%94hDa>0UzvDp$>cnHm9Wc1bTD zwd-$1Y~Jl8I7>)00fRNZ2f&+~Y36lQL|Ro;&M{lzc9GVGGgd@GTNVy+wOs?K?1v6g2OP zO}WA>e1&RN{%e0Qi11ZuK6DB;@eQjX8qP#&;+52YMKo0W6+sbl=f0KoYvrk$TH2KX zPu9VtL8Ih%*OL=+S}#qLF-~MVTX>FEK4xs9z`c+w9}42ct|twap}e_C;?@*tHC%rQ zeR#Q}^mQycD@Z~sa;rQW7qSXg+GF2C1a@tmOArc z+T)q{vh>pLL1*DY88pc%8M!QMKQ%u0@;n7HH>=+1g#p9V?@#e{Q--H=mIE%XhV3$+ zo!Oc`!|#~lgLR&AP!1o22`mya2I2J9z{Xr#^-E3gEleX|XY$cvILM}D{_D{{tc=X# z)jf~mr3<5;Pv(=8QC!!EUsvABzUvXOHWq*0(bvbHXTzdWq=K1U9qu(Skmvbjvq;|u z)6(;1@6qFsF>Ogm?gmK;8Ywc6V9U&Tm8HYJ7hpo}zsR3F0Fwfvwgz_7gV7_JdA#D> z{o}wuK?h14x}XIiG4+NPGnmd(NNZ@=5#b?4_;9Q;F{T6qS86A)0j)h%{LE_$8KCKq^iFo^=W+^s$_T&>4gupM z(-wiuT?@Z11kyX8j6$&ScC&BA3oZJA^tr&P#~viIQKr!4LGJ`vw~d-;p&PlS8&Lo| z+PmRjRU|x`bHB8h-8Y~+=}&iWAU%;htnp)wfQTO~y8Mh;jGKgr2n>NJE4`2)qa-#W zQkEl9vf%ApPdSy7z-S6b3xnF*Cc-hWjK2_JVK-q9*xEJ6-LCovd~N<35XYZfP}FfS zuNZ#4rE&gy zGO7ua*SQNKy|=Q}zeYD`gt|u$X`c4KE>fF-s>vNw@^`rX-mkGq_}h7}4TExo=o$NuW@~77H*iSsIClF=YPZY`@G&%=ih_Af|%j$~c(= zWL2QL)8|#JQ&s24^yflYQCwmy0yp|;b0;SB>D=RSYxUd_br6V_^x^*kAd+xDuHeEM z6knLDyq6QF{Z#swEYaK0IIX~>_RBkeb)%mf9ZQS1b$+iJpH&MLy(+5oO>40CQ$$`V z?i@EvmJ)T*A+nyo?o3(+dAF{ z)`6&=_Vbr~uaGAGoZUm7GO|Il_q8f*koIp%o{rL_RUU@YIob?-D zN+QjaCG(HgY6w@fl6$pLeM8ZzzuJOzJ`Jv#76nAaS&O9YjC1%t;2@lG6h>3^B^x)6G-8~l0XU#O9EhNXB0 z3$aVZ!k(q9F;lamzTWRn)qel!BPi~A4XTM$aYbi65sKu6*sV*6V}y}1Qse&`*eYq% z>j9573&JF5cfH8x*HWKQe~#>@!B2VJJ?b1T9wNEC<@5#$_@G==Km5*RIiCTK(gR}7R~Ws}-o zUQ+&O$O2^Js_6T%XxhD_@G*#!%ewBYxtcK)S^cPX{uI7WjE`up0r(jX@LT(7P(K|; z7C{*y*@E?ZMxS;Yotc_76(eiaG|;I&$|h|7@-Bzh0S?W+NsgO zzZG1i?I@u})TWQSGrw2D*Mbj`{bsl+YO`>zpFJ+u($m}9e@?t+X0t*Tf5VFO(tG!T zyFKNwQs7%3aR_4&DB(y-g&|e3oWHDMhKpChBRU_wlcZkV> zhkn2u*-lVa@($A8M~P_VUQ^6Fj8Y*r!cnpjnD7*=l7rA`SZE2=RW72d!Bpl`+e^@8c~UqYM$N5 z(*^ryR*6aevC#`|TSGOD@_Ln~!PqMcaib@J9~O9cWs3cM*`eu=d6DCY=+FF~fX)x3 zaVWQoc}SF|BSPWCMfKLG3{&2W>syt5DaoM3?>IJCs`~*dF-NQD#c@hFD^TJ zQsmFwQvG99^O`4#4NV;bi+&XXCzVpzt5N_BO%q=sMb`%jc z*y&Zne3t#Ddkk~Mfu%yb0%dSH9r6)F_C+Ek+0|i0JB(pPOl>ijL~;2c2X%`()3wGM z31R>t(dYC<&+sOwzeM_Tn)16s1}e%Ak#|`w{6sV72w3&Dm@9uif7c1YHt*`cpA`{r z$`5I(a<`yT-(Kt;MV;Ku%Xo_pNIm4tk!ZKZ)rwn(tdba5neBlmhoe(hpes({?9qRL zzoM|u%@q|z|7<+UFqC~Y1zx?~T}?io{|7s+5OtLuA`}%*iK*6}Uh|%XpV&!mnZYto z4E16OIZkctCi~u<=0#1Q5By!$|0!_VHEhwJ=Ura@(1zLj(&d;h)CA>&p+>4iVMx&A3hm#hkVb?b5NF#B5)u zX*!i1n*44NWGIktI*?>wAO#q~PS8P?eF@w4?AXI@{HN%hkVQOX^@L>{*QC8X)>|Ll zf{D=D?ol|v|2wX`8dp!wf~Jz@UU2g~0)`0$3rqGKf0^g1Y|;>saFm zVA<%{CEnzxU!h&6AyQT=Gq&Q3+PHi(#l<~7^4pjdwTM#KDaaFl=KCXeR3A82i@WEN zLplqJ9txI)_V)Ht*y$T+kE;4q@&p;5763d8nXE{A1la^sfe64bxwSINvm=&q07_Mc z5%n9@2ZkhqdeZ{FQ@J00s`)xLR&G~nDeCX%=Q-ILS=JM(bzoN>C=>u+c#c`WBMGPwpiCxfGVvl1^X z)QW?|*z1F&(+SHvNoaFi=PhiGdi6JH@PK2vqNi6KU<9&;S^7IKiTOl*J6#Y#e-gz` z_g!m+7amW)%bG7nY1sdDXXj9a_$yvru)UF^W+;TNGy*BpLC~cOv9rDlB|_WL5$Y+g zek`-kfm%Zx90qsiHwIo`s=mvX!AsY@sl(sC{X_3B^f2>$pCnq&m%gCm+n4{DKp@ne zp+7!7DWMy&GU4a1%3d3j-a9bOubt)KHom82mkh7FBKn-`_ zbV&b=*;CCEm%smG8f=1|sv&9sBuQpm8U8N=lTFz^uE?FaF~Pk)(B@hQ^Ff6>ncw5y zW{@U0C=dfEGI0(Rd-h*Hb4shUB|QUtH*i-;*gi))7c0$vT&$7|xKhEKsI5E*U<0-P zBI(a*W!!ZO1nhQdS^#KroJQsUG^@wMmq>G^X>odhuY+dDW`I3$g}pH5Pu$aUp}b0e zX|aH5ZR`!FVa0tP{q0UH@#s~E?EN`pgxRrNP}eL~Aw($YG(tNllh`Lr9{=)o7MLRI z=#=^=50rZhYZB0!K}p&^P0HB#L`hHMP2BdR$!y8Ai3ZCjO}*T^RRz`Y0HVNS@{vM6 zJv^(u)TxXPAYBa+h5$iWfqM5~;=W?iHx$&FGH^E^m@Kc4t_Ui8_s$KS)PSaxKObtt z>v~cNS?VK#dpV?deu*qUhDstH96%pi^hAiAoAxpcJdjzlgT{#Kn+TA9mj|WC>55Pa z1f>BI2*F$r>`iVm5-(?*LywW`5TFl^YDek_Bs57yPwyJ(3}YiDjmJHjYejQijK%Y& z8m-Oh_KJ?SavJ>`RHysh1Q}^B9_tDZHx3p zDX$R+OYLE&yKl}~A#T;^B$!j^R zzQdNsxH0@iQIz;R13tg1g&Ea$+Jp|%SL_;=Q%N65QTSQ8=@%V2>LXvYW()C*TRh}F zTebqj335#+^v&{`u7;WG-O2pWoG}G0YFvK@Ctcfcd0T9J@Vvs-&9S4)x3ETQgkHyi znCQjFE|0^T!Qml3ks<51BYfqYS}Z+M`N69IPS()1Y@1Nxp#AM#&rUs!erbK*Y@%I# zwTWu9UYL8p8yDLdlM6eJXoWRH&iFK=F4~xG{Og#BYjy#ENduC4ftJ>YXEBEXBz;4B#ZAYmW6rX>3mAa zN~*!v2UXTtLHu3$eRe@E$om#bRk2aemUKs5UNCO;ECaKr?@1!m6y@HlrL1(t*u_Jg z{aSv%$}bf`VehD{-BM^4h<>^I%@Ywe{A8*>@|Ak33aH;lZs=%Y7VmEA zS3dM)Caa)uv8hgpD5HLLVF%vQwyPWkO?sLwXE`%9=6CtybiIce^SZtf<@U>`R55H zzw?lbdgOe8f$HV0kZm2M8z3TB`1v8RL(8gT2Te7gSRL zQbTdS-;B!l<)B%eGhji0;n?@yi;5ZOXeLCt9TfA{_*U3}!d)t!T-b4;5(qMR#w{#& zt))4RM305Bg_oQ0tZ24>RjkwwhCY=o-`xAiS$nZW0U+1ijh2X1;pHTt>wd@Lp@Iw$P8k zo!Knp3OUQY-hfZ3&t!aQOq@AuRN!a*8TeK(`;Cwp?T6tBhUAKV>_+i|OR+ZdKClyP z)_Yc`aRxK58QNpY$qW9RsV$i^HY>bo5cP!+9%SFQ9(I{#6=mjh(?U&3per&hrjstC zF>~@xX9?=;5!Hm8qx2&=_B)wc<_6*!M@hwf+BpG%@oP!_WeY84UtajsZ#?fWJ!prJ znS!pPwfRkXwpI%gv!BoIX*d~-9skT7m&uhG$LpiqRLXPV*ZIA#ql50vBr`(?(@&4h z(b!Era)~Z4-K;z3R7CT7Vp)$6zBEv=r#1ZfF~?QK*t>$c%9|O=w{xIUygvBLXAH>= zAE*kA^0UstWo}hkSyH-ZB_tm)=ynV3AEoZz7A z8a;N~=x>0nY^tKX@__o$^5W^HcYB5t<7IEx|DYU0On!Fn)NNY|n)oevu{5F73Bga1 zzGue&MmfCcSwfp*0=|4lY(57S1IcZ{Tyev~4z}Ek&z>AKt-j|LgmW}@|H`~1_+jEJ zKJU)zHAa7}Tg2!h9Cg)T^vT0XzKlS1Gg%Wz@w34zps?cvDJ_U>^4!JHYFlJGXN*{D zWLf}V0yt1m9+nF02cI=CL8I6hL0!UIp`*9{Qv?axn-k5VLOO(6DkaReS>k~x%@U) zE|IKcpz1P{oDj)PaU!YSASma0oDVk4y?u40>?~S80>e_QS#K6ng|^%nfcaN~ln;9) zPa?9%;SbW8?Am5nzXo96U6^%ActPVPNI49gYvzbvx`Arx29?it%Klmqn~!2-QC_8G94Ym5HGN);hQ(pw{fItl9y@Q8b0u zf*vX*uPhF_+~WRYHzd4cxS5M2Z<*}mj5rz`Kl^h{A*C9m80&6ffz7a79+5r+v6OFb z+x_&xkJP#l+Y-p2PA@5`@mt!-CjPXJ)wd`nf}F5lFuVJVqa^SFRAXT@tW^r@w8ESM z1;G#ybpLrY!Ps?)uWNvi|59+-Au^VJb!{`*+k}MK>JT)&<~ePJ=;L?@Kc*wG$9TE@ zRJMH@N)k?6;yTb@)56UO(Wp-@{9HVFzg=D7rkn)dq<})qkckd|LeTZNvR^k-R%}EA zIO)weY93JO-X=v{jnG%o z4(d_@^j&1fWgS$3 zmCa@!Ju-YBIOuDSdyJR_F>>+&ci+UywbhmI#J%6Zbcwjpvc)xSgOnLJ#Vv}rOPjaC zk>y{(>}q!PbNWf-vqQV`uf8FWVGYy+T80hNmr5}6-*PJ5->m3c+~^POZ_*W(SY7J& zjeuA!SL?}9K5%CiXZt{Iy3 z2F6BL7(B=q+Xfn#m6rrcd&A12s}c7lCTwOcay|Rl$3R=5YAGYY)>Le#{J}M~v~ivh zq1GvI2z}oU7G%7m6jD6AKwwSUG>vyo9z%MRY>jgpg<6$lC5+oh;{KUuY$%~<(e&_) zYj^GKd-N|_d6TT%gWJ^P=0Cke1aTI2$INe*_$;BzWNN`xIT4U^lVk*e(t1CTEQMXR zzxBOm_!j>Fm;@$m1)dhY1P?x$R2s2AbVu!~L%%9K9Z<6SO=ba9a`8r-j77xTgS$L(xI1XJ}_TjIB#xWm_^N@PTyw`L3NNA1M!_b6O@A~f}MVd8WTu^D-l**o_;J7}h z>3-=d2q#;`5^R=!_WLbtaw@v9>Me!^Jg7c)3Iz95MDw`qPl79x(AGF36QHw4;rYW) z)FGpWe>+%{;w46O;%ndAl2jC$PpHU8HH4*!F7Z!Z)WVddO{Dk#g7Eu}kTi|dowlD# zsm2QG=rWQt$>Z;#{wB59wn-Ovgs2VH`)ty%ubgV2Yk8&Y-uTku#Y@>8aiJO?OOTY? zY5DwQ4m5=#fS78JBfzg`>3H@`HJZ$i&O8ZoCxW||Fq;!BR9VgD)k;XcxJ zfcGaCz7XbZ(nhh)<}l`*rBd+KSf&h0!$Cj<1+C}YV?h{6iw5K0+U*#(^A^8IzleH| z$n#f2Q-4cG@g)>CHqxxOCS_}V-|elQ3kK%GT$#G~spl#QOz~}%mO!)al2ao^5iKY3 zWQ*2xb%@Q<4iBze5OfWQpLi~%fc})#0j3|{b>DX&?~P^=6PkD^*pbBp>e8DX6lHPBoNiQ__CS$hL&=KcC zqE6dM1L@Dw9zj{RIa%J%P8^@Xe4=%5eflO&503cpPr8ZlZBsrgcJWa8n2aizY_$Mg zm`(k#m|At{*->7KcaCnf$aWztNChE*t~TEeL!g-WtoNJv^PW=g+U^WHNnB@^JglGB z$GteN0~@iKI;apdJy#98n76w$+7Nu}lAD-8Z-AHjyS9MD|JaV78ibOr;5Q<$zYT;V z@DdOE$1Mu1=o+r;d|NyCcYsegQodu+ADxeKPUCEDI6dzAiRoWPmwhvfeeOKUIHb!C zgYzM=rl|N`mE=wgbTie8MoRIFxxIp0Sy=qY#HCFHXxI6-zvJ%=b(k=)1qZ!A9p13} eZ}KOV1v}D$K5>4Y0akYf*I$k?=p8i_B60 literal 0 HcmV?d00001 diff --git a/figs/stiffness_cube_size.svg b/figs/stiffness_cube_size.svg new file mode 100644 index 0000000..fe8c4a8 --- /dev/null +++ b/figs/stiffness_cube_size.svg @@ -0,0 +1,113 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/figs/stiffness_cube_size.tex b/figs/stiffness_cube_size.tex new file mode 100644 index 0000000..24095d4 --- /dev/null +++ b/figs/stiffness_cube_size.tex @@ -0,0 +1,54 @@ +% This file was created by matlab2tikz. +% +\definecolor{mycolor1}{rgb}{0.00000,0.44700,0.74100}% +\definecolor{mycolor2}{rgb}{0.85000,0.32500,0.09800}% +% +\begin{tikzpicture} + +\begin{axis}[% +width=3.23in, +height=1.99in, +at={(0.528in,0.42in)}, +scale only axis, +separate axis lines, +every outer x axis line/.append style={black}, +every x tick label/.append style={font=\color{black}}, +every x tick/.append style={black}, +xmin=250, +xmax=350, +xlabel={Cube Size [mm]}, +every outer y axis line/.append style={black}, +every y tick label/.append style={font=\color{black}}, +every y tick/.append style={black}, +ymin=0, +ymax=0.0816666666666492, +ylabel={Rotational stiffnes [normalized]}, +axis background/.style={fill=white}, +xmajorgrids, +ymajorgrids, +legend style={at={(0.6,2.222)}, anchor=south west, legend cell align=left, align=left, draw=black} +] +\addplot [color=mycolor1, line width=1.5pt] + table[row sep=crcr]{% +250 0.0106166666666923\\ +270 0.0123500000000263\\ +290 0.0142166666666412\\ +310 0.0162166666666508\\ +330 0.0183499999999981\\ +350 0.0206166666666832\\ +}; +\addlegendentry{$k_{\theta_x}$} + +\addplot [color=mycolor2, line width=1.5pt] + table[row sep=crcr]{% +250 0.0416666666666856\\ +270 0.0486000000000217\\ +290 0.0560666666666521\\ +310 0.0640666666666903\\ +330 0.0726000000000226\\ +350 0.0816666666666492\\ +}; +\addlegendentry{$k_{\theta_z}$} + +\end{axis} +\end{tikzpicture}% \ No newline at end of file diff --git a/identification.org b/identification.org index d9a291b..334136b 100644 --- a/identification.org +++ b/identification.org @@ -25,7 +25,7 @@ :END: * Identification -#+begin_src matlab :results none :exports none +#+begin_src matlab :results none :exports none :noweb yes <> addpath('src'); addpath('library'); @@ -37,7 +37,11 @@ The hexapod structure and Sample structure are initialized. #+begin_src matlab :results none - initializeHexapod(); + stewart = initializeGeneralConfiguration(); + stewart = computeGeometricalProperties(stewart); + stewart = initializeMechanicalElements(stewart); + save('./mat/stewart.mat', 'stewart'); + initializeSample(); #+end_src @@ -45,92 +49,111 @@ The hexapod structure and Sample structure are initialized. G = identifyPlant(); #+end_src +#+begin_src matlab :results none + freqs = logspace(2, 4, 1000); +#+end_src + * Cartesian Plot From a force applied in the Cartesian frame to a displacement in the Cartesian frame. #+begin_src matlab :results none figure; hold on; - bode(G.G_cart(1, 1)); - bode(G.G_cart(3, 3)); + plot(freqs, abs(squeeze(freqresp(G.G_cart(1, 1), freqs, 'Hz')))); + plot(freqs, abs(squeeze(freqresp(G.G_cart(2, 1), freqs, 'Hz')))); + plot(freqs, abs(squeeze(freqresp(G.G_cart(3, 1), freqs, 'Hz')))); hold off; + set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); + xlabel('Frequency [Hz]'); ylabel('Amplitude'); +#+end_src + +#+begin_src matlab :results none + figure; + bode(G.G_cart, freqs); #+end_src * From a force to force sensor #+begin_src matlab :results none figure; hold on; - bode(G.G_forc(1, 1)); - bode(G.G_forc(2, 2)); - bode(G.G_forc(3, 3)); - bode(G.G_forc(4, 4)); - bode(G.G_forc(5, 5)); - bode(G.G_forc(6, 6)); + plot(freqs, abs(squeeze(freqresp(G.G_forc(1, 1), freqs, 'Hz'))), 'k-', 'DisplayName', '$F_{m_i}/F_{i}$'); hold off; + set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); + xlabel('Frequency [Hz]'); ylabel('Amplitude [N/N]'); + legend('location', 'southeast'); #+end_src #+begin_src matlab :results none figure; hold on; - bode(G.G_forc(1, 1)); - bode(G.G_forc(1, 2)); - bode(G.G_forc(1, 3)); - bode(G.G_forc(1, 4)); - bode(G.G_forc(1, 5)); - bode(G.G_forc(1, 6)); + plot(freqs, abs(squeeze(freqresp(G.G_forc(1, 1), freqs, 'Hz'))), 'k-', 'DisplayName', '$F_{m_i}/F_{i}$'); + plot(freqs, abs(squeeze(freqresp(G.G_forc(2, 1), freqs, 'Hz'))), 'k--', 'DisplayName', '$F_{m_j}/F_{i}$'); + plot(freqs, abs(squeeze(freqresp(G.G_forc(3, 1), freqs, 'Hz'))), 'k--', 'HandleVisibility', 'off'); + plot(freqs, abs(squeeze(freqresp(G.G_forc(4, 1), freqs, 'Hz'))), 'k--', 'HandleVisibility', 'off'); + plot(freqs, abs(squeeze(freqresp(G.G_forc(5, 1), freqs, 'Hz'))), 'k--', 'HandleVisibility', 'off'); + plot(freqs, abs(squeeze(freqresp(G.G_forc(6, 1), freqs, 'Hz'))), 'k--', 'HandleVisibility', 'off'); hold off; + set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); + xlabel('Frequency [Hz]'); ylabel('Amplitude [N/N]'); + legend('location', 'southeast'); #+end_src * From a force applied in the leg to the displacement of the leg #+begin_src matlab :results none figure; hold on; - bode(G.G_legs(1, 1)); - bode(G.G_legs(2, 2)); - bode(G.G_legs(3, 3)); - bode(G.G_legs(4, 4)); - bode(G.G_legs(5, 5)); - bode(G.G_legs(6, 6)); + plot(freqs, abs(squeeze(freqresp(G.G_legs(1, 1), freqs, 'Hz'))), 'k-', 'DisplayName', '$D_{i}/F_{i}$'); hold off; + set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); + xlabel('Frequency [Hz]'); ylabel('Amplitude [m/N]'); #+end_src #+begin_src matlab :results none figure; hold on; - bode(G.G_legs(1, 1)); - bode(G.G_legs(1, 2)); - bode(G.G_legs(1, 3)); - bode(G.G_legs(1, 4)); - bode(G.G_legs(1, 5)); - bode(G.G_legs(1, 6)); + plot(freqs, abs(squeeze(freqresp(G.G_legs(1, 1), freqs, 'Hz'))), 'k-', 'DisplayName', '$D_{i}/F_{i}$'); + plot(freqs, abs(squeeze(freqresp(G.G_legs(2, 1), freqs, 'Hz'))), 'k--', 'DisplayName', '$D_{j}/F_{i}$'); + plot(freqs, abs(squeeze(freqresp(G.G_legs(3, 1), freqs, 'Hz'))), 'k--', 'HandleVisibility', 'off'); + plot(freqs, abs(squeeze(freqresp(G.G_legs(4, 1), freqs, 'Hz'))), 'k--', 'HandleVisibility', 'off'); + plot(freqs, abs(squeeze(freqresp(G.G_legs(5, 1), freqs, 'Hz'))), 'k--', 'HandleVisibility', 'off'); + plot(freqs, abs(squeeze(freqresp(G.G_legs(6, 1), freqs, 'Hz'))), 'k--', 'HandleVisibility', 'off'); hold off; + set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); + xlabel('Frequency [Hz]'); ylabel('Amplitude [m/N]'); + legend('location', 'northeast'); #+end_src * Transmissibility #+begin_src matlab :results none figure; hold on; - bode(G.G_tran(1, 1)); - bode(G.G_tran(2, 2)); - bode(G.G_tran(3, 3)); + plot(freqs, abs(squeeze(freqresp(G.G_tran(1, 1), freqs, 'Hz')))); + plot(freqs, abs(squeeze(freqresp(G.G_tran(2, 2), freqs, 'Hz')))); + plot(freqs, abs(squeeze(freqresp(G.G_tran(3, 3), freqs, 'Hz')))); hold off; + set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); + xlabel('Frequency [Hz]'); ylabel('Amplitude [m/m]'); #+end_src #+begin_src matlab :results none figure; hold on; - bode(G.G_tran(4, 4)); - bode(G.G_tran(5, 5)); - bode(G.G_tran(6, 6)); + plot(freqs, abs(squeeze(freqresp(G.G_tran(4, 4), freqs, 'Hz')))); + plot(freqs, abs(squeeze(freqresp(G.G_tran(5, 5), freqs, 'Hz')))); + plot(freqs, abs(squeeze(freqresp(G.G_tran(6, 6), freqs, 'Hz')))); hold off; + set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); + xlabel('Frequency [Hz]'); ylabel('Amplitude [$\frac{rad/s}{rad/s}$]'); #+end_src #+begin_src matlab :results none figure; hold on; - bode(G.G_tran(1, 1)); - bode(G.G_tran(2, 1)); - bode(G.G_tran(3, 1)); + plot(freqs, abs(squeeze(freqresp(G.G_tran(1, 1), freqs, 'Hz')))); + plot(freqs, abs(squeeze(freqresp(G.G_tran(1, 2), freqs, 'Hz')))); + plot(freqs, abs(squeeze(freqresp(G.G_tran(1, 3), freqs, 'Hz')))); hold off; + set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); + xlabel('Frequency [Hz]'); ylabel('Amplitude [m/m]'); #+end_src * Compliance @@ -139,10 +162,12 @@ From a force applied in the Cartesian frame to a relative displacement of the mo #+begin_src matlab :results none figure; hold on; - bode(G.G_comp(1, 1)); - bode(G.G_comp(2, 2)); - bode(G.G_comp(3, 3)); + plot(freqs, abs(squeeze(freqresp(G.G_comp(1, 1), freqs, 'Hz')))); + plot(freqs, abs(squeeze(freqresp(G.G_comp(2, 2), freqs, 'Hz')))); + plot(freqs, abs(squeeze(freqresp(G.G_comp(3, 3), freqs, 'Hz')))); hold off; + set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); + xlabel('Frequency [Hz]'); ylabel('Amplitude [m/N]'); #+end_src * Inertial @@ -151,10 +176,12 @@ From a force applied on the Cartesian frame to the absolute displacement of the #+begin_src matlab :results none figure; hold on; - bode(G.G_iner(1, 1)); - bode(G.G_iner(2, 2)); - bode(G.G_iner(3, 3)); + plot(freqs, abs(squeeze(freqresp(G.G_iner(1, 1), freqs, 'Hz')))); + plot(freqs, abs(squeeze(freqresp(G.G_iner(2, 2), freqs, 'Hz')))); + plot(freqs, abs(squeeze(freqresp(G.G_iner(3, 3), freqs, 'Hz')))); hold off; + set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); + xlabel('Frequency [Hz]'); ylabel('Amplitude [m/N]'); #+end_src * identifyPlant @@ -228,11 +255,11 @@ We defined all the Input/Output names of the identified transfer function. We split the transfer function into sub transfer functions and we compute their minimum realization. #+begin_src matlab - sys.G_cart = minreal(G({'Dxm', 'Dym', 'Dzm', 'Rxm', 'Rym', 'Rzm'}, {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'})); - sys.G_forc = minreal(G({'F1m', 'F2m', 'F3m', 'F4m', 'F5m', 'F6m'}, {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'})); - sys.G_legs = minreal(G({'D1m', 'D2m', 'D3m', 'D4m', 'D5m', 'D6m'}, {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'})); + sys.G_cart = minreal(G({'Dxm', 'Dym', 'Dzm', 'Rxm', 'Rym', 'Rzm'}, {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'})); + sys.G_forc = minreal(G({'F1m', 'F2m', 'F3m', 'F4m', 'F5m', 'F6m'}, {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'})); + sys.G_legs = minreal(G({'D1m', 'D2m', 'D3m', 'D4m', 'D5m', 'D6m'}, {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'})); sys.G_tran = minreal(G({'Dxtm', 'Dytm', 'Dztm', 'Rxtm', 'Rytm', 'Rztm'}, {'Dwx', 'Dwy', 'Dwz', 'Rwx', 'Rwy', 'Rwz'})); - sys.G_comp = minreal(G({'Dxm', 'Dym', 'Dzm', 'Rxm', 'Rym', 'Rzm'}, {'Fdx', 'Fdy', 'Fdz', 'Mdx', 'Mdy', 'Mdz'})); + sys.G_comp = minreal(G({'Dxm', 'Dym', 'Dzm', 'Rxm', 'Rym', 'Rzm'}, {'Fdx', 'Fdy', 'Fdz', 'Mdx', 'Mdy', 'Mdz'})); sys.G_iner = minreal(G({'Dxtm', 'Dytm', 'Dztm', 'Rxtm', 'Rytm', 'Rztm'}, {'Fdx', 'Fdy', 'Fdz', 'Mdx', 'Mdy', 'Mdz'})); % sys.G_all = minreal(G); #+end_src diff --git a/index.html b/index.html index 1337f4b..fd92b09 100644 --- a/index.html +++ b/index.html @@ -3,7 +3,7 @@ "http://www.w3.org/TR/xhtml1/DTD/xhtml1-strict.dtd"> - + Stewart Platform Studies @@ -253,36 +253,37 @@ for the JavaScript code in this tag.

Table of Contents

-
-

1 Simscape Model

+ -
-

2 Architecture Study

+
+

2 Architecture Study

-
-

3 Motion Control

+
+

3 Motion Control

  • Active Damping
  • @@ -294,7 +295,7 @@ for the JavaScript code in this tag.

Author: Thomas Dehaeze

-

Created: 2019-03-22 ven. 12:03

+

Created: 2019-03-25 lun. 18:11

Validate

diff --git a/index.org b/index.org index 5e25b0f..fea6aaa 100644 --- a/index.org +++ b/index.org @@ -26,12 +26,13 @@ * Simscape Model - [[file:simscape-model.org][Model of the Stewart Platform]] -- [[file:identification.org][Identification]] +- [[file:identification.org][Identification of the Simscape Model]] * Architecture Study - [[file:kinematic-study.org][Kinematic Study]] - [[file:stiffness-study.org][Stiffness Matrix Study]] - Jacobian Study +- [[file:cubic-configuration.org][Cubic Architecture]] * Motion Control - Active Damping diff --git a/kinematic-study.org b/kinematic-study.org index 00cfb4d..301baf4 100644 --- a/kinematic-study.org +++ b/kinematic-study.org @@ -1,4 +1,28 @@ #+TITLE: Kinematic Study of the Stewart Platform +:DRAWER: +#+STARTUP: overview + +#+HTML_HEAD: +#+HTML_HEAD: +#+HTML_HEAD: +#+HTML_HEAD: +#+HTML_HEAD: +#+HTML_HEAD: + +#+LATEX_CLASS: cleanreport +#+LaTeX_CLASS_OPTIONS: [tocnp, secbreak, minted] +#+LaTeX_HEADER: \usepackage{svg} +#+LaTeX_HEADER: \newcommand{\authorFirstName}{Thomas} +#+LaTeX_HEADER: \newcommand{\authorLastName}{Dehaeze} +#+LaTeX_HEADER: \newcommand{\authorEmail}{dehaeze.thomas@gmail.com} + +#+PROPERTY: header-args:matlab :session *MATLAB* +#+PROPERTY: header-args:matlab+ :comments org +#+PROPERTY: header-args:matlab+ :exports both +#+PROPERTY: header-args:matlab+ :eval no-export +#+PROPERTY: header-args:matlab+ :output-dir figs +#+PROPERTY: header-args:matlab+ :mkdirp yes +:END: * Functions :PROPERTIES: diff --git a/mat/sample.mat b/mat/sample.mat index 85ab8c081c0f3b8a46c664516cfe90cf7ae9c7c2..db071b78aaab2b4bf133e526dbe33992c261edd0 100644 GIT binary patch delta 40 wcmbQnG>vJ3iG*){o`P>;k%Ez_f}x?6k)f4=rGk-xq2vJ3iG*8Grh;!`k%Eztf}x?6vALD8p@NZtq2~TZjX( z^x*b~3DGpj9|m~*ft2Tb$AN)D!j6nHlECSANIrK(P##!y8U$W|7iFV5&i*;_{$OGd<3#z0my-cC(K_k z^Kps8{EbS#+K)>d=00M7X`>G|pZ`8v0;eIiR@j(9`1@frOnkrIfAP~wGxkGi`(0pq zh5Z&NA4>0sitiT$gN^o38qODh@&(Z3$qm=@;BdRP-w7NJr=aQTl6^%c_sorT5)OyB zMd19lVNMxIrixW^t@nm=Tr>i4`~Wt3HU zanEkBdKs8{hl^16SYbE+0L*--dk#R=+nZo_{{fi$Vdn1+a!WIoo@ZkVb&n)eegEEd csY@5%w1K(@rvAWadL2!#Ln*xi0FfE&Y$f+B?EnA( delta 1393 zcmV-%1&;dJ1;PuEG#Ey5X&_Buav(A?ATcpIGdDUjF(5K9F*%V@BavVQk#rD$It2g# zc%02veNa?Y6u-cNfPm;IAC3;{5HThRLINp!A2KG2AuXAN2rj!D5X3UD!um&K4VCFQ z>1bqQ)A$FNk{Z%50mENyRr{l@WC+Lnfrcw&O0B! zbKZG(pBF+XWd=enBD#v(5wYce46?(3JxSa}23?7|&>-GdSZt_%skq~*)3PM-@*=&g z)@31-On=3y=_Qlir5Dv};$;;zUX_zyj1nLn@)CC_ddS1Y4i9AE>3~wfFU4_W{Fz>1 z)eDqQPQHQaRXU>uJ%s?~7e9=j(*Qp=ar=q;70c?xQl#;s?8H+bHZu?TGd)7(xYGV$h9tL5{#(@EZZ(&M?vP^ixp2P`*3ZKU@#fGUH& zz=D~2%iK!mQU&qybop6-*#_G=wO5anj~nPi;%42sx!4^)?sK8_pc{9cw>yt(Dy8x&zIEq&Q(hldNYeSavA zjYztJ1zQZ1;NZpU;P~V7_cZCteXTf}?-JVAT+nL(t^XTSdBq>fsMe`TR$L4ExL#w8c0(9PK^fkxaV=dZ9QiXW^7Ei%;V?rp=*=u! zv@lYXTL87gkioXT+pM> zWqv-cwzlDuhf<{oPO_qwQoxgsd~^_cmBN!oL#go zzF1dBD*j#F9&T(P0gh->d`%m1Tw%!QT-$|5nIB2=6G?u5@`(I+tnycTzy51xQxE>( zi8H%>j~yp!)m#2$Z+DSjN?xx2EbsuvfoaosU4Q-9xkgs~~`Q{_)HHp5K0nJ+tO)>)%m@Co?1qn4YK#?`y-f zwN^~rI%WUv>dpA<=KlG?XTHEqfN7vVc(p7|wXuSK0OBf;4}g3Ky>NbJ+=rhA-N7Y)x$f_H=?K08_Myy9P=Mchi2oqI;X*_5HL{N+e%!FPlkoU= zH}#!=`>IkQ^Z}+reCL(S{v&3OIsYDJXYRGNH=hPR!Hf^#d?JCjC-8xK1-X5#JJIC# ze#<+tOuN*y3$659w4p%BtO8%0A_e=BIAY zR=P#{d_8SFkB88%i%rqxEYO}s$Ul^TL0TH<0^{_Bm+ z)v7lq)i=bvVZ#q8ZR7mj*am(~?rUV|3is#nIzeuZ;dX_up3Qm&g~a|3H)x6O1q;ii diff --git a/references.bib b/references.bib new file mode 100644 index 0000000..957b49f --- /dev/null +++ b/references.bib @@ -0,0 +1,37 @@ +@inproceedings{abbas14_vibrat_stewar_platf, + author = {Hussain Abbas and Huang Hai}, + title = {Vibration isolation concepts for non-cubic Stewart Platform + using modal control}, + booktitle = {Proceedings of 2014 11th International Bhurban Conference on + Applied Sciences \& Technology (IBCAST) Islamabad, Pakistan, + 14th - 18th January, 2014}, + year = 2014, + pages = {nil}, + doi = {10.1109/ibcast.2014.6778139}, + url = {https://doi.org/10.1109/ibcast.2014.6778139}, + month = 1, +} + +@book{taghirad13_paral, + author = {Taghirad, Hamid}, + title = {Parallel robots : mechanics and control}, + year = 2013, + publisher = {CRC Press}, + address = {Boca Raton, FL}, + isbn = 9781466555778, + keywords = {favorite}, +} + +@article{geng94_six_degree_of_freed_activ, + author = {Z.J. Geng and L.S. Haynes}, + title = {Six Degree-Of-Freedom Active Vibration Control Using the + Stewart Platforms}, + journal = {IEEE Transactions on Control Systems Technology}, + volume = 2, + number = 1, + pages = {45-53}, + year = 1994, + doi = {10.1109/87.273110}, + url = {https://doi.org/10.1109/87.273110}, + keywords = {}, +} \ No newline at end of file diff --git a/simscape-model.html b/simscape-model.html index ef43443..31fcfea 100644 --- a/simscape-model.html +++ b/simscape-model.html @@ -3,7 +3,7 @@ "http://www.w3.org/TR/xhtml1/DTD/xhtml1-strict.dtd"> - + Stewart Platform - Simscape Model @@ -275,42 +275,136 @@ for the JavaScript code in this tag.

Table of Contents

-
-

1 Function description and arguments

-

-The initializeHexapod function takes one structure that contains configurations for the hexapod and returns one structure representing the hexapod. +Stewart platforms are generated in multiple steps.

-
-
function [stewart] = initializeHexapod(opts_param)
-
+ +

+First, geometrical parameters are defined: +

+
    +
  • \({}^Aa_i\) - Position of the joints fixed to the fixed base w.r.t \(\{A\}\)
  • +
  • \({}^Ab_i\) - Position of the joints fixed to the mobile platform w.r.t \(\{A\}\)
  • +
  • \({}^Bb_i\) - Position of the joints fixed to the mobile platform w.r.t \(\{B\}\)
  • +
  • \(H\) - Total height of the mobile platform
  • +
+ +

+These parameter are enough to determine all the kinematic properties of the platform like the Jacobian, stroke, stiffness, … +These geometrical parameters can be generated using different functions: initializeCubicConfiguration for cubic configuration or initializeGeneralConfiguration for more general configuration. +

+ +

+A function computeGeometricalProperties is then used to compute: +

+
    +
  • \(J_f\) - Jacobian matrix for the force location
  • +
  • \(J_d\) - Jacobian matrix for displacement estimation
  • +
  • \(R_m\) - Rotation matrices to position the leg vectors
  • +
+ +

+Then, geometrical parameters are computed for all the mechanical elements with the function initializeMechanicalElements: +

+
    +
  • Shape of the platforms +
      +
    • External Radius
    • +
    • Internal Radius
    • +
    • Density
    • +
    • Thickness
    • +
  • +
  • Shape of the Legs +
      +
    • Radius
    • +
    • Size of ball joint
    • +
    • Density
    • +
  • +
+ +

+Other Parameters are defined for the Simscape simulation: +

+
    +
  • Sample mass, volume and position (initializeSample function)
  • +
  • Location of the inertial sensor
  • +
  • Location of the point for the differential measurements
  • +
  • Location of the Jacobian point for velocity/displacement computation
  • +
+ +
+

1 initializeGeneralConfiguration

+
+
+

1.1 Function description

+
+

+The initializeGeneralConfiguration function takes one structure that contains configurations for the hexapod and returns one structure representing the Hexapod. +

+ +
+
function [stewart] = initializeGeneralConfiguration(opts_param)
+
+
+
+
+ +
+

1.2 Optional Parameters

+

Default values for opts.

opts = struct(...
-    'height',  90,    ... % Height of the platform [mm]
-    'density', 8000,  ... % Density of the material used for the hexapod [kg/m3]
-    'k_ax',    1e8,   ... % Stiffness of each actuator [N/m]
-    'c_ax',    1000,   ... % Damping of each actuator [N/(m/s)]
-    'stroke',  50e-6, ... % Maximum stroke of each actuator [m]
-    'name',    'stewart' ... % Name of the file
+    'H_tot',   90, ... % Height of the platform [mm]
+    'H_joint', 15, ... % Height of the joints [mm]
+    'H_plate', 10, ... % Thickness of the fixed and mobile platforms [mm]
+    'R_bot',  100, ... % Radius where the legs articulations are positionned [mm]
+    'R_top',  80,  ... % Radius where the legs articulations are positionned [mm]
+    'a_bot',  10,  ... % Angle Offset [deg]
+    'a_top',  40,  ... % Angle Offset [deg]
+    'da_top', 0    ... % Angle Offset from 0 position [deg]
     );
 
@@ -329,37 +423,263 @@ Populate opts with input parameters
-
-

2 Initialization of the stewart structure

-
-

-We initialize the Stewart structure -

-
-
stewart = struct();
-
-
+
+

1.3 Geometry Description

+
-

-And we defined its total height. -

-
-
stewart.H = opts.height; % [mm]
-
-
-
-
- -
-

3 Bottom Plate

-
- -
+

stewart_bottom_plate.png

Figure 1: Schematic of the bottom plates with all the parameters

+
+
+
+

1.4 Compute Aa and Ab

+
+

+We compute \([a_1, a_2, a_3, a_4, a_5, a_6]^T\) and \([b_1, b_2, b_3, b_4, b_5, b_6]^T\). +

+ +
+
Aa = zeros(6, 3); % [mm]
+Ab = zeros(6, 3); % [mm]
+Bb = zeros(6, 3); % [mm]
+
+
+ +
+
for i = 1:3
+    Aa(2*i-1,:) = [opts.R_bot*cos( pi/180*(120*(i-1) - opts.a_bot) ), ...
+                   opts.R_bot*sin( pi/180*(120*(i-1) - opts.a_bot) ), ...
+                   opts.H_plate+opts.H_joint];
+    Aa(2*i,:)   = [opts.R_bot*cos( pi/180*(120*(i-1) + opts.a_bot) ), ...
+                   opts.R_bot*sin( pi/180*(120*(i-1) + opts.a_bot) ), ...
+                   opts.H_plate+opts.H_joint];
+
+    Ab(2*i-1,:) = [opts.R_top*cos( pi/180*(120*(i-1) + opts.da_top - opts.a_top) ), ...
+                   opts.R_top*sin( pi/180*(120*(i-1) + opts.da_top - opts.a_top) ), ...
+                   opts.H_tot - opts.H_plate - opts.H_joint];
+    Ab(2*i,:)   = [opts.R_top*cos( pi/180*(120*(i-1) + opts.da_top + opts.a_top) ), ...
+                   opts.R_top*sin( pi/180*(120*(i-1) + opts.da_top + opts.a_top) ), ...
+                   opts.H_tot - opts.H_plate - opts.H_joint];
+end
+
+Bb = Ab - opts.H_tot*[0,0,1];
+
+
+
+
+ +
+

1.5 Returns Stewart Structure

+
+
+
  stewart = struct();
+  stewart.Aa = Aa;
+  stewart.Ab = Ab;
+  stewart.Bb = Bb;
+  stewart.H_tot = opts.H_tot;
+end
+
+
+
+
+
+ +
+

2 computeGeometricalProperties

+
+
+ +
+

2.1 Function description

+
+
+
function [stewart] = computeGeometricalProperties(stewart, opts_param)
+
+
+
+
+ +
+

2.2 Optional Parameters

+
+

+Default values for opts. +

+
+
opts = struct(...
+    'Jd_pos', [0, 0, 30], ... % Position of the Jacobian for displacement estimation from the top of the mobile platform [mm]
+    'Jf_pos', [0, 0, 30]  ... % Position of the Jacobian for force location from the top of the mobile platform [mm]
+    );
+
+
+ +

+Populate opts with input parameters +

+
+
if exist('opts_param','var')
+    for opt = fieldnames(opts_param)'
+        opts.(opt{1}) = opts_param.(opt{1});
+    end
+end
+
+
+
+
+ +
+

2.3 Rotation matrices

+
+

+We initialize \(l_i\) and \(\hat{s}_i\) +

+
+
leg_length = zeros(6, 1); % [mm]
+leg_vectors = zeros(6, 3);
+
+
+ +

+We compute \(b_i - a_i\), and then: +

+\begin{align*} + l_i &= \left|b_i - a_i\right| \\ + \hat{s}_i &= \frac{b_i - a_i}{l_i} +\end{align*} + +
+
legs = stewart.Ab - stewart.Aa;
+
+for i = 1:6
+    leg_length(i) = norm(legs(i,:));
+    leg_vectors(i,:) = legs(i,:) / leg_length(i);
+end
+
+
+ +

+We compute rotation matrices to have the orientation of the legs. +The rotation matrix transforms the \(z\) axis to the axis of the leg. The other axis are not important here. +

+
+
stewart.Rm = struct('R', eye(3));
+
+for i = 1:6
+  sx = cross(leg_vectors(i,:), [1 0 0]);
+  sx = sx/norm(sx);
+
+  sy = -cross(sx, leg_vectors(i,:));
+  sy = sy/norm(sy);
+
+  sz = leg_vectors(i,:);
+  sz = sz/norm(sz);
+
+  stewart.Rm(i).R = [sx', sy', sz'];
+end
+
+
+
+
+ +
+

2.4 Jacobian matrices

+
+

+Compute Jacobian Matrix +

+
+
Jd = zeros(6);
+
+for i = 1:6
+  Jd(i, 1:3) = leg_vectors(i, :);
+  Jd(i, 4:6) = cross(0.001*(stewart.Bb(i, :) - opts.Jd_pos), leg_vectors(i, :));
+end
+
+stewart.Jd = Jd;
+stewart.Jd_inv = inv(Jd);
+
+
+ +
+
Jf = zeros(6);
+
+for i = 1:6
+  Jf(i, 1:3) = leg_vectors(i, :);
+  Jf(i, 4:6) = cross(0.001*(stewart.Bb(i, :) - opts.Jf_pos), leg_vectors(i, :));
+end
+
+stewart.Jf = Jf;
+stewart.Jf_inv = inv(Jf);
+
+
+ +
+
end
+
+
+
+
+
+ +
+

3 initializeMechanicalElements

+
+
+ +
+

3.1 Function description

+
+
+
function [stewart] = initializeMechanicalElements(stewart, opts_param)
+
+
+
+
+ +
+

3.2 Optional Parameters

+
+

+Default values for opts. +

+
+
opts = struct(...
+    'thickness', 10, ... % Thickness of the base and platform [mm]
+    'density',   1000, ... % Density of the material used for the hexapod [kg/m3]
+    'k_ax',      1e8, ... % Stiffness of each actuator [N/m]
+    'c_ax',      1000, ... % Damping of each actuator [N/(m/s)]
+    'stroke',    50e-6  ... % Maximum stroke of each actuator [m]
+    );
+
+
+ +

+Populate opts with input parameters +

+
+
if exist('opts_param','var')
+    for opt = fieldnames(opts_param)'
+        opts.(opt{1}) = opts_param.(opt{1});
+    end
+end
+
+
+
+
+ +
+

3.3 Bottom Plate

+
+ +
+

stewart_bottom_plate.png +

+

Figure 2: Schematic of the bottom plates with all the parameters

+

The bottom plate structure is initialized. @@ -382,16 +702,7 @@ BP.Rext = 150; -

BP.H = 10; % Thickness of the Bottom Plate [mm]
-
-
- -

-At which radius legs will be fixed and with that angle offset. -

-
-
BP.Rleg  = 100; % Radius where the legs articulations are positionned [mm]
-BP.alpha = 10;  % Angle Offset [deg]
+
BP.H = opts.thickness; % Thickness of the Bottom Plate [mm]
 
@@ -429,9 +740,9 @@ The structure is added to the stewart structure
-
-

4 Top Plate

-
+
+

3.4 Top Plate

+

The top plate structure is initialized.

@@ -457,16 +768,6 @@ The thickness of the top plate.
-

-At which radius and angle are fixed the legs. -

-
-
TP.Rleg   = 100; % Radius where the legs articulations are positionned [mm]
-TP.alpha  = 20; % Angle [deg]
-TP.dalpha = 0; % Angle Offset from 0 position [deg]
-
-
-

The density of its material.

@@ -501,17 +802,16 @@ The structure is added to the stewart structure
-
-

5 Legs

-
+
+

3.5 Legs

+
-
+

stewart_legs.png

-

Figure 2: Schematic for the legs of the Stewart platform

+

Figure 3: Schematic for the legs of the Stewart platform

-

The leg structure is initialized.

@@ -570,6 +870,29 @@ The radius of spheres representing the ball joints are defined.
+

+We estimate the length of the legs. +

+
+
legs = stewart.Ab - stewart.Aa;
+Leg.lenght = norm(legs(1,:))/1.5;
+
+
+ +

+Then the shape of the bottom leg is estimated +

+
+
Leg.shape.bot = ...
+    [0        0; ...
+     Leg.Rbot 0; ...
+     Leg.Rbot Leg.lenght; ...
+     Leg.Rtop Leg.lenght; ...
+     Leg.Rtop 0.2*Leg.lenght; ...
+     0        0.2*Leg.lenght];
+
+
+

The structure is added to the stewart structure

@@ -580,14 +903,14 @@ The structure is added to the stewart structure
-
-

6 Ball Joints

-
+
+

3.6 Ball Joints

+
-
+

stewart_ball_joints.png

-

Figure 3: Schematic of the support for the ball joints

+

Figure 4: Schematic of the support for the ball joints

@@ -615,7 +938,7 @@ SP.c = 0; % [ Its height is defined

-
SP.H = 15; % [mm]
+
SP.H = stewart.Aa(1, 3) - BP.H; % [mm]
 
@@ -660,195 +983,74 @@ The structure is added to the Hexapod structure
- -
-

7 More parameters are initialized

-
-
-
stewart = initializeParameters(stewart);
-
-
-
-
-

8 Save the Stewart Structure

-
-
-
save('./mat/stewart.mat', 'stewart')
-
-
-
+
+

4 initializeSample

+
-
-

9 initializeParameters Function

-
-
-
function [stewart] = initializeParameters(stewart)
-
-
- -

-We first compute \([a_1, a_2, a_3, a_4, a_5, a_6]^T\) and \([b_1, b_2, b_3, b_4, b_5, b_6]^T\). -

-
-
stewart.Aa = zeros(6, 3); % [mm]
-stewart.Ab = zeros(6, 3); % [mm]
-stewart.Bb = zeros(6, 3); % [mm]
-
-
- -
-
for i = 1:3
-    stewart.Aa(2*i-1,:) = [stewart.BP.Rleg*cos( pi/180*(120*(i-1) - stewart.BP.alpha) ), ...
-                           stewart.BP.Rleg*sin( pi/180*(120*(i-1) - stewart.BP.alpha) ), ...
-                           stewart.BP.H+stewart.SP.H];
-    stewart.Aa(2*i,:)   = [stewart.BP.Rleg*cos( pi/180*(120*(i-1) + stewart.BP.alpha) ), ...
-                           stewart.BP.Rleg*sin( pi/180*(120*(i-1) + stewart.BP.alpha) ), ...
-                           stewart.BP.H+stewart.SP.H];
-
-    stewart.Ab(2*i-1,:) = [stewart.TP.Rleg*cos( pi/180*(120*(i-1) + stewart.TP.dalpha - stewart.TP.alpha) ), ...
-                           stewart.TP.Rleg*sin( pi/180*(120*(i-1) + stewart.TP.dalpha - stewart.TP.alpha) ), ...
-                           stewart.H - stewart.TP.H - stewart.SP.H];
-    stewart.Ab(2*i,:)   = [stewart.TP.Rleg*cos( pi/180*(120*(i-1) + stewart.TP.dalpha + stewart.TP.alpha) ), ...
-                           stewart.TP.Rleg*sin( pi/180*(120*(i-1) + stewart.TP.dalpha + stewart.TP.alpha) ), ...
-                           stewart.H - stewart.TP.H - stewart.SP.H];
-end
-stewart.Bb = stewart.Ab - stewart.H*[0,0,1];
-
-
- -

-Now, we compute the leg vectors \(\hat{s}_i\) and leg position \(l_i\): -\[ b_i - a_i = l_i \hat{s}_i \] -

- -

-We initialize \(l_i\) and \(\hat{s}_i\) -

-
-
leg_length = zeros(6, 1); % [mm]
-leg_vectors = zeros(6, 3);
-
-
- -

-We compute \(b_i - a_i\), and then: -

-\begin{align*} - l_i &= \left|b_i - a_i\right| \\ - \hat{s}_i &= \frac{b_i - a_i}{l_i} -\end{align*} - -
-
legs = stewart.Ab - stewart.Aa;
-
-for i = 1:6
-    leg_length(i) = norm(legs(i,:));
-    leg_vectors(i,:) = legs(i,:) / leg_length(i);
-end
-
-
- -

-Then the shape of the bottom leg is estimated -

-
-
stewart.Leg.lenght = leg_length(1)/1.5;
-stewart.Leg.shape.bot = ...
-    [0                0; ...
-     stewart.Leg.Rbot 0; ...
-     stewart.Leg.Rbot stewart.Leg.lenght; ...
-     stewart.Leg.Rtop stewart.Leg.lenght; ...
-     stewart.Leg.Rtop 0.2*stewart.Leg.lenght; ...
-     0                0.2*stewart.Leg.lenght];
-
-
- -

-We compute rotation matrices to have the orientation of the legs. -The rotation matrix transforms the \(z\) axis to the axis of the leg. The other axis are not important here. -

-
-
stewart.Rm = struct('R', eye(3));
-
-for i = 1:6
-  sx = cross(leg_vectors(i,:), [1 0 0]);
-  sx = sx/norm(sx);
-
-  sy = -cross(sx, leg_vectors(i,:));
-  sy = sy/norm(sy);
-
-  sz = leg_vectors(i,:);
-  sz = sz/norm(sz);
-
-  stewart.Rm(i).R = [sx', sy', sz'];
-end
-
-
- -

-Compute Jacobian Matrix -

-
-
J = zeros(6);
-
-for i = 1:6
-  J(i, 1:3) = leg_vectors(i, :);
-  J(i, 4:6) = cross(0.001*(stewart.Ab(i, :)- stewart.H*[0,0,1]), leg_vectors(i, :));
-end
-
-stewart.J = J;
-stewart.Jinv = inv(J);
-
-
- -
-
stewart.K = stewart.Leg.k_ax*stewart.J'*stewart.J;
-
-
- -
-
  end
-end
-
-
-
-
-
-

10 initializeSample

-
+
+

4.1 Function description

+
function [] = initializeSample(opts_param)
-%% Default values for opts
-    sample = struct( ...
-        'radius',     100, ... % radius of the cylinder [mm]
-        'height',     100, ... % height of the cylinder [mm]
-        'mass',       10,  ... % mass of the cylinder [kg]
-        'measheight', 50, ... % measurement point z-offset [mm]
-        'offset',     [0, 0, 0],   ... % offset position of the sample [mm]
-        'color',      [0.9 0.1 0.1] ...
-        );
+
+
+
+
- %% Populate opts with input parameters - if exist('opts_param','var') - for opt = fieldnames(opts_param)' - sample.(opt{1}) = opts_param.(opt{1}); - end +
+

4.2 Optional Parameters

+
+

+Default values for opts. +

+
+
sample = struct( ...
+    'radius',     100, ... % radius of the cylinder [mm]
+    'height',     100, ... % height of the cylinder [mm]
+    'mass',       10,  ... % mass of the cylinder [kg]
+    'measheight', 50, ... % measurement point z-offset [mm]
+    'offset',     [0, 0, 0],   ... % offset position of the sample [mm]
+    'color',      [0.9 0.1 0.1] ...
+    );
+
+
+ +

+Populate opts with input parameters +

+
+
if exist('opts_param','var')
+    for opt = fieldnames(opts_param)'
+        sample.(opt{1}) = opts_param.(opt{1});
     end
-
-    %% Save
-    save('./mat/sample.mat', 'sample');
 end
 
+ +
+

4.3 Save the Sample structure

+
+
+
save('./mat/sample.mat', 'sample');
+
+
+ +
+
end
+
+
+
+
+

Author: Thomas Dehaeze

-

Created: 2019-03-22 ven. 12:03

+

Created: 2019-03-25 lun. 11:18

Validate

diff --git a/simscape-model.org b/simscape-model.org index 25d7635..717d3e7 100644 --- a/simscape-model.org +++ b/simscape-model.org @@ -17,29 +17,73 @@ #+LaTeX_HEADER: \newcommand{\authorEmail}{dehaeze.thomas@gmail.com} #+PROPERTY: header-args:matlab :session *MATLAB* -#+PROPERTY: header-args:matlab+ :comments no -#+PROPERTY: header-args:matlab+ :exports bode -#+PROPERTY: header-args:matlab+ :eval no +#+PROPERTY: header-args:matlab+ :comments org +#+PROPERTY: header-args:matlab+ :exports both +#+PROPERTY: header-args:matlab+ :eval no-export #+PROPERTY: header-args:matlab+ :output-dir figs #+PROPERTY: header-args:matlab+ :mkdirp yes -#+PROPERTY: header-args:matlab+ :tangle src/initializeHexapod.m :END: -* Function description and arguments -The =initializeHexapod= function takes one structure that contains configurations for the hexapod and returns one structure representing the hexapod. +Stewart platforms are generated in multiple steps. + +First, geometrical parameters are defined: +- ${}^Aa_i$ - Position of the joints fixed to the fixed base w.r.t $\{A\}$ +- ${}^Ab_i$ - Position of the joints fixed to the mobile platform w.r.t $\{A\}$ +- ${}^Bb_i$ - Position of the joints fixed to the mobile platform w.r.t $\{B\}$ +- $H$ - Total height of the mobile platform + +These parameter are enough to determine all the kinematic properties of the platform like the Jacobian, stroke, stiffness, ... +These geometrical parameters can be generated using different functions: =initializeCubicConfiguration= for cubic configuration or =initializeGeneralConfiguration= for more general configuration. + +A function =computeGeometricalProperties= is then used to compute: +- $J_f$ - Jacobian matrix for the force location +- $J_d$ - Jacobian matrix for displacement estimation +- $R_m$ - Rotation matrices to position the leg vectors + +Then, geometrical parameters are computed for all the mechanical elements with the function =initializeMechanicalElements=: +- Shape of the platforms + - External Radius + - Internal Radius + - Density + - Thickness +- Shape of the Legs + - Radius + - Size of ball joint + - Density + +Other Parameters are defined for the Simscape simulation: +- Sample mass, volume and position (=initializeSample= function) +- Location of the inertial sensor +- Location of the point for the differential measurements +- Location of the Jacobian point for velocity/displacement computation + +* initializeGeneralConfiguration + :PROPERTIES: + :HEADER-ARGS:matlab+: :exports code + :HEADER-ARGS:matlab+: :comments no + :HEADER-ARGS:matlab+: :eval no + :HEADER-ARGS:matlab+: :tangle src/initializeGeneralConfiguration.m + :END: + +** Function description +The =initializeGeneralConfiguration= function takes one structure that contains configurations for the hexapod and returns one structure representing the Hexapod. + #+begin_src matlab - function [stewart] = initializeHexapod(opts_param) + function [stewart] = initializeGeneralConfiguration(opts_param) #+end_src +** Optional Parameters Default values for opts. #+begin_src matlab opts = struct(... - 'height', 90, ... % Height of the platform [mm] - 'density', 8000, ... % Density of the material used for the hexapod [kg/m3] - 'k_ax', 1e8, ... % Stiffness of each actuator [N/m] - 'c_ax', 1000, ... % Damping of each actuator [N/(m/s)] - 'stroke', 50e-6, ... % Maximum stroke of each actuator [m] - 'name', 'stewart' ... % Name of the file + 'H_tot', 90, ... % Height of the platform [mm] + 'H_joint', 15, ... % Height of the joints [mm] + 'H_plate', 10, ... % Thickness of the fixed and mobile platforms [mm] + 'R_bot', 100, ... % Radius where the legs articulations are positionned [mm] + 'R_top', 80, ... % Radius where the legs articulations are positionned [mm] + 'a_bot', 10, ... % Angle Offset [deg] + 'a_top', 40, ... % Angle Offset [deg] + 'da_top', 0 ... % Angle Offset from 0 position [deg] ); #+end_src @@ -52,22 +96,190 @@ Populate opts with input parameters end #+end_src -* Initialization of the stewart structure -We initialize the Stewart structure -#+begin_src matlab - stewart = struct(); -#+end_src - -And we defined its total height. -#+begin_src matlab - stewart.H = opts.height; % [mm] -#+end_src - -* Bottom Plate +** Geometry Description #+name: fig:stewart_bottom_plate #+caption: Schematic of the bottom plates with all the parameters [[file:./figs/stewart_bottom_plate.png]] +** Compute Aa and Ab +We compute $[a_1, a_2, a_3, a_4, a_5, a_6]^T$ and $[b_1, b_2, b_3, b_4, b_5, b_6]^T$. + +#+begin_src matlab + Aa = zeros(6, 3); % [mm] + Ab = zeros(6, 3); % [mm] + Bb = zeros(6, 3); % [mm] +#+end_src + +#+begin_src matlab + for i = 1:3 + Aa(2*i-1,:) = [opts.R_bot*cos( pi/180*(120*(i-1) - opts.a_bot) ), ... + opts.R_bot*sin( pi/180*(120*(i-1) - opts.a_bot) ), ... + opts.H_plate+opts.H_joint]; + Aa(2*i,:) = [opts.R_bot*cos( pi/180*(120*(i-1) + opts.a_bot) ), ... + opts.R_bot*sin( pi/180*(120*(i-1) + opts.a_bot) ), ... + opts.H_plate+opts.H_joint]; + + Ab(2*i-1,:) = [opts.R_top*cos( pi/180*(120*(i-1) + opts.da_top - opts.a_top) ), ... + opts.R_top*sin( pi/180*(120*(i-1) + opts.da_top - opts.a_top) ), ... + opts.H_tot - opts.H_plate - opts.H_joint]; + Ab(2*i,:) = [opts.R_top*cos( pi/180*(120*(i-1) + opts.da_top + opts.a_top) ), ... + opts.R_top*sin( pi/180*(120*(i-1) + opts.da_top + opts.a_top) ), ... + opts.H_tot - opts.H_plate - opts.H_joint]; + end + + Bb = Ab - opts.H_tot*[0,0,1]; +#+end_src + +** Returns Stewart Structure +#+begin_src matlab :results none + stewart = struct(); + stewart.Aa = Aa; + stewart.Ab = Ab; + stewart.Bb = Bb; + stewart.H_tot = opts.H_tot; +end +#+end_src + +* computeGeometricalProperties + :PROPERTIES: + :HEADER-ARGS:matlab+: :exports code + :HEADER-ARGS:matlab+: :comments no + :HEADER-ARGS:matlab+: :eval no + :HEADER-ARGS:matlab+: :tangle src/computeGeometricalProperties.m + :END: + +** Function description +#+begin_src matlab + function [stewart] = computeGeometricalProperties(stewart, opts_param) +#+end_src + +** Optional Parameters +Default values for opts. +#+begin_src matlab + opts = struct(... + 'Jd_pos', [0, 0, 30], ... % Position of the Jacobian for displacement estimation from the top of the mobile platform [mm] + 'Jf_pos', [0, 0, 30] ... % Position of the Jacobian for force location from the top of the mobile platform [mm] + ); +#+end_src + +Populate opts with input parameters +#+begin_src matlab + if exist('opts_param','var') + for opt = fieldnames(opts_param)' + opts.(opt{1}) = opts_param.(opt{1}); + end + end +#+end_src + +** Rotation matrices +We initialize $l_i$ and $\hat{s}_i$ +#+begin_src matlab + leg_length = zeros(6, 1); % [mm] + leg_vectors = zeros(6, 3); +#+end_src + +We compute $b_i - a_i$, and then: +\begin{align*} + l_i &= \left|b_i - a_i\right| \\ + \hat{s}_i &= \frac{b_i - a_i}{l_i} +\end{align*} + +#+begin_src matlab + legs = stewart.Ab - stewart.Aa; + + for i = 1:6 + leg_length(i) = norm(legs(i,:)); + leg_vectors(i,:) = legs(i,:) / leg_length(i); + end +#+end_src + +We compute rotation matrices to have the orientation of the legs. +The rotation matrix transforms the $z$ axis to the axis of the leg. The other axis are not important here. +#+begin_src matlab + stewart.Rm = struct('R', eye(3)); + + for i = 1:6 + sx = cross(leg_vectors(i,:), [1 0 0]); + sx = sx/norm(sx); + + sy = -cross(sx, leg_vectors(i,:)); + sy = sy/norm(sy); + + sz = leg_vectors(i,:); + sz = sz/norm(sz); + + stewart.Rm(i).R = [sx', sy', sz']; + end +#+end_src + +** Jacobian matrices +Compute Jacobian Matrix +#+begin_src matlab + Jd = zeros(6); + + for i = 1:6 + Jd(i, 1:3) = leg_vectors(i, :); + Jd(i, 4:6) = cross(0.001*(stewart.Bb(i, :) - opts.Jd_pos), leg_vectors(i, :)); + end + + stewart.Jd = Jd; + stewart.Jd_inv = inv(Jd); +#+end_src + +#+begin_src matlab + Jf = zeros(6); + + for i = 1:6 + Jf(i, 1:3) = leg_vectors(i, :); + Jf(i, 4:6) = cross(0.001*(stewart.Bb(i, :) - opts.Jf_pos), leg_vectors(i, :)); + end + + stewart.Jf = Jf; + stewart.Jf_inv = inv(Jf); +#+end_src + +#+begin_src matlab + end +#+end_src + +* initializeMechanicalElements + :PROPERTIES: + :HEADER-ARGS:matlab+: :exports code + :HEADER-ARGS:matlab+: :comments no + :HEADER-ARGS:matlab+: :eval no + :HEADER-ARGS:matlab+: :tangle src/initializeMechanicalElements.m + :END: + +** Function description +#+begin_src matlab + function [stewart] = initializeMechanicalElements(stewart, opts_param) +#+end_src + +** Optional Parameters +Default values for opts. +#+begin_src matlab + opts = struct(... + 'thickness', 10, ... % Thickness of the base and platform [mm] + 'density', 1000, ... % Density of the material used for the hexapod [kg/m3] + 'k_ax', 1e8, ... % Stiffness of each actuator [N/m] + 'c_ax', 1000, ... % Damping of each actuator [N/(m/s)] + 'stroke', 50e-6 ... % Maximum stroke of each actuator [m] + ); +#+end_src + +Populate opts with input parameters +#+begin_src matlab + if exist('opts_param','var') + for opt = fieldnames(opts_param)' + opts.(opt{1}) = opts_param.(opt{1}); + end + end +#+end_src + +** Bottom Plate +#+name: fig:stewart_bottom_plate +#+caption: Schematic of the bottom plates with all the parameters +[[file:./figs/stewart_bottom_plate.png]] The bottom plate structure is initialized. #+begin_src matlab @@ -82,13 +294,7 @@ We defined its internal radius (if there is a hole in the bottom plate) and its We define its thickness. #+begin_src matlab - BP.H = 10; % Thickness of the Bottom Plate [mm] -#+end_src - -At which radius legs will be fixed and with that angle offset. -#+begin_src matlab - BP.Rleg = 100; % Radius where the legs articulations are positionned [mm] - BP.alpha = 10; % Angle Offset [deg] + BP.H = opts.thickness; % Thickness of the Bottom Plate [mm] #+end_src We defined the density of the material of the bottom plate. @@ -111,7 +317,7 @@ The structure is added to the stewart structure stewart.BP = BP; #+end_src -* Top Plate +** Top Plate The top plate structure is initialized. #+begin_src matlab TP = struct(); @@ -128,13 +334,6 @@ The thickness of the top plate. TP.H = 10; % [mm] #+end_src -At which radius and angle are fixed the legs. -#+begin_src matlab - TP.Rleg = 100; % Radius where the legs articulations are positionned [mm] - TP.alpha = 20; % Angle [deg] - TP.dalpha = 0; % Angle Offset from 0 position [deg] -#+end_src - The density of its material. #+begin_src matlab TP.density = opts.density; % Density of the material [kg/m3] @@ -155,12 +354,11 @@ The structure is added to the stewart structure stewart.TP = TP; #+end_src -* Legs +** Legs #+name: fig:stewart_legs #+caption: Schematic for the legs of the Stewart platform [[file:./figs/stewart_legs.png]] - The leg structure is initialized. #+begin_src matlab Leg = struct(); @@ -198,12 +396,29 @@ The radius of spheres representing the ball joints are defined. Leg.R = 1.3*Leg.Rbot; % Size of the sphere at the extremity of the leg [mm] #+end_src +We estimate the length of the legs. +#+begin_src matlab + legs = stewart.Ab - stewart.Aa; + Leg.lenght = norm(legs(1,:))/1.5; +#+end_src + +Then the shape of the bottom leg is estimated +#+begin_src matlab + Leg.shape.bot = ... + [0 0; ... + Leg.Rbot 0; ... + Leg.Rbot Leg.lenght; ... + Leg.Rtop Leg.lenght; ... + Leg.Rtop 0.2*Leg.lenght; ... + 0 0.2*Leg.lenght]; +#+end_src + The structure is added to the stewart structure #+begin_src matlab stewart.Leg = Leg; #+end_src -* Ball Joints +** Ball Joints #+name: fig:stewart_ball_joints #+caption: Schematic of the support for the ball joints [[file:./figs/stewart_ball_joints.png]] @@ -223,7 +438,7 @@ We can define its rotational stiffness and damping. For now, we use perfect join Its height is defined #+begin_src matlab - SP.H = 15; % [mm] + SP.H = stewart.Aa(1, 3) - BP.H; % [mm] #+end_src Its radius is based on the radius on the sphere at the end of the legs. @@ -253,251 +468,46 @@ The structure is added to the Hexapod structure stewart.SP = SP; #+end_src -* More parameters are initialized -#+begin_src matlab - stewart = initializeParameters(stewart); -#+end_src - -* Save the Stewart Structure -#+begin_src matlab - save('./mat/stewart.mat', 'stewart') -#+end_src - -* initializeParameters Function :noexport: - :PROPERTIES: - :HEADER-ARGS:matlab+: :tangle no - :END: -#+begin_src matlab - function [stewart] = initializeParameters(stewart) -#+end_src - -Computation of the position of the connection points on the base and moving platform -We first initialize =pos_base= corresponding to $[a_1, a_2, a_3, a_4, a_5, a_6]^T$ and =pos_top= corresponding to $[b_1, b_2, b_3, b_4, b_5, b_6]^T$. -#+begin_src matlab - stewart.pos_base = zeros(6, 3); - stewart.pos_top = zeros(6, 3); -#+end_src - -We estimate the height between the ball joints of the bottom platform and of the top platform. -#+begin_src matlab - height = stewart.H - stewart.BP.H - stewart.TP.H - 2*stewart.SP.H; % [mm] -#+end_src - -#+begin_src matlab - for i = 1:3 - % base points - angle_m_b = 120*(i-1) - stewart.BP.alpha; - angle_p_b = 120*(i-1) + stewart.BP.alpha; - - stewart.pos_base(2*i-1,:) = [stewart.BP.Rleg*cos(angle_m_b), stewart.BP.Rleg*sin(angle_m_b), 0.0]; - stewart.pos_base(2*i,:) = [stewart.BP.Rleg*cos(angle_p_b), stewart.BP.Rleg*sin(angle_p_b), 0.0]; - - % top points - angle_m_t = 120*(i-1) - stewart.TP.alpha + stewart.TP.dalpha; - angle_p_t = 120*(i-1) + stewart.TP.alpha + stewart.TP.dalpha; - - stewart.pos_top(2*i-1,:) = [stewart.TP.Rleg*cos(angle_m_t), stewart.TP.Rleg*sin(angle_m_t), height]; - stewart.pos_top(2*i,:) = [stewart.TP.Rleg*cos(angle_p_t), stewart.TP.Rleg*sin(angle_p_t), height]; - end - - % permute pos_top points so that legs are end points of base and top points - stewart.pos_top = [stewart.pos_top(6,:); stewart.pos_top(1:5,:)]; %6th point on top connects to 1st on bottom - stewart.pos_top_tranform = stewart.pos_top - height*[zeros(6, 2),ones(6, 1)]; -#+end_src - -leg vectors -#+begin_src matlab - legs = stewart.pos_top - stewart.pos_base; - leg_length = zeros(6, 1); - leg_vectors = zeros(6, 3); - for i = 1:6 - leg_length(i) = norm(legs(i,:)); - leg_vectors(i,:) = legs(i,:) / leg_length(i); - end - - stewart.Leg.lenght = 1000*leg_length(1)/1.5; - stewart.Leg.shape.bot = [0 0; ... - stewart.Leg.rad.bottom 0; ... - stewart.Leg.rad.bottom stewart.Leg.lenght; ... - stewart.Leg.rad.top stewart.Leg.lenght; ... - stewart.Leg.rad.top 0.2*stewart.Leg.lenght; ... - 0 0.2*stewart.Leg.lenght]; -#+end_src - -Calculate revolute and cylindrical axes -#+begin_src matlab - rev1 = zeros(6, 3); - rev2 = zeros(6, 3); - cyl1 = zeros(6, 3); - for i = 1:6 - rev1(i,:) = cross(leg_vectors(i,:), [0 0 1]); - rev1(i,:) = rev1(i,:) / norm(rev1(i,:)); - - rev2(i,:) = - cross(rev1(i,:), leg_vectors(i,:)); - rev2(i,:) = rev2(i,:) / norm(rev2(i,:)); - - cyl1(i,:) = leg_vectors(i,:); - end -#+end_src - -Coordinate systems -#+begin_src matlab - stewart.lower_leg = struct('rotation', eye(3)); - stewart.upper_leg = struct('rotation', eye(3)); - - for i = 1:6 - stewart.lower_leg(i).rotation = [rev1(i,:)', rev2(i,:)', cyl1(i,:)']; - stewart.upper_leg(i).rotation = [rev1(i,:)', rev2(i,:)', cyl1(i,:)']; - end -#+end_src - -Position Matrix -#+begin_src matlab - stewart.M_pos_base = stewart.pos_base + (height+(stewart.TP.h+stewart.Leg.sphere.top+stewart.SP.h.top+stewart.jacobian)*1e-3)*[zeros(6, 2),ones(6, 1)]; -#+end_src - -Compute Jacobian Matrix -#+begin_src matlab - % aa = stewart.pos_top_tranform + (stewart.jacobian - stewart.TP.h - stewart.SP.height.top)*1e-3*[zeros(6, 2),ones(6, 1)]; - bb = stewart.pos_top_tranform - (stewart.TP.h + stewart.SP.height.top)*1e-3*[zeros(6, 2),ones(6, 1)]; - bb = bb - stewart.jacobian*1e-3*[zeros(6, 2),ones(6, 1)]; - stewart.J = getJacobianMatrix(leg_vectors', bb'); - - stewart.K = stewart.Leg.k.ax*stewart.J'*stewart.J; - end -#+end_src - -* initializeParameters Function -#+begin_src matlab - function [stewart] = initializeParameters(stewart) -#+end_src - -We first compute $[a_1, a_2, a_3, a_4, a_5, a_6]^T$ and $[b_1, b_2, b_3, b_4, b_5, b_6]^T$. -#+begin_src matlab - stewart.Aa = zeros(6, 3); % [mm] - stewart.Ab = zeros(6, 3); % [mm] - stewart.Bb = zeros(6, 3); % [mm] -#+end_src - -#+begin_src matlab - for i = 1:3 - stewart.Aa(2*i-1,:) = [stewart.BP.Rleg*cos( pi/180*(120*(i-1) - stewart.BP.alpha) ), ... - stewart.BP.Rleg*sin( pi/180*(120*(i-1) - stewart.BP.alpha) ), ... - stewart.BP.H+stewart.SP.H]; - stewart.Aa(2*i,:) = [stewart.BP.Rleg*cos( pi/180*(120*(i-1) + stewart.BP.alpha) ), ... - stewart.BP.Rleg*sin( pi/180*(120*(i-1) + stewart.BP.alpha) ), ... - stewart.BP.H+stewart.SP.H]; - - stewart.Ab(2*i-1,:) = [stewart.TP.Rleg*cos( pi/180*(120*(i-1) + stewart.TP.dalpha - stewart.TP.alpha) ), ... - stewart.TP.Rleg*sin( pi/180*(120*(i-1) + stewart.TP.dalpha - stewart.TP.alpha) ), ... - stewart.H - stewart.TP.H - stewart.SP.H]; - stewart.Ab(2*i,:) = [stewart.TP.Rleg*cos( pi/180*(120*(i-1) + stewart.TP.dalpha + stewart.TP.alpha) ), ... - stewart.TP.Rleg*sin( pi/180*(120*(i-1) + stewart.TP.dalpha + stewart.TP.alpha) ), ... - stewart.H - stewart.TP.H - stewart.SP.H]; - end - stewart.Bb = stewart.Ab - stewart.H*[0,0,1]; -#+end_src - -Now, we compute the leg vectors $\hat{s}_i$ and leg position $l_i$: -\[ b_i - a_i = l_i \hat{s}_i \] - -We initialize $l_i$ and $\hat{s}_i$ -#+begin_src matlab - leg_length = zeros(6, 1); % [mm] - leg_vectors = zeros(6, 3); -#+end_src - -We compute $b_i - a_i$, and then: -\begin{align*} - l_i &= \left|b_i - a_i\right| \\ - \hat{s}_i &= \frac{b_i - a_i}{l_i} -\end{align*} - -#+begin_src matlab - legs = stewart.Ab - stewart.Aa; - - for i = 1:6 - leg_length(i) = norm(legs(i,:)); - leg_vectors(i,:) = legs(i,:) / leg_length(i); - end -#+end_src - -Then the shape of the bottom leg is estimated -#+begin_src matlab - stewart.Leg.lenght = leg_length(1)/1.5; - stewart.Leg.shape.bot = ... - [0 0; ... - stewart.Leg.Rbot 0; ... - stewart.Leg.Rbot stewart.Leg.lenght; ... - stewart.Leg.Rtop stewart.Leg.lenght; ... - stewart.Leg.Rtop 0.2*stewart.Leg.lenght; ... - 0 0.2*stewart.Leg.lenght]; -#+end_src - -We compute rotation matrices to have the orientation of the legs. -The rotation matrix transforms the $z$ axis to the axis of the leg. The other axis are not important here. -#+begin_src matlab - stewart.Rm = struct('R', eye(3)); - - for i = 1:6 - sx = cross(leg_vectors(i,:), [1 0 0]); - sx = sx/norm(sx); - - sy = -cross(sx, leg_vectors(i,:)); - sy = sy/norm(sy); - - sz = leg_vectors(i,:); - sz = sz/norm(sz); - - stewart.Rm(i).R = [sx', sy', sz']; - end -#+end_src - -Compute Jacobian Matrix -#+begin_src matlab - J = zeros(6); - - for i = 1:6 - J(i, 1:3) = leg_vectors(i, :); - J(i, 4:6) = cross(0.001*(stewart.Ab(i, :)- stewart.H*[0,0,1]), leg_vectors(i, :)); - end - - stewart.J = J; - stewart.Jinv = inv(J); -#+end_src - -#+begin_src matlab - stewart.K = stewart.Leg.k_ax*stewart.J'*stewart.J; -#+end_src - -#+begin_src matlab - end - end -#+end_src * initializeSample :PROPERTIES: + :HEADER-ARGS:matlab+: :exports code + :HEADER-ARGS:matlab+: :comments no + :HEADER-ARGS:matlab+: :eval no :HEADER-ARGS:matlab+: :tangle src/initializeSample.m :END: + +** Function description #+begin_src matlab function [] = initializeSample(opts_param) - %% Default values for opts - sample = struct( ... - 'radius', 100, ... % radius of the cylinder [mm] - 'height', 100, ... % height of the cylinder [mm] - 'mass', 10, ... % mass of the cylinder [kg] - 'measheight', 50, ... % measurement point z-offset [mm] - 'offset', [0, 0, 0], ... % offset position of the sample [mm] - 'color', [0.9 0.1 0.1] ... - ); +#+end_src - %% Populate opts with input parameters - if exist('opts_param','var') - for opt = fieldnames(opts_param)' - sample.(opt{1}) = opts_param.(opt{1}); - end +** Optional Parameters +Default values for opts. +#+begin_src matlab + sample = struct( ... + 'radius', 100, ... % radius of the cylinder [mm] + 'height', 100, ... % height of the cylinder [mm] + 'mass', 10, ... % mass of the cylinder [kg] + 'measheight', 50, ... % measurement point z-offset [mm] + 'offset', [0, 0, 0], ... % offset position of the sample [mm] + 'color', [0.9 0.1 0.1] ... + ); +#+end_src + +Populate opts with input parameters +#+begin_src matlab + if exist('opts_param','var') + for opt = fieldnames(opts_param)' + sample.(opt{1}) = opts_param.(opt{1}); end - - %% Save - save('./mat/sample.mat', 'sample'); + end +#+end_src + +** Save the Sample structure +#+begin_src matlab + save('./mat/sample.mat', 'sample'); +#+end_src + +#+begin_src matlab end #+end_src diff --git a/src/computeGeometricalProperties.m b/src/computeGeometricalProperties.m new file mode 100644 index 0000000..8278cb2 --- /dev/null +++ b/src/computeGeometricalProperties.m @@ -0,0 +1,59 @@ +function [stewart] = computeGeometricalProperties(stewart, opts_param) + +opts = struct(... + 'Jd_pos', [0, 0, 30], ... % Position of the Jacobian for displacement estimation from the top of the mobile platform [mm] + 'Jf_pos', [0, 0, 30] ... % Position of the Jacobian for force location from the top of the mobile platform [mm] + ); + +if exist('opts_param','var') + for opt = fieldnames(opts_param)' + opts.(opt{1}) = opts_param.(opt{1}); + end +end + +leg_length = zeros(6, 1); % [mm] +leg_vectors = zeros(6, 3); + +legs = stewart.Ab - stewart.Aa; + +for i = 1:6 + leg_length(i) = norm(legs(i,:)); + leg_vectors(i,:) = legs(i,:) / leg_length(i); +end + +stewart.Rm = struct('R', eye(3)); + +for i = 1:6 + sx = cross(leg_vectors(i,:), [1 0 0]); + sx = sx/norm(sx); + + sy = -cross(sx, leg_vectors(i,:)); + sy = sy/norm(sy); + + sz = leg_vectors(i,:); + sz = sz/norm(sz); + + stewart.Rm(i).R = [sx', sy', sz']; +end + +Jd = zeros(6); + +for i = 1:6 + Jd(i, 1:3) = leg_vectors(i, :); + Jd(i, 4:6) = cross(0.001*(stewart.Bb(i, :) - opts.Jd_pos), leg_vectors(i, :)); +end + +stewart.Jd = Jd; +stewart.Jd_inv = inv(Jd); + +Jf = zeros(6); + +for i = 1:6 + Jf(i, 1:3) = leg_vectors(i, :); + Jf(i, 4:6) = cross(0.001*(stewart.Bb(i, :) - opts.Jf_pos), leg_vectors(i, :)); +end + +stewart.Jf = Jf; +stewart.Jf_inv = inv(Jf); + +end diff --git a/src/identifyPlant.m b/src/identifyPlant.m index 929a3fd..868b2a8 100644 --- a/src/identifyPlant.m +++ b/src/identifyPlant.m @@ -53,7 +53,7 @@ G.OutputName = {'Dxm', 'Dym', 'Dzm', 'Rxm', 'Rym', 'Rzm', ... % identifyPlant:7 ends here % [[file:~/MEGA/These/Matlab/Simscape/stewart-simscape/identification.org::*identifyPlant][identifyPlant:8]] -sys.G_cart = minreal(G({'Dxm', 'Dym', 'Dzm', 'Rxm', 'Rym', 'Rzm'}, {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'})); +sys.G_cart = G({'Dxm', 'Dym', 'Dzm', 'Rxm', 'Rym', 'Rzm'}, {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'}); sys.G_forc = minreal(G({'F1m', 'F2m', 'F3m', 'F4m', 'F5m', 'F6m'}, {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'})); sys.G_legs = minreal(G({'D1m', 'D2m', 'D3m', 'D4m', 'D5m', 'D6m'}, {'F1', 'F2', 'F3', 'F4', 'F5', 'F6'})); sys.G_tran = minreal(G({'Dxtm', 'Dytm', 'Dztm', 'Rxtm', 'Rytm', 'Rztm'}, {'Dwx', 'Dwy', 'Dwz', 'Rwx', 'Rwy', 'Rwz'})); diff --git a/src/initializeCubicConfiguration.m b/src/initializeCubicConfiguration.m new file mode 100644 index 0000000..6817217 --- /dev/null +++ b/src/initializeCubicConfiguration.m @@ -0,0 +1,89 @@ +function [stewart] = initializeCubicConfiguration(opts_param) + +opts = struct(... + 'H_tot', 90, ... % Total height of the Hexapod [mm] + 'L', 110, ... % Size of the Cube [mm] + 'H', 40, ... % Height between base joints and platform joints [mm] + 'H0', 75 ... % Height between the corner of the cube and the plane containing the base joints [mm] + ); + +if exist('opts_param','var') + for opt = fieldnames(opts_param)' + opts.(opt{1}) = opts_param.(opt{1}); + end +end + +points = [0, 0, 0; ... + 0, 0, 1; ... + 0, 1, 0; ... + 0, 1, 1; ... + 1, 0, 0; ... + 1, 0, 1; ... + 1, 1, 0; ... + 1, 1, 1]; +points = opts.L*points; + +sx = cross([1, 1, 1], [1 0 0]); +sx = sx/norm(sx); + +sy = -cross(sx, [1, 1, 1]); +sy = sy/norm(sy); + +sz = [1, 1, 1]; +sz = sz/norm(sz); + +R = [sx', sy', sz']'; + +cube = zeros(size(points)); +for i = 1:size(points, 1) + cube(i, :) = R * points(i, :)'; +end + +leg_indices = [3, 4; ... + 2, 4; ... + 2, 6; ... + 5, 6; ... + 5, 7; ... + 3, 7]; + +legs = zeros(6, 3); +legs_start = zeros(6, 3); + +for i = 1:6 + legs(i, :) = cube(leg_indices(i, 2), :) - cube(leg_indices(i, 1), :); + legs_start(i, :) = cube(leg_indices(i, 1), :); +end + +Hmax = cube(4, 3) - cube(2, 3); +if opts.H0 < cube(2, 3) + error(sprintf('H0 is not high enought. Minimum H0 = %.1f', cube(2, 3))); +else if opts.H0 + opts.H > cube(4, 3) + error(sprintf('H0+H is too high. Maximum H0+H = %.1f', cube(4, 3))); + error('H0+H is too high'); +end + +Aa = zeros(6, 3); +for i = 1:6 + t = (opts.H0-legs_start(i, 3))/(legs(i, 3)); + Aa(i, :) = legs_start(i, :) + t*legs(i, :); +end + +Ab = zeros(6, 3); +for i = 1:6 + t = (opts.H0+opts.H-legs_start(i, 3))/(legs(i, 3)); + Ab(i, :) = legs_start(i, :) + t*legs(i, :); +end + +Bb = zeros(6, 3); +Bb = Ab - (opts.H0 + opts.H_tot/2 + opts.H/2)*[0, 0, 1]; + +h = opts.H0 + opts.H/2 - opts.H_tot/2; +Aa = Aa - h*[0, 0, 1]; +Ab = Ab - h*[0, 0, 1]; + +stewart = struct(); + stewart.Aa = Aa; + stewart.Ab = Ab; + stewart.Bb = Bb; + stewart.H_tot = opts.H_tot; +end diff --git a/src/initializeGeneralConfiguration.m b/src/initializeGeneralConfiguration.m new file mode 100644 index 0000000..05ec300 --- /dev/null +++ b/src/initializeGeneralConfiguration.m @@ -0,0 +1,47 @@ +function [stewart] = initializeGeneralConfiguration(opts_param) + +opts = struct(... + 'H_tot', 90, ... % Height of the platform [mm] + 'H_joint', 15, ... % Height of the joints [mm] + 'H_plate', 10, ... % Thickness of the fixed and mobile platforms [mm] + 'R_bot', 100, ... % Radius where the legs articulations are positionned [mm] + 'R_top', 80, ... % Radius where the legs articulations are positionned [mm] + 'a_bot', 10, ... % Angle Offset [deg] + 'a_top', 40, ... % Angle Offset [deg] + 'da_top', 0 ... % Angle Offset from 0 position [deg] + ); + +if exist('opts_param','var') + for opt = fieldnames(opts_param)' + opts.(opt{1}) = opts_param.(opt{1}); + end +end + +Aa = zeros(6, 3); % [mm] +Ab = zeros(6, 3); % [mm] +Bb = zeros(6, 3); % [mm] + +for i = 1:3 + Aa(2*i-1,:) = [opts.R_bot*cos( pi/180*(120*(i-1) - opts.a_bot) ), ... + opts.R_bot*sin( pi/180*(120*(i-1) - opts.a_bot) ), ... + opts.H_plate+opts.H_joint]; + Aa(2*i,:) = [opts.R_bot*cos( pi/180*(120*(i-1) + opts.a_bot) ), ... + opts.R_bot*sin( pi/180*(120*(i-1) + opts.a_bot) ), ... + opts.H_plate+opts.H_joint]; + + Ab(2*i-1,:) = [opts.R_top*cos( pi/180*(120*(i-1) + opts.da_top - opts.a_top) ), ... + opts.R_top*sin( pi/180*(120*(i-1) + opts.da_top - opts.a_top) ), ... + opts.H_tot - opts.H_plate - opts.H_joint]; + Ab(2*i,:) = [opts.R_top*cos( pi/180*(120*(i-1) + opts.da_top + opts.a_top) ), ... + opts.R_top*sin( pi/180*(120*(i-1) + opts.da_top + opts.a_top) ), ... + opts.H_tot - opts.H_plate - opts.H_joint]; +end + +Bb = Ab - opts.H_tot*[0,0,1]; + +stewart = struct(); + stewart.Aa = Aa; + stewart.Ab = Ab; + stewart.Bb = Bb; + stewart.H_tot = opts.H_tot; +end diff --git a/src/initializeHexapod.m b/src/initializeHexapod.m index 21cfd3f..d7517da 100644 --- a/src/initializeHexapod.m +++ b/src/initializeHexapod.m @@ -1,228 +1,86 @@ -% Function description and arguments -% The =initializeHexapod= function takes one structure that contains configurations for the hexapod and returns one structure representing the hexapod. - function [stewart] = initializeHexapod(opts_param) - - -% Default values for opts. - opts = struct(... 'height', 90, ... % Height of the platform [mm] - 'density', 8000, ... % Density of the material used for the hexapod [kg/m3] + 'density', 10, ... % Density of the material used for the hexapod [kg/m3] 'k_ax', 1e8, ... % Stiffness of each actuator [N/m] 'c_ax', 1000, ... % Damping of each actuator [N/(m/s)] 'stroke', 50e-6, ... % Maximum stroke of each actuator [m] 'name', 'stewart' ... % Name of the file ); - - -% Populate opts with input parameters - if exist('opts_param','var') for opt = fieldnames(opts_param)' opts.(opt{1}) = opts_param.(opt{1}); end end -% Initialization of the stewart structure -% We initialize the Stewart structure - stewart = struct(); - - -% And we defined its total height. - stewart.H = opts.height; % [mm] -% Bottom Plate -% #+name: fig:stewart_bottom_plate -% #+caption: Schematic of the bottom plates with all the parameters -% [[file:./figs/stewart_bottom_plate.png]] - - -% The bottom plate structure is initialized. - BP = struct(); - - -% We defined its internal radius (if there is a hole in the bottom plate) and its outer radius. - BP.Rint = 0; % Internal Radius [mm] BP.Rext = 150; % External Radius [mm] - - -% We define its thickness. - BP.H = 10; % Thickness of the Bottom Plate [mm] - - -% At which radius legs will be fixed and with that angle offset. - BP.Rleg = 100; % Radius where the legs articulations are positionned [mm] -BP.alpha = 10; % Angle Offset [deg] - - - -% We defined the density of the material of the bottom plate. +BP.alpha = 30; % Angle Offset [deg] BP.density = opts.density; % Density of the material [kg/m3] - - -% And its color. - BP.color = [0.7 0.7 0.7]; % Color [RGB] - - -% Then the profile of the bottom plate is computed and will be used by Simscape - BP.shape = [BP.Rint BP.H; BP.Rint 0; BP.Rext 0; BP.Rext BP.H]; % [mm] - - -% The structure is added to the stewart structure - stewart.BP = BP; -% Top Plate -% The top plate structure is initialized. - TP = struct(); - - -% We defined the internal and external radius of the top plate. - TP.Rint = 0; % [mm] TP.Rext = 100; % [mm] - - -% The thickness of the top plate. - TP.H = 10; % [mm] - - -% At which radius and angle are fixed the legs. - -TP.Rleg = 100; % Radius where the legs articulations are positionned [mm] -TP.alpha = 20; % Angle [deg] +TP.Rleg = 80; % Radius where the legs articulations are positionned [mm] +TP.alpha = 10; % Angle [deg] TP.dalpha = 0; % Angle Offset from 0 position [deg] - - -% The density of its material. - TP.density = opts.density; % Density of the material [kg/m3] - - -% Its color. - TP.color = [0.7 0.7 0.7]; % Color [RGB] - - -% Then the shape of the top plate is computed - TP.shape = [TP.Rint TP.H; TP.Rint 0; TP.Rext 0; TP.Rext TP.H]; - - -% The structure is added to the stewart structure - stewart.TP = TP; -% Legs -% #+name: fig:stewart_legs -% #+caption: Schematic for the legs of the Stewart platform -% [[file:./figs/stewart_legs.png]] - - -% The leg structure is initialized. - Leg = struct(); - - -% The maximum Stroke of each leg is defined. - Leg.stroke = opts.stroke; % [m] - - -% The stiffness and damping of each leg are defined - Leg.k_ax = opts.k_ax; % Stiffness of each leg [N/m] Leg.c_ax = opts.c_ax; % Damping of each leg [N/(m/s)] - - -% The radius of the legs are defined - Leg.Rtop = 10; % Radius of the cylinder of the top part of the leg[mm] Leg.Rbot = 12; % Radius of the cylinder of the bottom part of the leg [mm] - - -% The density of its material. - -Leg.density = opts.density; % Density of the material used for the legs [kg/m3] - - - -% Its color. +Leg.density = 0.01*opts.density; % Density of the material used for the legs [kg/m3] Leg.color = [0.5 0.5 0.5]; % Color of the top part of the leg [RGB] - - -% The radius of spheres representing the ball joints are defined. - Leg.R = 1.3*Leg.Rbot; % Size of the sphere at the extremity of the leg [mm] - - -% The structure is added to the stewart structure - stewart.Leg = Leg; -% Ball Joints -% #+name: fig:stewart_ball_joints -% #+caption: Schematic of the support for the ball joints -% [[file:./figs/stewart_ball_joints.png]] - -% =SP= is the structure representing the support for the ball joints at the extremity of each leg. - -% The =SP= structure is initialized. - SP = struct(); - - -% We can define its rotational stiffness and damping. For now, we use perfect joints. - SP.k = 0; % [N*m/deg] SP.c = 0; % [N*m/deg] - - -% Its height is defined - SP.H = 15; % [mm] - - -% Its radius is based on the radius on the sphere at the end of the legs. - SP.R = Leg.R; % [mm] SP.section = [0 SP.H-SP.R; @@ -230,40 +88,18 @@ SP.section = [0 SP.H-SP.R; SP.R 0; SP.R SP.H]; - - -% The density of its material is defined. - SP.density = opts.density; % [kg/m^3] - - -% Its color is defined. - SP.color = [0.7 0.7 0.7]; % [RGB] - - -% The structure is added to the Hexapod structure - stewart.SP = SP; -% More parameters are initialized - stewart = initializeParameters(stewart); -% Save the Stewart Structure - save('./mat/stewart.mat', 'stewart') -% initializeParameters Function - function [stewart] = initializeParameters(stewart) - - -% We first compute $[a_1, a_2, a_3, a_4, a_5, a_6]^T$ and $[b_1, b_2, b_3, b_4, b_5, b_6]^T$. - stewart.Aa = zeros(6, 3); % [mm] stewart.Ab = zeros(6, 3); % [mm] stewart.Bb = zeros(6, 3); % [mm] @@ -285,25 +121,9 @@ for i = 1:3 end stewart.Bb = stewart.Ab - stewart.H*[0,0,1]; - - -% Now, we compute the leg vectors $\hat{s}_i$ and leg position $l_i$: -% \[ b_i - a_i = l_i \hat{s}_i \] - -% We initialize $l_i$ and $\hat{s}_i$ - leg_length = zeros(6, 1); % [mm] leg_vectors = zeros(6, 3); - - -% We compute $b_i - a_i$, and then: -% \begin{align*} -% l_i &= \left|b_i - a_i\right| \\ -% \hat{s}_i &= \frac{b_i - a_i}{l_i} -% \end{align*} - - legs = stewart.Ab - stewart.Aa; for i = 1:6 @@ -311,10 +131,6 @@ for i = 1:6 leg_vectors(i,:) = legs(i,:) / leg_length(i); end - - -% Then the shape of the bottom leg is estimated - stewart.Leg.lenght = leg_length(1)/1.5; stewart.Leg.shape.bot = ... [0 0; ... @@ -324,11 +140,6 @@ stewart.Leg.shape.bot = ... stewart.Leg.Rtop 0.2*stewart.Leg.lenght; ... 0 0.2*stewart.Leg.lenght]; - - -% We compute rotation matrices to have the orientation of the legs. -% The rotation matrix transforms the $z$ axis to the axis of the leg. The other axis are not important here. - stewart.Rm = struct('R', eye(3)); for i = 1:6 @@ -344,10 +155,6 @@ for i = 1:6 stewart.Rm(i).R = [sx', sy', sz']; end - - -% Compute Jacobian Matrix - J = zeros(6); for i = 1:6 diff --git a/src/initializeMechanicalElements.m b/src/initializeMechanicalElements.m new file mode 100644 index 0000000..1ec9077 --- /dev/null +++ b/src/initializeMechanicalElements.m @@ -0,0 +1,94 @@ +function [stewart] = initializeMechanicalElements(stewart, opts_param) + +opts = struct(... + 'thickness', 10, ... % Thickness of the base and platform [mm] + 'density', 1000, ... % Density of the material used for the hexapod [kg/m3] + 'k_ax', 1e8, ... % Stiffness of each actuator [N/m] + 'c_ax', 1000, ... % Damping of each actuator [N/(m/s)] + 'stroke', 50e-6 ... % Maximum stroke of each actuator [m] + ); + +if exist('opts_param','var') + for opt = fieldnames(opts_param)' + opts.(opt{1}) = opts_param.(opt{1}); + end +end + +BP = struct(); + +BP.Rint = 0; % Internal Radius [mm] +BP.Rext = 150; % External Radius [mm] + +BP.H = opts.thickness; % Thickness of the Bottom Plate [mm] + +BP.density = opts.density; % Density of the material [kg/m3] + +BP.color = [0.7 0.7 0.7]; % Color [RGB] + +BP.shape = [BP.Rint BP.H; BP.Rint 0; BP.Rext 0; BP.Rext BP.H]; % [mm] + +stewart.BP = BP; + +TP = struct(); + +TP.Rint = 0; % [mm] +TP.Rext = 100; % [mm] + +TP.H = 10; % [mm] + +TP.density = opts.density; % Density of the material [kg/m3] + +TP.color = [0.7 0.7 0.7]; % Color [RGB] + +TP.shape = [TP.Rint TP.H; TP.Rint 0; TP.Rext 0; TP.Rext TP.H]; + +stewart.TP = TP; + +Leg = struct(); + +Leg.stroke = opts.stroke; % [m] + +Leg.k_ax = opts.k_ax; % Stiffness of each leg [N/m] +Leg.c_ax = opts.c_ax; % Damping of each leg [N/(m/s)] + +Leg.Rtop = 10; % Radius of the cylinder of the top part of the leg[mm] +Leg.Rbot = 12; % Radius of the cylinder of the bottom part of the leg [mm] + +Leg.density = opts.density; % Density of the material used for the legs [kg/m3] + +Leg.color = [0.5 0.5 0.5]; % Color of the top part of the leg [RGB] + +Leg.R = 1.3*Leg.Rbot; % Size of the sphere at the extremity of the leg [mm] + +legs = stewart.Ab - stewart.Aa; +Leg.lenght = norm(legs(1,:))/1.5; + +Leg.shape.bot = ... + [0 0; ... + Leg.Rbot 0; ... + Leg.Rbot Leg.lenght; ... + Leg.Rtop Leg.lenght; ... + Leg.Rtop 0.2*Leg.lenght; ... + 0 0.2*Leg.lenght]; + +stewart.Leg = Leg; + +SP = struct(); + +SP.k = 0; % [N*m/deg] +SP.c = 0; % [N*m/deg] + +SP.H = stewart.Aa(1, 3) - BP.H; % [mm] + +SP.R = Leg.R; % [mm] + +SP.section = [0 SP.H-SP.R; + 0 0; + SP.R 0; + SP.R SP.H]; + +SP.density = opts.density; % [kg/m^3] + +SP.color = [0.7 0.7 0.7]; % [RGB] + +stewart.SP = SP; diff --git a/src/initializeSample.m b/src/initializeSample.m index 2c5c848..1ae05e8 100644 --- a/src/initializeSample.m +++ b/src/initializeSample.m @@ -1,21 +1,20 @@ function [] = initializeSample(opts_param) -%% Default values for opts - sample = struct( ... - 'radius', 100, ... % radius of the cylinder [mm] - 'height', 100, ... % height of the cylinder [mm] - 'mass', 10, ... % mass of the cylinder [kg] - 'measheight', 50, ... % measurement point z-offset [mm] - 'offset', [0, 0, 0], ... % offset position of the sample [mm] - 'color', [0.9 0.1 0.1] ... - ); - %% Populate opts with input parameters - if exist('opts_param','var') - for opt = fieldnames(opts_param)' - sample.(opt{1}) = opts_param.(opt{1}); - end +sample = struct( ... + 'radius', 100, ... % radius of the cylinder [mm] + 'height', 100, ... % height of the cylinder [mm] + 'mass', 10, ... % mass of the cylinder [kg] + 'measheight', 50, ... % measurement point z-offset [mm] + 'offset', [0, 0, 0], ... % offset position of the sample [mm] + 'color', [0.9 0.1 0.1] ... + ); + +if exist('opts_param','var') + for opt = fieldnames(opts_param)' + sample.(opt{1}) = opts_param.(opt{1}); end - - %% Save - save('./mat/sample.mat', 'sample'); +end + +save('./mat/sample.mat', 'sample'); + end diff --git a/src/initializeSimscapeData.m b/src/initializeSimscapeData.m new file mode 100644 index 0000000..ff0bfa5 --- /dev/null +++ b/src/initializeSimscapeData.m @@ -0,0 +1,59 @@ +function [stewart] = initializeSimscapeData(stewart, opts_param) + +opts = struct(... + 'Jd_pos', [0, 0, 30], ... % Position of the Jacobian for displacement estimation from the top of the mobile platform [mm] + 'Jf_pos', [0, 0, 30] ... % Position of the Jacobian for force location from the top of the mobile platform [mm] + ); + +if exist('opts_param','var') + for opt = fieldnames(opts_param)' + opts.(opt{1}) = opts_param.(opt{1}); + end +end + +leg_length = zeros(6, 1); % [mm] +leg_vectors = zeros(6, 3); + +legs = stewart.Ab - stewart.Aa; + +for i = 1:6 + leg_length(i) = norm(legs(i,:)); + leg_vectors(i,:) = legs(i,:) / leg_length(i); +end + +stewart.Rm = struct('R', eye(3)); + +for i = 1:6 + sx = cross(leg_vectors(i,:), [1 0 0]); + sx = sx/norm(sx); + + sy = -cross(sx, leg_vectors(i,:)); + sy = sy/norm(sy); + + sz = leg_vectors(i,:); + sz = sz/norm(sz); + + stewart.Rm(i).R = [sx', sy', sz']; +end + +Jd = zeros(6); + +for i = 1:6 + Jd(i, 1:3) = leg_vectors(i, :); + Jd(i, 4:6) = cross(0.001*(stewart.Bb(i, :) - opts.Jd_pos), leg_vectors(i, :)); +end + +stewart.Jd = Jd; +stewart.Jd_inv = inv(Jd); + +Jf = zeros(6); + +for i = 1:6 + Jf(i, 1:3) = leg_vectors(i, :); + Jf(i, 4:6) = cross(0.001*(stewart.Bb(i, :) - opts.Jf_pos), leg_vectors(i, :)); +end + +stewart.Jf = Jf; +stewart.Jf_inv = inv(Jf); + +end diff --git a/src/initializeStewartPlatform.m b/src/initializeStewartPlatform.m new file mode 100644 index 0000000..0d48c10 --- /dev/null +++ b/src/initializeStewartPlatform.m @@ -0,0 +1,94 @@ +function [stewart] = initializeStewartPlatform(stewart, opts_param) + +opts = struct(... + 'thickness', 10, ... % Thickness of the base and platform [mm] + 'density', 1000, ... % Density of the material used for the hexapod [kg/m3] + 'k_ax', 1e8, ... % Stiffness of each actuator [N/m] + 'c_ax', 1000, ... % Damping of each actuator [N/(m/s)] + 'stroke', 50e-6 ... % Maximum stroke of each actuator [m] + ); + +if exist('opts_param','var') + for opt = fieldnames(opts_param)' + opts.(opt{1}) = opts_param.(opt{1}); + end +end + +BP = struct(); + +BP.Rint = 0; % Internal Radius [mm] +BP.Rext = 150; % External Radius [mm] + +BP.H = opts.thickness; % Thickness of the Bottom Plate [mm] + +BP.density = opts.density; % Density of the material [kg/m3] + +BP.color = [0.7 0.7 0.7]; % Color [RGB] + +BP.shape = [BP.Rint BP.H; BP.Rint 0; BP.Rext 0; BP.Rext BP.H]; % [mm] + +stewart.BP = BP; + +TP = struct(); + +TP.Rint = 0; % [mm] +TP.Rext = 100; % [mm] + +TP.H = 10; % [mm] + +TP.density = opts.density; % Density of the material [kg/m3] + +TP.color = [0.7 0.7 0.7]; % Color [RGB] + +TP.shape = [TP.Rint TP.H; TP.Rint 0; TP.Rext 0; TP.Rext TP.H]; + +stewart.TP = TP; + +Leg = struct(); + +Leg.stroke = opts.stroke; % [m] + +Leg.k_ax = opts.k_ax; % Stiffness of each leg [N/m] +Leg.c_ax = opts.c_ax; % Damping of each leg [N/(m/s)] + +Leg.Rtop = 10; % Radius of the cylinder of the top part of the leg[mm] +Leg.Rbot = 12; % Radius of the cylinder of the bottom part of the leg [mm] + +Leg.density = opts.density; % Density of the material used for the legs [kg/m3] + +Leg.color = [0.5 0.5 0.5]; % Color of the top part of the leg [RGB] + +Leg.R = 1.3*Leg.Rbot; % Size of the sphere at the extremity of the leg [mm] + +legs = stewart.Ab - stewart.Aa; +Leg.lenght = norm(legs(1,:))/1.5; + +Leg.shape.bot = ... + [0 0; ... + Leg.Rbot 0; ... + Leg.Rbot Leg.lenght; ... + Leg.Rtop Leg.lenght; ... + Leg.Rtop 0.2*Leg.lenght; ... + 0 0.2*Leg.lenght]; + +stewart.Leg = Leg; + +SP = struct(); + +SP.k = 0; % [N*m/deg] +SP.c = 0; % [N*m/deg] + +SP.H = stewart.Aa(1, 3) - BP.H; % [mm] + +SP.R = Leg.R; % [mm] + +SP.section = [0 SP.H-SP.R; + 0 0; + SP.R 0; + SP.R SP.H]; + +SP.density = opts.density; % [kg/m^3] + +SP.color = [0.7 0.7 0.7]; % [RGB] + +stewart.SP = SP; diff --git a/stewart.slx b/stewart.slx index 2f4e76c88a7ed18b74e02f941aa040280dfc48a5..6b993a8d6337c6ed25f49bb2eeb0aff0915c9c73 100644 GIT binary patch delta 48160 zcmZsBV{l+WvvzFTwl}tujgw6__QtkxVs32PwrwXH+uGPpzJ2fge%xDie@xY!?x(xv zOjk{HKiw%Y5Z&|O=t{ES5EvjJATS^T79I-RwN7^?ap*LFuHpa*#s@v(731u*3At{{ zNj-H6PSxDAdrK9=~AsY>HHQvv+55ZNlET)5!XBU^Rg(f`pcEThO=XB(!+Ha2s4!lgjSYi|_XTBZJ=R-FKe^wOZconRZ zesA&sb>km@3!}x27uDw-7s%U34foZvPe(Bsm*LMCo+xRo5-v)4+@jxd%)cI?biv>| z$~Rlc-gP9~`@t7(k6jpu)|Wg+o@Ol~gs^I!!T$H%E0C475B-b8cTff9Wk0=mVULH=9O<8bYGvw=!e{T9392ZeGy&j&HaM-@v_n?fSHSWq}7nRs4 z{(&$qc4RU$v#==nzFjQD-eaB#pS0P;lVQMm{ znqUae452!ux6x%tMTTNp$QRz#R`ud4)vxiZQjgl-OfB1^Cy*d4GAtf5O}a(ztMAwh zp1wIv)-g`7sfyUmJha4|OZ9zgg<@c_pD+ID**93N@m*S0-Qo^z5I|#?(aIBFa)>Ad{EH$2MEk`9rZx|A2KR4h?0(Ls{uVHM*ebR&(IG&FArL zSv3|`nnrLx$XI;RU;YkH-eEgs%-Xf1NfQd7IN+p3kp?9;8=IqbgISx%UdRkuudeg#ARz zLHV7)559%*ia(Pyyp+ks9fEZPxX2*q@PJ-5B7Mawd#+rH((sI zCZoD8g=i1Z^EyS=S&J~&fwqM4*x0E?Pk{|$1q+X#SY&hr8uud{ke=#UbP&i+DhiEk z)xQbYtxvM90ch<^HhL30=C(bu<&nk_M{--WqG?xWgwz;SJ2}Be;-TBBl{V;6*_X(Y znFc`b<@r{%V5mDJ_!urxiMAifOo!c(N>4h}m$DiblrjX=ff_;6dI?wH7-zXtZV#R{m3VcUYu3S76pdxhfNTa0R(#(`#yvLn#^BZmZw#U`>=vZVo2l5mpdsWLKR$qvAC!A<4+ygRF)=j(65@7ie>fI*xV-YK33wR?VN@8xF z*R%R6lj1yFTTu@&n^uJ%Ct{OZr4S;>r(6@1zXB%=FTF^jP}{VKqL7ls_fH#>3G*si#TC1(Efv8$T-(H7 zYk_e1}x2tc46>5?hTt zCW1rakD}>ZuBz+lj2g=wfvsVy2X`cKn~KhiKp59!ZMKnsJZ-#4l=49|$#HyOKP|}p z=Wd`lMXY~Nw3JzsbJJ8pt{K-ft=3UvRAX5STc60w;+5XhE3-`PG1VVBw>m=b0ypTE z0=phK&H`*17&V+ynGzJ~ZiR54+f;7UUVA#UILnw{m`BY0o4yc)V}EA;L?BIsf1Nks zLtU1li2V(b_Zz3qDxMW^$rmXF$a#O!Wft5m)NQ>x-~9Ze=TN!Kn=y}#kw0qEcCh)x)i{$&2D6KSzR3vV<~GJcNoPy!$h^0!>Mhst7hT67%1oCp zQ9N`(9d_6C9C4pE#+h+^b=`EvhoesKU4V;zx2fg;SbbyLPyVl9-^VCifLxPUw2uaa z7In{%AJ1(LCU#Cr)O@e-%=;!ZdwtvcSKt^VB}W)^H08rzC)qpcf-`2&9Cmk~$&bCJ zx`gL2esp+yd{{HA&@eoInj4Oi6_Jqd#Gr#Hl|wfo=ia>Ksw5hLxU?x6Er(#LlTswy zcq-6_bs_2a92vX3%-Sme@E%T0$>w%H)beZHYb|3MFS}Otd{fVN$rQwC~j-e2Wl4jCe9GI zl<+5ch?6AKf|NsQrr{I8d7@SQ&BJm{2#>Jrf9D_ul65!7Q6L~87%&O32qeIp(>ixO%j?@aCf)H?)p@m1Yj`z|3 z_I1~)!+vQaWY7Pk&o`{+RASh{W_Q`j^|huMx_tG@_jNpgd^OYA*2V2mBLG+gpUe$2 zYXY&zLhN|=sPC{oL|lTJvTyo)DrZ~S#9Lb39Pl<@G@_k%yLUr39iML>4)@P5i(hLE z{}Q||%-}ZGzrPyUsTEaqgVSC7zqF__S9I{}mH zJnG?t@Zq6(xDQ`*W-Pv_xQ52fut*>k7GMt;0ZN$PmZuTodhS4fu@;_OBncc8z=AANS!&HAi=fUIJ zPFwfDxq9XOdLD(XtOyp+VSo`P@tlNXWGKSn!>j5Qd@x=5Wf@9}*PTmX+N#A!0PwY5 zy9(wm`)D!SY^Uu)bJvduI(8WDYDTth{A?6phOKRbW&k$MFobSjj`}+>u;(CAc`f1mn@BP_>n;0qMer!(gQy-4!?`}?x9g;5*kpKel zGShcs@65`NOT->3l!E|#A$v0CU$#L1ZsEy9eYbi4z?%o0UUQ+oe{u~c-hbOgdXY1B zPK?KzIK-Pc+_}3p=j_BGdS~T-<>&9fbqyUE*gc2Z{qP985j5<41du+Xw%NS6-Fv+Y zp14AZ-%i?g1-?Ak@xHqaRAdAmpS*nyZIizU*^HkhdJo_0Z5W9@eI?Awo>KJWJkHNh z!=@y1u@3@iGpASIAp!aTm5+5)QqA|4xRQ`N4bW;h!nfz=N7~+qnA8|4QlhQ3h7N}X6B z{eTX4v@S?^?8t-Br?T^ndTOA_8ygwo09f69--7KlM@@EoTXpH*E0J{F*=R+d=%P(% zIIaqCO0lOTyFVC~pe_M7yL^_4$-Ak=It1sIP(hvg@oNM_(A^MvcSY>z&)DziMkNiE z!T6@s75^3uBUTyEYgCx5a(H5~y~g9?&yC06pP#>8q7OsNPp8T-HAmgf>+wk!FM(DS zV}1A>AT!qtwH&fNKAny-(41_sRiDv`GsFDXJ`q+N&g)dbh3T35x6%Y20sdq z)rmVryCVNs%tPBB88)*NIosAM0bTu)7wW3Ba*A6A0pnz!cEE*Pk9XTx<{rsuv=M7uP$#7pvquoq`# zL<(WKT_g-ujhQ!`geVmTW)l~1iW`|Iv1{4VHC2Y6T8`xa#Y z_864LWQc9&Y-A2y@{`K-(S8+yOa%BYrbWtOJfqYIo9PfHCW zy9o0DWr`A5q~X6e@Q>p$A3&UZk|HbQy;H48e6^$zF~6V2$2)zK<2FXZh%(hrQ5kzP zcK;%n=6q@7{x>tKHcV$m_I>g&ngnOyPQVLQ0LKfiHJTr4YKCFK)WBkQ69K%lN_>ei z?^`QF7#nV-5iAbx8Vr&2ENfQw@1L+TnJ!-{qEkntvV|*KMmdF7e*koNGiaonCulY9 zj-oY%R@DUPQ%A*4r2s-Q&*y$O+ps4jc^kJW^}Mw26OA@UKdd3(eo7ye6+rSx&%t#+5w0~c`Bbr%{Z~EVc(C~}q=6m*H z_wDOQBx9Z`Ry3sCb$;=ZX%`xUDPCnRj(XY8anER$_Pdb;httsYMNvv2-!AO%4i;|| zLndgqvmXf6%_-P*m;>l*EGw}lL`B790#4X#D+IL(PNWb#Jiv+*82i25k}TSn!75EY zu9vW>74Zk9oB}vcb!*0Yuw7dp2U2lS$C_VHg^!NA`ceSsp0zA_yJ5ojFj60bP~_$d zg`AC5$Zz7Sy8EMuOWm8PMsL2StqLf-4U#xrxi_vB0{KtObK7&CpL_r{MwcT_Vkdgt zAK|wmpTOcT6=1+<=E4tq2RsE%@r0g4(fsmtX*?3ag0J)8i1O-lFx^{IJKP-K+jD@E z!t}_%L7f0>^*5Vw^0wvfWF`u31ZkYqv^}Ll@gC1hHeQ4WA7^y=JPR*U{uSq>!pMdV z&V}hQ&}ub}1p58(9<{w7`uru`Zq)Qw81bZQa?AmbOYAUTz+nvvB(oMza-us?XqtrxLHSfP3#T!5sd>aCKM7 zg81tsm$(2b=fjl{dG8olT>queCTa-V>6ptj0X&`-3P8 z?98$uBj8>vwNC!lC+K#=a}Gt=nD3mvv2um333ix)YKKg*rN*FF0FPpK^@h&;2Ta7A z^z9qgjTqgYZFtx=u0ZGQ4TkUc!OeilU8b*a{mLP{ss*$4r+}7C-Tf=oR&IqfbN^Hl z^k7!dblR#EgJ0Q>bN+}D!kRF zUx?xLM_JbCYlIedT`YQxC)wX>;eof6`_F=|b#r)%3As|LvG4uG(g`%BzNhxikQwKL zpH4Q=gBlS6FF!q#`6dV{+3XJtxd`4KyNraCw)?&JHxk*JaS(6=EA)+R>Woy49lj|h zYXQ2Ixva@4a}$)shmx;@L#7&f-`w7Q17SkGrug3?(OcyzaXgQxS~ft>od*?ncVy9e z2c61x(S)w4@Xy~N9g_dHU4o3K&sj)x;%*ZCZmWK#{ma6tAN=NA^Opm3!;Q}!iwpHh z*E@g(k>sh1^-{a0&u7^DuUIk1W`(u}?Jl5bgLAhDwncN7F&3}=OR%I<=yhvtYSJ%S z1L~(2en*t)(brs!q(4mkI{lWWe1aU&ds&W(pZ6Rl1Dtf%bZ@^iAL!Vb8&RL%E96n%e z(^pTL1sN;_%zum-T5uwKpZVz3fN+ENQhtA%`;^qATYZvWmr&l-<-WB-jDoWubXfvF zBU{5dkm;v&;5(in(eM79aJQxgGuz8gd=z#T4`H9~zFWs#oeOjih_~PFBpN5)Nl=lj z%ca;f)9O~Ssjo>~K)kSnAJq*hEFO?4|6)LWu){_!js7CUX7v$*C=#*6C>wS03vO1{ zyD>zJfEKfq8e|9CWOO@`6j1l?ynYv2mho1WqLid9MJvJh8L$Y?+=vw)nAR^o&?kCD6gcsf`M|pP*!j^)z%(z{MP+&bbFb zk-iUsF8A(_q>`tLO0XH_7S`7qZQpqJQzP+>iGC+i=E}z?O^Fr2~7%e$sTlNKlx! zXG-siNtj;=0egV*zimXsm$dwikm`S=7+(qbd&hl!Nx}jVUuFLQ<%Q2V7??uH3Zgf6 zy_g4&m8H)f_B-E>K`UmfbDy~kDKNgMO5uhqBXYp0%AR>}eva0N-3Y0xz0bf!d})f@ z2+`AhnsE$$=>Y%s>dNmk5fM4i(CT0hG@r-+5N+{$fZES@es0*I8Ss>pb@92yf#Ar} zoOLdl9lC{yicbQ$O3|;n4d@?wnjeY_1cLmv2p4v!H-3zMp%THtc+Gy&CM7fCeWz?c z>|fS5&ox>g@fLzBbeW?1`O<+da{a2*J^ zcopY&`(29RE~4dsP972h<2InmI{+%nOJbtbeom!Gcyr~@e`^(z{f9lMJcf=ix&-#D z_!K02*$&uRP|{Dc2qqGy%-_7FX85H$5dS1e8GD>cI}iaj;18|-R1voSw1ch7`!MMM z4R?SeOZ>X9i`hR1xP#y-D^QjWF!F!xVdUxff~eq-^1=he%=1rB(o1=Qs4xjcGiu}i z%FU4u1}FT0ey|3|)cGf=cU0Mcg3}SLwaE=oIr;GYAw$Z|yzwIi(Tz?A8kK zV3GkB)c^6PrqVOPZ-4FGZU1z8iysN#z2ETK$eOS#0x0C;t77#Hx;zALB?*#b?8t=L;lYvTxfWTR;$3jJMd+hLM=@TN`KAWT!2acd_)ok1-$8<_nBZYl}Uf zhxii5i`Xee7#4^GdKsv%sxVYUY9K~XGhx(U;0BU>%9OSs=U7jwefV{&i)}|!?Em8>kPikgy_v|gF3i@Jc| zgl2(ryJi7nb4+%(gxTREzk7*c8*2ybL97j9rqg*zjZE?7$=wbKS!V}=30aqgis@h<*gKXvDtFqPcB_oYHbekgkOW6IYd zb=#pK2KP-gk-DA%^}6K3J>o*qwA*M_q!U=6`Oq@d{LFLp&Oys_N&?TPcsIa$ef4$^ z{~l+YIo#tNVGw<)lEX?f?E{VLb7S}OVRxJCaBni&X5({{%I`D>miC_cTl1_oM?e!` zGj%e64^VB_+2OxUqg~Jpe5W?FGd3bO&E5bB>G?Xof=GU%PBv9LAc#1%<3GskvDd)3 z9ojXvEGT0Ot$i}dIQJpq&3K@ zu}QWHB69l_mdwvs14&lx>j386pze62!)WbUNB4sW@zA9} z{#x_1&54DEEy(F94s_4y#2m-#5FZgaiuK#TA!c=gw8b|T(i>!0$9fZ6cQe1i%M(^%?f8R1) ziYIz3RO3cQuzXW5F-k+UzkhlzLM*=*wE0<=tgRX%89Ijixw56E6iplcl}hbJ0cfg* zlUWq~=cCLqAv{>~1uj72BC2TfMAbPIluQ(*fubo&o5-K%tQdKyDP#QTKohQs;{g_f z1#gDwK21Pw-&;a~g&;!*UnG2PbW(G(A$Z?Kk~)k%`70f;?2H7u#lCiO4&| zrs!cbVf!fGE5@*j6t3Wtjc)}xvGT#8^4VD4aZHa{L^as(+zTjIa^}WwhfT2za?%gx z@`B4Zt79+RP8p*$**&AJIz>$A-wHa!*RCtXW%@PT885th^AM(;#`zV*-uiCE9=8&G z#}-LpD;Uwr2LN^YCaHsHx2AZ%^>{Ej(c85Bx0P~CcT*gog$AsaR0wT34rPb7ULODX zyW@T?eoe0<(**zGCxX87{8`sc+^Yk?;NdM-&DN(pa_Q}#i|pNqV2h8M_2b9o-2EQf z*UoGvb;-6z0}V;&ca;1Rdbs6Fl?Y?0ECr-UT0%(DJfKnBK0v+aUk6b0N-8B$vWQ%l zVvPXU1p936laM|Yo*V+<)F)>`EA}{Z!q-VGTpFJ5EE|TLNnVA*rYtl2h8=>3-TBgv z$Ta@g7#7)#hs}>`6Bt=<3W|!&$id`(=Yp>T;~m4pDaXO-K3?F52-Da5(eO2_9jfFA zZAV}c48Y|zO}-kKGkS0@eN8dWY5lSGFKRm2O;t0JZ3J^uld&2b_*Qk4Yz}#uleiQg zYNVyDosZcpE7_Rb#2IdGV;8QrqPKE3e&XMaP<8dhqfRAO%{*0fleyZUJ>e2yl4@Oc{<0Tly0lETF@w+J)>)Pyt&meXeOTBj?0 zzGUgdICY761zXq>2CIpL|A?M;1;cU$Iw|vX1+be{mudmvWv=B?`kq|DoIW6&=yRwz zr844^ufj;!Y912Leu0=N1F+^>@tXRNGwo=sr^anypHb|GP~hjB(PzK8@W?= z0RD~Wc{3M$mxt`Pj0c1soz_JPSl6yC+k(v@;weF6+U5?($RCHUyLP+fJ6KNyvG{Hq zKkVbwN1xZ72lFHf7~PpnpwHG7Dx%&DccQychK~g} zvleK@(5=5?4tBG)XOlML7Dc29*v!p*|K4yxxmKjjOTRx!?rRLbT3X!?bw#|5qrLUl zD`Y?HTf^^?0bx+du7S zrHQKgVEcm#viNC(*MB`{zRyAnl(AauoByhSujV*Seu3O6_+b=fAX!Mq5iq_3_~VK6 zn&@cLq6Mj5`S7U*G%a7+RFuk>`f8QE`m438Dhqum6#CBA7(A#Pr7!*cUO`;t8x*rx z+CJm_ZmS6raYcc{KzdJ;5wCVL8nKoW=oC_DVc03+ z$X)W&0*51h8|TQ){q<4AZa}^0NBL6vVBRZY4elz}il~7lxs0b|C0qp>9OH9{r*xoD zqYke3oQ%JtAvg!H!({yxoUM}1cp;Grm*({P)^WqrIv-Hpqo(PqCa|e(uIV=5cq~Mb z5BHc5Bcv4G_mBa1z_qXr98NX|G%0%SitCcGNEhKn>3DvJcNf;ByxxydAh}_eM1tQh zn!$#+Yn^G?nfZeLgBHZk<4-Q2zs9wMJ$4Kvcz?Q$9a9D=WT&9;dgw`>kTVAf3B-AN zwrXsSk7n~TlX~5D2Az-Hv7!?RF|+O7+$q-SEaa$P3?Jp(DFkPV-uJK0&3 z?-m=;$e;J&@C_}clZ6!T84L406Nt?mDcV+2LCPQ+5y~J^v5t3&w(Xx(PtRBJR?y)p zdfB&NNy+ApleQwH=J?8eo|kE|M{YXp+K{Z{1^WHR6Ab z-mc&^k`b-Tn>$nibF8vt`)H62s_@YcOp207`pP_s8~KT&dD~6VKWOhN7O6^f{K}WwFY>jX z)GOo_+CUZ?T-J3tnBZ8jp+Gp(=sG9|+Uv3F63UIE2Ek%!4*Rv{R%3!^vl+%g?k&P&&73hg5J`_@8HoAp4 zw%JrS+F9;imfWNbSR;ec%>=Mv>d`~2*uHdl0E{wS|*XsP++Q~Ru(UyEQ33m&f zc;Y>uTDke3MxX$3jwjXQMhnqrQ{eUa`LV%uU?DZY4$I)J;lA{Kv0a&j{odHp)7byv zC*^|dQ@DM}dD3(5_4;xp^x?M&iI5*9GCfbPA8np`Kc0G|{xfFfc=~R`xX8pQ9G&8n zed({rx?R`Vejs!;sn0Sg$EJyD_>QR&N9OMd>|@kw)kdrobA{=1*@-NDJ$J$M$8Zw8 zoi$Rxab$?EU^BWp%u39M;X)ytv8FZv*L^JF`{%eJi>X?S;Uk|jXj)cuIJT1Pj!1&8 zI0A$_DQamwrenBq>NKLB9{1ht`Ju8T+g}wkgAaytm66^Nu@8krhTLX7$Dgl;&HGG% z8f*%#zCF2DTCz%<{_mgmoz8y{=r>51UsxbXyaU*rwp)a$-AM^rG1mf@fo%I9%c29EOxcVdZIVA`U4%y?+ zmX)NPlbd2&L9kk*Jj*G9eYVAV;AO)03p+H3)Gp*(qmb1bn;w4c4 zsNd56h@*mOB{TF#2gvoqfJ=+B)&-W*TP1Rf@)nBro<2&%Vhs69ut=a9qRRcS)_?%V zg3iL`@jw`uP2ZH{D(l^ruakxg0h5;bw<4(O$0IOpr9Jgji)cFwSqoS^(i{=^{$TAx zIhV5_{<%m#8PAX0#(ka?gkJfbd)f;iC=qh0JEDwl>5YkiDk5TmrxZh@E71nicx6z6 z>rkqs9x5NH$wHxJvrPJpQ6M%j1fqxHvS{40fRnk+n-F0*uTz4nW!6vf(>a|{(!AFKw!GPam$${N#X$Pd)!e)GS6Nqux!E%fE+rom66(9pbVZ;1Y zEf8IlCyXL?upR`SvNWq`@xEwPpv*(DhNWAKyIE=0uA2W+9-hs2KLaRtRA<|Wv|bixsa3NFA@{?URP^6VSMCZCebddumgrqTIS1^=(qFkG(?z*M8A(nz1I^x;TFRdZHX2`wrkwQDP{+g>=2#E zDG-bnHkyP)xh9evdXV74Oc?3*+M{&PJPC=a__rMVfd29zHWFk%F+goltVdg^V|d?y zq;j_=##>5(Lrl;c1gali=8QZ?zg10G&~H1{+fdci=Ky@kSjwz-Okq6q-MC$`4a=!fet!eq!!e&8 zXb$8GLz~Caa(%NV)&Suwj=1RZ@8EEj3vF`F@V59zbu1{&LZxxOrys<%CPQK*ox!b= zuSJL;z1f)a%$@Rt!a!3IXbb!-#ScBaJxhKO7r_$8EZ>?n0-UtV>CES%_~s^Q9=>PO zu&AwGw1>LF8N5$_Hf_Y~O&ycvNV|q_EO8pIkPwUysx%JU`@$#}iVFdCG|BA|b7pz@bgYj63&_PkISILCZ+}6<7I~izt z82ypJ--Mkw{Y6yOJ+pjP6jUYevlf11%6LGX^u^629;op@fcJhWhg-$%4ZCmiDS%?0 z=^cbmd-#+-2Oy{VVr|##lM~LwZ&EAR= zctsA`?{2i>c*FbWi8m6*v`QWs4^RMXRfNBjOph_MEep zy(xy5wn`pUE8t~xZ%C;Z1lF=Y;8z+}r%D2(@mqT8t9F){A}ZfGys_+DuEr}&KcqH5 zkN&bI02oK*jrs&pkvH5Sg+39}Dyge4LZc-h?adiYar}MGy(VIsTN=gm7epEQ>`fs> zEOYbqNkHcIdgyiEo(*4;e8WPvA7^T4ZG<_JAOq3`{*{ZYGyJTIGc^T2Na)5uX!7KH z#WTM&KGjnPNWhXy_|iM!f{sawXl6tv5(N8o0p87WF5&FRfqcY z$?^3U`uxSXH0G2;mTL66P=XNQwB6>g@yt~Yabp*k?qE97j9KlI0a6T570&hyu2gpd zEceM#1{eC;Y_IRb=m&g{!A9Gfl1E1Gi=)F9HFt6Q^V}?-pE*6~8e2IU^_qE3VZ}W+ zu}+`;yUL^3p$TPCR5JwqTPZg6Pen+Nt)1s=4c0kn8E>bZj2TbFK2|Pg;!*yGkKA9= zk0mWw-_X@sq&S698b{&cEx8pZ&iuoG3jIuw(-BqWO}}QN`^7b_9lN?_1|b6RRLSXw z2fTGk_{>}Ui*vU33@|VgUwe2nao!Iq)7DPM+2XW6zYIk8 zh|vy=QE6428l3}r+x}%^u|DV@)FSYKl0KQXgxD77*5#Gw>?s*92&ueN3z#{x2u_C$y?@wMSUl2CIk9Ei?jK*z z_h;K;gX5^L&Fk#d{EsKUfkE>FHkvFnWeka6buoE8!)%|kPXPvaW<>udpK$tLe8Mbt zRM*ga)UmG?vxB@62@}F<5VwBlDHwAR6EcOg0hF?Z@eP#2Z=x9Mn#h7W2o#-(?eAGV z9x7qeglw;{tLE-22Nr#Z=MGbwH=cEVfSAM_bb&sRkAa~~=CF1JiHUavub@&OUk07<|S1PI)RY_Iz{0nB&*lA3{zrnC;N^&OD<^jj%+OF zv9eX7Q5|{n<_>0W)rueSrf79P+=Cg|G;WfD1#X&bp#`<_TcW~dPd-x%PKPKzfj;?> zZIY68y7r+I#aX@rO#S@lYG#>%)sn)oS^g{ntc1*H>s@h_&i1vc0LEFHsH*J2AU!?d|gNU_4M{Z!(E736JsX3w|{%$g1qRc>Uzldt;e%7Uc#iCyS z_HtTA4^!gLC?`C!#GdTh+r8j7z#H=yt`Id-m(}s)tsOy1R8X=X5ns&XyP2aFx_;;| z|9b`7NV3angOFGE-FaJ{gbH->V6xV=TOGm*^GXhvk)NoYs%Y}@I#+j#>v7q-`7Aq> z?uHQ6i}5+f*q021qrudrr5NXJ*W&$Bx)<^xn5-EVM>FGgGgH-pZ0gh;K)>1^GZ!YF zt^JAEM~fL-Hgk5+@a@53_{aX*9sX|BW~>hE)uf;By3K*pgezK`q5cWQq z7FUNmda_tz9K*z2X*8WefYh+6`dK)bu^Ns|Tba2yw@CHIroFtYQkgTANDVYjd+x4w zTD43)@Iu4IsH6F6GJ=GOUwy@fZZR*p=U&H5?bRTW#yDY1`S8zumzCL%&yC~W;ioR9 z(aXbDt|Aa;?h<5$FuU4;tvF|pp zUwbrW_MN=tho^6*msFvvgQKgnhqKOTRab3x0Grq8%RhbsctKQn;7X^O;Z#)LKtxZ&S#pCI3-^n3+DC-*geJNF2HY{_7= z;&&B4u;sLKR5XA+e;Ie3IAT0Gy8C?uvgMf_-F3_uQ>7Ue!{Ae`M%RHakUeRmHy~Oq zvPrIjJ^~|kc0*InpF7r50N;U&vRs z!W|jxpIDZT3YJ_L3$wc*m0Xoe3lXxAk3puiFVdb~jH8tf|4@zxH6>|+SgPu+tb@LO z1HIqH^PvDnplmx3sB)mvd>-NtFwu3bGM5?}#Evd~W9hxtf+Esz5C{Yjm7h&I!*gHZ zw8Z~oq5gAQDWnt)h;TtFDy2g$(z#L!sYFwaa6v9AEsrA3{metD{<9A1f&ys}QDb^W zD!6w7dE>_WZvuzi5IsO9Us4o-+Q_kVQHF(v;*1i`zywCUD#IYwdP%_#U{La%3gS2B zh@Ws=g!lU?m0X!_VBbqe9Yn%}Pa;B?Mm7`wC=XqsR&KtqAr2^MWX_+K1Y z5GZTgBJPFM)pMdT*Yt!wkj)~VT)GO34HabsRrz1aU6d2wN>RZtzl{m|zsW^xt1eh6 zzgOq`Cg`9_KV>ouDlfRzKR@JdC4gW=oQYLIQ(~)cgtBgpQBAZAZ$G)G1yj;cjJi_} zY{(%v>4|(B(CP}|0ir+AJ37fzKy&R&nm8w#G?4)QI*{Siyd`Ho8?qyxnVX%eQNPfvdG-}cn=NyBNM>SS(T@3!&bqO`&9>-a**`WT=of&Mw-ciiz{>hBFWkQ0FEc;|o zj6Iz2N*1E*PD zoka>17hpd;Vitz`r}@1xG0t^E>H?yfQt7Sz;r`j2;dqDbx$4*H{gMLRQ|Jvmybry{ z%kU)IV54v=nnZp$KC5{+<^-N7d-xlJzN?4;pg)~=KWKQ?PWCJ2k>QE{X)n$qBW9OR&v6%!q(U9F&QQqMmDLW7x-n8zd~n(QW40y z6lYp#eQTTaEv&upcT!dA`%iYgxNlN}e%HZ+J$|=II+S12=P-6rR4CAbyiQx3WbL%* zz`xG#zch?=$N!1Uvo34(9d^WW3o(Kaq%%cscUPHf@VSubXP&=i#t6aB7fx=#`kN=WV0a*8M}bFQ|Z(^r(5(HjM+i zq~bjMPmlVhE*axGbQN||lJca;n10gmZ@zFD_Qm3dWkxO`IGXKp8yFr^<@H)doBQO| zFS6mSEBNZtV7;TXjSzylgii%K-U}C5rdv5XUdj)hSAk!p2J}^sow4)gPcqfKz{ikQ z!U4Uo+_vdn84ZO1*j{_UyZ1wMo&U#1wzq~%<`li2IT7jKWY#hb5#1$%b zAbZDeau;P@l{%r0h$Gg6-sIwmZ_E(N(&nC5$tn&|QlrkON|dK9KwYJ-n`3SV^&g;G zFsDdd95dxJQ5kooNW)%u#D2--widPdE~=Sj?W)X~SBz-bU_~XXvcQ=#P&~O-d4b^< z=c2;tp_#jvAk4)Bd%s&Srf7W7pea4W`WBXB+>F!3uo=v% zHFXHoj+qP#K@rN07fYY3jhn*rW`@a^&S_2E#TqrFou?OX*gx7sF&#E6hpa($5v@Fy zwevb<7C-vK3IvL0y1v4e_>?9s)8Dz<+WF&|^19`%%QT9wk8K3=LC$Rimv30=&BzO~ zS&t)@u1a(KK&}q=oOM#?I9{dt&rhGMvI4&va(j^H5{rvgIu;uF5Vl-WQ7EUf_kdUo`jq z#p(pq1S_mr*A#JsvsK9?`A)+Ey0isqvC6%*R*juwS?OA;oZn8N;9L{#dp%2+?f|$C z0?5qVeT(#<33D^tUICGv1Tz~2h<6^uP|=Y%7Va=yb_(yL9WgVTPw;o1sBqCJt^Pbi zDhAgbh5+QurWd5^V|E5OfgB|)KG;YD?dEleE3&5Q0SeZ&pf$I|A>YaT+SZ5xGWW02 zDKkGI>b^Oug=TVwbjf})_sDa+9U!Y9eh9sZF1+pisc64?$st+3L^t2j9AplIvt-xn zhg25X>m1ntvb^l6tBkeqpJJ0Hds8eQ^eR!`H)LP*XozzNHhu}>@7T4oW+9c%&WXR1pAH?`ik{D0HU329~}YC!8_)vTbK z;w-%FzmfH=#~SRdz%bhf&7C+HD;+G8#Fb~d`CgWr>!)uh(w{6^0iJ(5{~vE}9Ti8E z?rTGE3GVI$2<{F^aCdiicPTUwT!Kpo?hxFa;O_43?&Nkdb7tl{_s(5s=A8TeQ?={u z-BkBlH2mu6XTMcukhpKpkNTCm%h^W+{cf`;rYwn5@pp2C|K|yLjohn1`<{oC2*g7rfHBhwxOQL*H0Sd4PiGop zBb4DK@Q@mED4_FFogSkZu@WaLSSc6f&}_{cv&>^D^Lqin0eB-XUQ1$SYDT+7GiHG`XahnjV zME)>L4q{t8AWh(k9Z^5LKxX~Z@NXWcovGy~6bXcwr_!;+1}5&3g$PGR#-5PLJO-&9 zwaB;b7)-Lc=04o*UQ5B<2kpG<0KGeX9$X@#tvP)O*z*HOqMl|SG&0Go`ZT%5Zqw_Q zmmkjSMefmGp6k=j3;rhf{D;wFZ zR0O^Kt}D6v)7z{%do}QKP$n`Qi^;>@;R*}?8H-@iUibt?36}i@#o-|won)jbY?#`tQFDI3q_(zW z&5$3#DjM4WpL=f3${L2g@*-I!iS;>wEMF3Fvl_X|_c=6QFx4wV^!eKlm}&xd(8UV7 zwl251oU8>4lkf$yL{(Kkt%A#6*<4kO1t#!9ErA|bym-ID!=NZKKYR2AIS|S|Vb!;- z%GCIXQ(s0{gQ-_d?2t;4jM&EbOdY|ohPyp;{%+MUa)t_W2GT+u!Ob%_bqBey@n^@t z{2*c$-V=;@K|B8U5FPJy#N1(NEY;8Fk@d7hAcZC>Ty_!N>a-L>A72kkyf~Z%K@*5H zU9{AS+pQ6-XB)v#jx=qm_^J5$BuN8@CZO8Sa+`=AYn1jpom+HMT*e$r+4MtoOjwZM z=U2RnkdJE!0T$XeQ3t<@E*M@PkX{0TE}YHpUpMJQQRLKP07D4L-C!fT3+JuIZ?jU% z{PgcE)l))v^g@bwz!Xwplu0-s%J_gwcYGdEl2{9O2ew4WuS=YpHjx>Y8t5z?PaCTV z)Q37SLhowNl`ukSjP<{FcXokcN45bk5>4XD%_)+%09x_FQ>9$&R|v3^Z+_1*-lE0_VW)`sK^}SZUcT2 zj%jZsFH_zW+ZVEw;|gI?C5W;@z?og4;1a8+EVXZr?6_{SgdI1Y4=<>CPU+)uHLuXvm+_ zi5dBti#*ZZQJL=1LuLG9eaCP3nfry@zU3TEcCQsAMBnY7FvUUuSv+%-k;#2Z1l;NQ^PFo-NJTsr5&{prB$Rc?vf>f`AxIi`lM-3 znbXcMQytI)BTTou1`p#GT~j1_bxhH9MG_C25wSTED6PM3ka@I9O$6C&BKk6Z{G23h zS)UtUv6M6L(qJ8z+c0PhUk?+5Pbi7s#~e*PvISNs{B|4m6D4pAxIacUj1k;L-5VkE z->u$$r0_QmGG>V4s7mQ~%$ezIJZd1wnabnD>qo@OMZd_Gt5ZSo-)lCG4X$j^4(UIJ z`*zD3_e2_-nyyxd248NbxnN!h@?-)+Fw+DIOeb z6ks=5mxL=W_>_^1bN@;127HHFQ_g}v?`B$0QLeXS8(49tt;%=zfmUZOxIHzsNHW&J zK5_d9-yBN%-b4Ye35*4KuC$0{QfWpxLEcfn}}lPSL?tm#toANJE7YiO9W} z1*1YF5&%?Wgj=`m1bQxhC@@%uR&Nn86_8we6i`_p8xEODD~A|Z4B9=Z4Si-P^W0e)WIs`&HU6aHrkwe`ZAD$!yFP#3;iNy^Qz<= zW>zQ2ZAo9EmmB-eoD*7Cq!HMG13RkYGk+VPJZEjlhS{$;Wd*4$Q?|1PKWq6=ACQ2@ z8%cY>#z0#sxrI(vF#&(Btf9}o&#G$k>F{{rwsqYGVVW~OP-v!`Za<5k@N9*KB*xB6 zQ;Kyedvzf+J_Qe{HZ$MFg)PrU+-AWE8Uk9-m`VQ}9W?k{yj)zH4~Uk*y-8q=)Qnck z?=IOsV1|z8w+4Wu7%IEak0`TM#a2usP?qnjCg|Q@(yBHUj`1Atq6x>}D4l`7 z89jk#V7_N}hORhy{bI>KTjHv2wjsCd?vbQ`6sOvRdEeTm{b>aULCOY%GDcfu|F za|AEJb6HA0#&f9+x1mRVS!!L`uFZz$UY~>{c4W_n9@SR)lDDP#eXs9g|CrMOrAdz{ zNVdEG{*7=>r0=!(PL=YEqZbK0#oSMoUFdm#Hm#MQvNi&(Y$SmhM;O2z7lP_O;Cc`j zB7@5)i#&r_AM2WJ@xxEQ(;tKIs(0$3Pc~6WQ(y7v4^5=^hdS&=fHy zJL=Fw5!E|@S`yq%*&OLAcc|IKK;pQ*F4S4%L%&!@d*QoLrv6g~ z?&njoQFZ&${vGpCKE_e&WeD7gS=5=)QtP{b)W|^6W%=*20KpGt5=xca2vywgQHe!- zT2+?>J(p~Vxc+s`FP9;5G5G}Cot6fqPs9i%8|6uAA3nB(Ax5#Xm=6th?AIHTA{t{U zdx7D2ol_JkXcp`*LvMqlA>WwoH`YyfZzq_TrOzd}$P@EJe(7}@X20D!v9cV2XF2|o08>7g2NbH( zNGCoqy(V@Q)z91=uu+HwN*aCfIX2P?yU9XSSY7O0|^u?e#lPsLDHi__^~K@fz@xu zq@rr;*sR3yD*97{@+RWV%C1sNJIhe2X+|`wiuHoo;Slo3+hf5!5U%CimH?0&-JB4L)$xg#&}=?TTs?#iQKC#^ULz)gM)wru9_@Q2TLYF zeC1q$uR`}%2h&<#N#d`?qGx~B`Ynuu&qeXME^#$^@wpG$hZGhf$~+Qy5t0D4 zgqlR$t2wz>pJq(X$b(BN8YjfJnc5$LE2uzYyERf3@9heE$}gGmA=DPFHs{Z z{c7{`V-`+?2iC1eU*hCS-c4Z;m2FHLvT$20PMLe) zgkOk(R*ydJjQbguKA8~zHBghK+Y7qQTx0f<)~;?bpQ4Qw^U`4D1xKF6EoKyF`Qn(PiP z%06EF=VZGiCk8t{!GAG`w;*l2fV9yd2F@T09LLqz7Udu42{-j*7frP}@-RvE>45kv!;@M4H}*<~6^Cb7xez|ZZLK2y zWqsO*Jt72?9k07lfnqW2PILPXE^TE}*6Tad1N_VL;`yFC%sOy>y(I(40zA^&NS<|cDB z?2|+YU`(Xh{irv;qHS4x?&Pp(1?`_@+W%9eWtkHj2sm=o(J3z(a*^7;QTcjw$Qz;C z3K();>g&0ev^?S27s$z+9x=!?hble@m4!~>`-3S+{K=#zZ4Ab$%@wsznt$6gK}!E^ z{HNN4qxiefMDS<#r^Itdo%MuAoDQvd91;B4cJc$HQZC0{ zqF^7xa0c?PXPsC`#pOKM61)!vC=Y6~`(owu?}%V{Q83nvKHy|(bO$?a8GiamvA}4r z&Xw3BoRZfEv#=gYDK)KpwaND0?|3;1l{-=WMzmsG07*PRn7T)Ga zRS-9I#XrfMu65QC0oRQSb8@|Oy&HI zyDi%0E*sX81L?E<$6y|Zo}YeSm19{nO@eqdsVPd> znCbd(D~P4qt;1Lm^w}K~m%t1#*6;s6C)wE!!NO7`{<+8-!3b9IuhZYY?=@wNra_S{ zzo3G#z<+o%Ne}MP9&NFPWEL}%YQHPxILj_6R5yT|rQ_A3Q4hCgEiJi|V*|6taKf?b z|K=twkRI)sL*$J)ElPMUz2JPH8iBRYCGc@Lg{D=gxm9f&(J<#z`i-*k*pUM?lknui zJATt$I!EYAD8o@ik5SEv{spj64XMoPS2{=4_3eR^po?Pg6y6KpiRe3oqLXaB5e`2V zMuYY1HTNTVLuIcK&e7R}BqpQ9xNEnPaXlN!E}3Lw$u~lAGz;Noxf5Sg;sTRW;sARi zCBKOX^94jfd0;Fh+TU=%4S9(!R7PN{Umk84D2joTis9B5Q(y-lZcp)YiDxb z0>*W1Uq$R4N4{MY9MOf53haDa+x1|^?9_b5=!?@=`Mp_3vT=N zH!EJ)Xd=-1&&jXfUvM%T8gg(P_`>2hR?^YKG9H^_jn(249HnO18kB&+u~)#`!eUSLImBj{#x+wN zg4{2+;i-1?cnC<_@?@MFt_YsGbol-OVMwVMy8HM|9l&B?Rx-LX*Z9nn)E=YpC&RWU zYWt!L0Vm3@9Vtr=Vb0yt5|cav9*^YIEOSj)mE*W|AbIFLx-$7$gxE#kNA@h;i<() z>fm(JQ~3irr}!ESi?US3-G!4vz1t=q1%sCJzD`2H{t-Uhts3#nxR{4@)JIyZf{a2AhG zNv+~akXkH7Ju|(0+-81_l)98A13bHiEbTF$wtD01pf*Nv`t~gm33fsS*1&i99l)=C z11zQRNEMZcO2w5{ubsKbDm-Po4kx)d`Q0gVJiOQNC!gpPe>^Q_^{?-s+O?#Gj6yHrPfDI3}|o`v&T>b3qv9A<6=_XXWgTL_oCAg(>ms39uRL|lkVRoQMZH8D+Hs{*)&D_V zyZoc^ZIIj(?!ZfoxXdV>797+ZYsqnR#_UcsB_ zXP>PO-Lcjmk##AJO6tL#euPigEa)N2wQs@_HfvEy!m-(0u{;4mlVjqCra9x z?}OtVP3Pw$YSRecDC+^cw1KXA8?+E*1vQzQ{+9eVGY3WP2`%_?BC{A-Z&eM?Y!h82 zW?f>3%u;hJ!*RM4u~cB>DYUBd2gT)7lvF-^XICLjOG||>b!gKOxfyVJgP$?|VXaYf z%4E-zp=hALjQmzOnIk8HlF zrj$@&!Df+A@r4tjk#=n~+?4MiTSv7L1ZE+M!d+b^${7~vVO}%CT`y+CW%PU+W6PI7 zSe8=zut`Tmxe2hvj*y%?Q7u{urbE@qdn#6G%Bn_dmsBIF$|TdFiQADPI;xm3DUXhW zn)^*-)sl`9`;SWA&CR&sw0id1Zg;kwt9snAufHawF3;(tx}xS?`aeb#aJ~W0j{7Tp z)#)#F)w8;*{oBR`F8M#kz+cKP%(=fSF5G{1e`dOz$_d@E3y2~(ReHFEGfU6x_Hb+x zSbyY!X*PLd`P1r*Ck0k6Z!eeZobz~MmXO+|PlA$b#jy(Ive}ZGyQ*R$kwusAnaT2r-M z93WR1w?%9Ta~whko3-&6$Ac^?U+6KXjmgWOgDp(e9BRibow>AwqGNZ(Q<=2TR@P7W zN&QJT2Xnoss>5>JtaLGSdZGHnt8)pf(2femzc@r~T-b|ewOL7sWNox2(KKJAwHlS0 zm7TznU*_o0TyiO9v1$(y8qv33zhj*m5r9TSRB2SPl8Mwrhom*bt0k(C4pAGJGD4*C zaE|Dti0+%TF?W(Nr(75UG1z3N1Y@NlE8Bdt@){VSgY$~*&RDyHaPZhu#U_;ii(su8 zs$C-`rl^Nd<vTVjQz+UN+u%=iC>u{H?6t_fvz zGY<9qD+8&_DoO}Rsfo&*ek#JWx^a%0`nF1`v%)u*`4LJ`+xCK02*~s$Ol`w+t9?Y> zr5E%W&r-FM%F(WG4HuUTW5__GJ8QjR@r_~Uu5O70UA||-+a~2+{l@kHb$PF&?9i z_xlz#!4cpqMhTduAQzuxMxyKt9=A%FDs($ z(Hfk2>Sqap()$8V-o#6%BB;Q$H38zrXLy&*&`5BaA~KVjL0Fd>=^gHvgguhP0)u|o znw66zLGJ*zoqjk~1cZfO>gsRZK+DSUHdT!6(+Bm(zb5!k*!6zE>3?5%3&wQ2E}@uH zBRkRfwjb2j^>A$5X+`%gvK|S5bcP~^B8A3bTjM&7&c<$8!&adAC}0d+FmFTLNA{o9 z*UJeACBJ_F^EJBUU7{wIuOW_KOZqCXsh05!{VIIZ1B$;tP9TinW7JSsXFRrYM20(s)FE|fAxm6zGQyj*RYWfewGAb z*$LZGvGF>L5ix7|2{-_5u>FfzwVI89YFt0q``9*(4^(DZUVkUC`FvKpR#njTY>)IF zvk`N~Z*7CGn$JLOdrm#42Fl~iy0BM;r9svzv9W|kThloXl*0lL;k=`_uNxB9-dKP2-!SLYD4uWkIev3A1JC^KFUofb-vs@7# zq7u_hN=RNt*&q0Nr2YEA)PbJj$^|~kc}&kqj;GRy^X3R5laJ!>lW~dhI#S%ddwDhY$k10?=5IjT@=|M13{Xv za8Z1AI9U5$?tUp8?)r=U*&sxM&3?rG_7~by+v2hT8(NQVoLO!tb9*2iLeo*e4sE}a z-eOV5J3KOd3_s?p;u91HZex+QK@Q?8@b;*rQhyGgrzdt5IG^YJi`-oCrT_hH%&+wIVT$Kgv)eryMdanD0m91nzwTU+&3Ch z&zLDNs+c2;%OEQ7s$?Z@bPQVHBE6Y8&?-wf1SL$0#z+hQI1J7_oi5EuM}@)xM@56Z zjjq8PwcTv_9g6xpu*O2~T5+UcT9}r%F#Vr&>ch^NimH?z9wQ}mw1z3_dpneSKRJL> z?7R`xq1SNkCQ&sUV+AfJbH6zt%1~M=P-K$?int~m8!E;{ZA113CR*Q|V#UR)O&Qnw zb<2t4@mwFJj;|otW@W3IDKorvmMs^}Z~i+hmiJ^|AjSgC))-)oHQ^1~B7)+&X_K04 z%1h0619w496If6chRi&R6T#~G-LtEj8q~8({50f~rK9eGkAWN#lk zS#w7Cw9#K%jzz(YX1=i|05vZmGlW>#(+xA$-dwYS-&f1Hw`~<;XW`@0P#NGCW`?Ql zX?!9qW z*A|$f2-fLANvr}2dHl#0Q`uESJ&RL|(csI9;1`ysmGvX9PH2neGSTPvbFm&rXHpq> z=bVIf;otDo*=M23C`ioQ7x~U4V+K_VQE;D*jAulThj`IBpZ<_nZF4&tHo#4oxcuHA zspW1$BJmf)0PmzeRM4ej0rCV6)GX|tyYhvZ(oJ_8@K|_^5{lzz6j5pOqw-}}c}NwF zSA9rzXN@VjJZUli8PBk20tNC4xMTis*u(4<$Mv&Db8NfT`Rkb^{DUSPoqDaVyz(WL zPaw0Pv(S0PHlazU0c}F1sX{Xkfrsv*#CeDGh-NZ@Orvf4$19%B?&CWR`#&7krO_7n z($W^@sN)kdQKEJ%`dcWdJ!m^+2fwSB-u|mlfIJ<>)rty>k}!R0^~VkPVET_F7KB=* zI%@s_&4LQyq<>}%{bl!O>;$}Ns<>d*j0s$^x;*`xQ~>-xu?qg{Qo+Ar6@1eGt)Gr# zb%Dc-=0nE%l8R&CXiEamUzH!8># zS%J6CEp7#VLTwoq^dr*Yo@V5-rj}gOo~g4l6JP5{YfZ**5pkYlI{iB3a1e2DiXBU4 zQ}Jr4V3kMNEcta)kSgK|`f#K#_i+Lxh@$hB#&=W4C99G^S(X_ApdH9poLiP2)3!kN zo7~VF2qa&d#D*YS$#X7&oPw_}mKpBL*C)6_Em9wVqVONtc|#C3@ZCFT5Sk54k1(h> zW%@l5`%;r1Qf2J#RJ({ZJS1uA#w=U;qVplOg%n9xeWY0SYL< zC{p5D-9_1$A9?(j~GF>j#rEU@m8-9f;xH%h!-@!rrR2iDPVkZ1{B^8H>UM;x#Cm3 zlStVk+F$p!iA!HT*&>DzMoa>#Q=6Y}V*YLtkjmgLMsIux=M6*c%i+R3<=4vxY3g=Z zGnB6rHb!=&x7Nx0&(#Z9mTl4?aqcoPack4wM?q7UDu>ZG{jpB$)|(%_vG;1rdy}O+ z-PsQuJCE5`A!p(5D#7XEAC-WyfqT@w(G>8dPfv_Sz|>UFRAk37#jZ?{;MMvQTtP@S zc=%8o)Fk9r?e=A$`m0sJCCun@lu|B!zHHpA#AKpu+^!QyD!^1Yps-*9L0KJ2iN~DC zV?rz8D2}~3i%E?4y^_>2?S_+V=7ZiQ8k34_N4e&(&>0vy0gBWj*x`T>+C;V0*U{!O8`jy56T4p zx=WA%td8r0{Ueb5|Cz@E{~5^s`#iRA5PQ6*;y)BwbUSEAm9`A*5%)=v=2Cr^2?iKN z?2|v1tQOKUKlaIH8FpIRBj8A`Q(toAD%CLU(hRy5U17jUC|@d5tVd8IYm&TEDRCAy zqx4NE=QHLPX;P#ZO5&T<%Nf!prbH+oa&c)aXPBdpol{dNFF9lKya`+B5A@k6yF9h( zc%fr&tY~ICA(PyJxWSdPgM9Oe@~^42DMsV3Rsl$N1^y&jG^W2-{uB(w|Lh$9?EaE^ zm%sV_abkD$(^{H)aq=yl{!c!^zp4`e|HD4Pzn~Lvnu2r!;D6XB_*ZoT;Gc=H|E5py zuj&NAKNVyDJ)ht|=>%%bCU}fk)~B_pHHO6@OIcDX(zU~Nf9J1=Ko$}Q_Q%7&5!%19 zT2_?E-;=K92(49B&3G<{$tHf&*xA@UG$s&~g_!w$q)ICBo5q3?EFI~y)u+sax3@{* zq7Y}dlN;uQQKnrJ*mdpB+H}{?Ttpc!R7fAvc7*rYA|e=3*cSK2qLmq>ROssgm~0_O z8|^&Kj#PS!x+XX+AMUzOgxWzwJ`XDH4pCHiTzzV3q7M?;r7iajTFx2+HiR~kuDR;!r@UMRVe%!5oa}tFV zi<0W_2orHh(B(IYou7Cc@MpmFRG>X>;_d1fMNZ`~9PA3!X8eJH@QYB~!h%hWCYN^A zlKEY3dEU_*G8iNzjP%91Y?~6aGwjtclNP#8cVZ{&TQ~d{0aIY*t6{6!E7SL<;R_$@ zW^57pY6qqueA?+RquBvFn{VDi6TZ^E zYKo7cdM=mv_b@Z)A(=-%>yRU8gmi_6m5(B$vC0rM(2XV?!S?)*<1mrM0^8AT8E}M38jp zcg<56y((E2$!cZJSf=aqLFeDJ*hMzY2}IPgq_V+JU3JWPA^3pBmKuRATyvlDgrKF? z%hSt&63XJxNIR@-`2*`KXn`ejPrgx#;r$HqfLZjIbGH=_)DF5bz0_8Lo~34EMR6LI+h zI4{j>h4SN@BL4!c>w=Hiosa-hUb@{cpld0J+LuGNH__q-YqOgp{s(Y6pC|g09MBH(+x0~4x7++i^Sna8>W&gK=Hnrny>#(UmQ-uWZWOdk0> zYfqnKa3Oa-hkCW0wd=fjYQ3r~bo^-(;k#KrOWMNuc;A?Rx^LdXp_xA92T0T-N3VZ< zbP%hgrLX84!{jXz2=^@dpyg+47`j;WrWO%KRd&c8<@wi%&Whb~T@^5<_d{IIb3AvV zUR4BzNvg^G69Q&YdCGqnPEC4SOyE zN8g;{wyiAC-MdvN1|ajHB!M_&NiT@NToa`4R73HoyvWszNO~#ULA2C?tuXz)`;%mW zq{`g-He5nf`NgzdcoGR26FZ!;`HP0K&{~MY%IP3Uftvg_8U2QT*La&~>MXiG;suo{ zF?IplN{(vDL{{{a<>i&ON_ovB+2_aj-moyrWI7kTJIadnSsKCZB>)^I6N9NYd#pqv zUV1=UF4iQCVP(pFYsj8lg%B4Qc6lsAjQrwUVj;`2P~XV3xmHs~L_)lhIGi4G#V05r z;3L~@=5R?J+1Dl$-~4VU2Ww*Gr(aN7Gh^%z*bT@WKMHEkYYk3#wiSqNk!z!>x^?JG z!Z>=qpqm8_#^ucCCm@_~fZrnbbNFBsUI1>2N>pE_EM{~bE|P=+TTV0A<1GW|HbK`0 z6yx3PuWh8lhb$w0;(WgnO@U020hRPmW^|8c^41n!udal)9C_}xoMtpSUNPm6sKJHK z++q%IjzyUT7k$sycvn9ysdy4#E)COSnHo4ZwT=xMQZbj+z5$x(D3@T*XU}gaJu1{_ zcSH{%M|`Y$Y87pQq4B{=SyNJ2B=SF56eK1qLXRqb|LR|-v?%+d$&&YG|5&+IGL!h* zWeW`$qUzS!tx|K0hfd9XgfMz@A$i1Qp|%j(Nl&7sm}haK%Q%D$w#liGSYd)^l2{?a0im5((L9GO$72EFU+Nh(L;FSXt}c`1vWp3B zuhi5hab-yjZA}faqf0X$&7iL_SIal$dF-(HzK$*t#@8colJQ9030MD)#;%DBZF_7I zP4D6^Xria~_FV_X44RLebu!9Jrd%j5JuwcNnm$hinjNd69?Kn^FnPZ%Y-drpU!?n{ zqb&CzBoFl1h>&!YHXkFfqhe;J-6yw_r zy=}#6?=t+WuDHgE<*i+aL8>k6Pu!0<6Qy%U_q3!Ctqc@TxT{I#N(E=wy=y*!M@tVY zoR*9Bn)&*o6=wqqdAfSrzoz><9}lmvgYKbo0Tjw^oyjn0yxK(`a+&Y<#NB-1X9p?s zSuUC3IZQ9nsjo@hzu|6@!K~{Ef+q^p(dBgg>ddh2Hc(U?5bIde7k zYK~`>N)`N9+WA748S}3)Mo3T`7S=_ zt|8%Z0shw;xnS^f`}}ynl(5Qb1X+gZpYq*o8SoP|L8OtDdl9mn_oO*fZ+*M=ogwb< z-p=r#%3HDe4W@{`-2ydJ4&&pWU5OFvYr?;DkNEtZ&~Kb-PKI)NnQ&O! z8S=NTfYI6c@i8tc_(ZXocEZ1l@CY5K7E`j1T7W2W9{~9Zr&aohy?x)0!4nA0JKU8} zigy*=`sA<5pq%|OticKO?b33Ra+Yl`lJ$RSeZX5q4MF4@D9-F)-%I{6C`SCFzt8=E zFWp6b2MwwJG2|LQmlqwAfcXKPBv4KjFeLc-s2+4<`>Q)wclGja zzQVxji&1#UI_v2P*i|oBgV5tXHiYeqVTVXNP9$%v>Gp$+Wp8qHlcVDb|rBZ8rSZ`-D1GM*R_6hPs;Wm)Hf_gLuQx(5DQ3>k4mC zO2Gq+{%qNW&QAs3GU!AJ5)sAX$3KqdeS#7=(r)Am4W}6LsjIYc)VZ|YxG$`7CIZ%X zNvN=)h_j_u>)6BYTtBR}lm6cy%E_PiBv0epHXUP^;)13$} zm|5K0$svg8Ae=1bKEN^|48nmqAp@#$aCtZ1x$5cr#b`?EE#jtciGSj5C$craTYRW{ zm}(;7dw4s(qaQ!TkeE9(gdKG2!4+6K`?(r%D24HWh1v|P;Wm{Od31qUCZVE^@Y3~Q zVUv45yG?L`uXBtB4XjXz60J{2u5L?U-57#Ma5}#A6Qg{euh1xofF!$FT^MlS!8HoT zAYKw_KAMQ!kK2J=SUb_@gvCc<2A*CG);^jJvn`FXja#W&ffv)PbcQ|T*)C**J<7EP zHpti2>EJ6_&uyyO`fYRJK&*ioI?mS%@nuUHZKG?N7H)sCFjvni*Fs-;awS@_DIJ_hG0L{vUGC@q zVoZ-eI*<6};HCHN>_E-416f-2p>)(Ct<)v@2`2>;nh7CX-no(<4ThAx+IlYW+O~yf zRCE#kh37@I?Siu=UG6KNaW5=J-g1j=Jw2c*?}*0T>`QJY z2sX4}c678RI$E%l23=*h6jVY0L1BtOZHhPJ*dHP%z&GmJhr+TH_71Lbo~;D`{{0Ho zao<@W%|pAMFE|??eH)SY8x)6{5ebxU!yOj7Ozz1j({0c7A~z-u*dgJ`E!nbNH)KoY z3rXDczqZ*`lEuUZ3?_gB+QF#P>|;;|=dFnV`RJ=j?bDxw(F0rei{~Dt?^FHruj5$k zkERNQ~+FTQ5^_dT_tm#Nm}8yf?8zJT0hvHe3)u!8RQLBT|xj>>GkPK*jhb^bz{=A zyB5|x@GEmOG7Z5lW9D&r`<)51F^~p^FU8^G10@ZrNX@VYT{CvYZ{6j_peDZh;pX_KMfyVXA#r#?@#?0Me-b85KeQ)oYBBW5Zlw)ZwZ&* z)2VD+7F!iDU~mBzdr!rAPTnwF1D=b$?Kxd5aC6tjPR-DMDaDi% zW9E=+C4J}MM8l^5_x_3Q^9~oAOyK8%0Zw8}I?i2jwPXfhS%*jp+n~yGQr!D$lcFum z?bQ##kIwbg|Ko--))5lH=~7qer!+3ehjHE)tL4RXSFhN6uaej_i%d0!!zIrqy~&;Pr;<_yTMm{ey0azjjHd zW(l}PiLja+glZY096vb84F<}zQh@B8LH<$M@%FCSm0o-1dWcZW1yg3rjIl=(nD_>b zjz>txw4&N-=f*S-N5{ZyTg&Z^|4S_+^5qWw$&i&Ep!;;Wm^9bM_gr7Y_zTC!xG{p6Yz|^yUPlI>@P23*h{e33T3;6TodpirgS7zYxay0s2 zsJV<0SxE8QWYXR9V`Gb*VdfBaTZ`{s&T+Po@l?{Cre0=n z>au~2rrxUCQA5kvN7R$+wTm5acI=wp&(;S{h624kBO(*lgcQ)f6sFK4#x5J~^sf$MIlqt4D(YJ(DIwe%}if}y3Du!H& z!Q<)AZg&bFut-XnOu zHyZm~=O%fvX7rYkMQ8h(L_Y*n5)Sj;9pC43Iq7OM(gqa6OH#)1QT}>RvYW{FUa(7 zniV_{sQ+b8nkqtrJ1}vWVf4X$)L3ViE{$+^F2js8H(k?*;?7z%-ToXl=ofGp=;G)m zQ8r(7UTiV&SPONgQ^#(uNwgxWA%2v%%Z?v`q~Cbmjd8a1WbWeHjO28An2i>*RT)-P zmF!Ct16JMozJ(#$+lhN49egXZyAHE*KZ2#1!kt||F}S7MaF)#?v#dIoRl3d7-j&j% zj#L3x{+d`imbnUmm*JLwiq()~P=3J0_`gH-mt+ zA-i-u`nGYhRI)ima04~UThlcYb%-w$jGWpP0vHmeP0QB&-;erM&HI2K3epr_dS@A@ zEkfQ+N4*54i-Cp@+HV9%0`?&Ln<23uAC#I#gr|8vKPW|Daf>%#h0bn9faT3xds{IW zatopP7$(^p`b^1_xJIy4%cZx73<#iJQxb*Bre2+QdT`EbeT^a&(7uK6&!*&aRM2FR zGj&t=&~u72%IA5ifwBP1=6)EiGa9a^AiWJ_V6FVYy2t8@@+ABgXPE`&sg@Y4$5$Rp znd4)k6l?rT2RAjEUdf8btqqJ$sD{Nu%sc&N8k!4m76!DXS!Mm9GwE0k`HNsv7>*VQe`cye54pkxZl3>gLdX&N0f^ncWrJUnX zAL~MCk+;xX0v;o#fO@_umVmSdQ;my`%KiK|T@RG2d0T!I2#LtiEj~$9Ece`9cnxr4l-@Dx+dJ)Xg;5j3cJ}%cpB2caTVp|`Ua-POBWTfH?sJ1u$Q zZ7!GUrkBO}3Ob`{H=>cZRjk6J*VXf=Pjm&{@4vVCR9RAImcVqZXsLZ3xt+em)2g@N z*j>MoSDn5@FxE+PjBKMFMkgh4a$TGgpcUIz$J85_pYIw%)iTsYh_4tKb^@r*j5(M! z6r$xaSZ&IqEROCkksvROS#P(>OqXJ1xu@mIHrPg&zzp_LM+-b9FXa40b23Oj^$Oc} zH96eFWQx`LeX34UmD^igErpNf6?&GX(6DbhP6KQl?;Nv+SM#IJn-?opOVvDpYxyM8 z7bfrERA-LCk*IaP#p;piB7nSM{ZVWpv{sAy%y*ntE}dGrZ&(3Bbwlf`AMxy`sbfyB zdUkk+jSvrd`%AoshK5Q*pJMfbaJq2Z{3Y}~S<>JKU7!E+akq2*zImg|xE^tWgUMeE zEr0elAPs98LM>;%7K+Ca-ftqvVZ4J@^vyy5lv)JX((1%>PniH1i(!nE38EM{>?c^Y zB6il#D_N8HuE$p$wmji*!T zY_;jED>$0@r=)$L{f?VaV|mYHX~=;U^`-OO!lOuhwEv&J%v_mEVRF7Nqh;^V#2cm; z$_QULF~oKoxRytcMlG{#S#k+`g6B?Z;A|`}w71fDzkH8(_!BsyT5v+v{j~Kkde?Ap za>w1oEBpR}o}Pz<)71R}lf2*Uu7N;r zt~jbSUov9J*UV%og!b{xBT8$|_Vm8CXIlMOuFeJ2Yo=nqo0nmM*t?j-x``p03{QdIJT21RGz zRVty?^?dDYbUlx(yE1S!;3z6vq>%DlJ&HNbXLwoB}$Ky40P4v-zevX99y@)3eRnKd^#e!4scF>_0b-Zt)^TZz z&D4A%8GA+<6@Xb-Z1wnN*OX#Lc}Ti$f7x|%W!%8`c<#y1fuuh@2NTxMJGHt*)!NtO zg5B1)_I`3NblHafN-TuYgxoBhxa2K4$gj$2i`y^(uY5hd3yQY_HgV&VtPz-`*tL_G z?9>k!%I{o)vO+3hB5zovYVbQAoL*zhUDguDwR+saWi9a$o)38Rt7iCM3$BBm!Hr!$ zj?)&_l}xh^cJ{SWh?ZzFqtvr;%QL z|4^8SztUcMt@2j-ExS`@K%xUxD82aNTKETG(=0=RE7+qj-sd4Amb%U&xFo+Uf@tI8 z@Luf>VIwC2vFn%ldOV%IcgxG?w*bV-(pfvZ6JDS>ys~?I@K!(eq=RyqDoFkx83*~s z?w!xkmdt&hZ*CX%`2?Qt#9ePrv_$ zTYDg1Bky%c?R=_GHlsrTMCzU+GL9XBwXK68N+e;}N+gIPTi0mCmHG~&9hCF(6!NY7 z7f=#1Dhq~{*10cV7d`88$0WVZjtLQ?Sx#5%<5E1{za2Jhs%@v_xU^hK-q{c;-fy8| zZk&!hzIMBFqg9>-*LworvK4JiB1NfKQg*^5I7UIxQ8E;vX8zDGE7g$TDE+1D;BS9y zeo!+uqhdcTUQtIHQEHfXu|Uus0$o@%uQxqvD=Xr~VRn%`=0#ff-Llf0QiTuHDvbk` z)~%F_6{^9zTC;@#PB0A0#p8NVMe{R-M%V@qwXBNoLy!Eb%UyxXkt131pYTOcN`}W6 z#E`_FGL0c(&~ffrgeti+;;(zWa3#Tg9r2Hn5+srud_(&b9+IogW zi5c{5p^OT$oO%8&2tg2P5N!a?;SM8DYAo<`xG{8)tZZhWKn?gBrk67}L>ug{h2ZDq zR~5U=pPEYkRo4+{Gw2s&#cLL13|^KnC`Q)@SQb-q@{eicEiS%2Tw3q5xGWNg%$a7W ze!Qf$6d|3b+zmwz@q9usg3=kWbm{jUOiH!irdGI&<-chU7q=XQH?~QQ!gx1 zPL?=Dc!2stKNYqSMmIOid$_I`AwTR&{iM=TwOv#zwjX!^JZyuLw-aNrzU_x@dSj19 zs5)?VU(#>wGggT9A8NgZ@&)5r8{>Ce&S|{g5?#>O;P1}dn$Bp+KR0oWru$5XT#SRT zjxU5(5bnBO_DOCZ5A+ysv)=fW8Q>jH4?KdYR(g$qU(PoRcsp}3201@`P^0Q76h|=; zM)jOT3IAjPE9TjGp)K4|%>ERUZw5D3&siQIA?GWO&RV;nqX?H3f=&# zA4jSwX|9?=RPtzVzseigsz|r;@I>YmT|N0EW`F+*paLPPYB(Kqpj=HO({GsiBMjr# zWJqmL$+h=$km^c^Yj2&FH_cp}rS#`1S)7<|1U#y3?Dd?AHyQ_NoXOY-HK7=bT~b-_ zC|u-G1iD$uM?RmVnSZFRAeh?dgzyBewHP7$_S>Ozv^1F>yO7n{zEe|%o!gadNa@CX zvp0|J0<7a?a%(-p&iK$=r_&qe`wg6;zOAC?q$aiqJ^nc22@hK*nbxx6Lp;VypGIw9 zvgA@Sa-88k_s;T;jxA#3mPx_D@0ZRTS)c`Jp!|Ajg#5Rn>7WTq&dXZR<@IRkFPnrd zXe4oSDg`1+1thWkj@Q2cH=a%jrow3&x^X?6Oo4d6ueOBB-N|q*eU7QYT-41U=y*pX z>v2|A?IRC=ZZV_c1;2@|rq*GpKH)WrajqSuCD`W}Y0&)7^wIDCJ9~6A0D0UxSwu_| zTVH=Itwr{5J598~;A)$g873?XbL0ZbfM{ny5(2$IrE0QitYEJF+&TYy3 z^NKwQ@Fnw+&wlTB4>`qT1v}NBWNMO_!n3h}%-W9PNJo5tre{MiD!y^`jQD3kK2qg0 zOtaCB_%#d46GwV65+?P}9!G6ok`dKkn1HOEl=!w3%P$5GNtSU&G~3m*9R91G#hAE+ zmAc1{l}3y&3H(y_TgBWINFK7@v=^jd926qNAL27tZ_dt2#kO%2L%(iXvffE$3Mu?wwkc)Nx21MB@5`h&vmx+3cDEdV*ID# zpJdy@Hmg&q1L4zCCGegOdwV*yBd(t*7FGN3OPYd1{){Lb9Eqv~WI-SBwPecMI^+&7p~_Fifdu1`|ZmpHQPx9@bIS99f2oU|OOy2j6jFt!cx*DO`x{zpH~k|nIXV(mQ{3Zm0<7>27{FJ)nD zpox|e8R>WzVd14E>JBkYV2tfYQ+ad9&>qIK%?8g1vJ7(OS#WDcAC)MBN{*Uhliu!K+E8iXMeLo z?ww9v8qD_e=@(YCHRM8B=odDzEq%G-h3mGK={XGM?8OiJ!6aAm;XZ!k{K%4iU!j(3=flr%{fdZBs-P2XiqrSG7{Bhv@*Fw?yTOhV;dWGTR94PV$3TpQ zE=50iLSNSJ0(ptgW8G4i+R%jswqOV(_^iMFFY}kp|pmE5`f46A#8?xrUaqU`{(9yZGEx( zBHw9z=1JuV&o8W43KtMUVNf@S8~}t+to-uph6IH8&*E(%h)BOd=Rn@kLw7@yX7_g> zp(sLzK@sErt*R+JAuewvPhP?nnESRH*|0OvihLm|*oTuB9GJTZq1gimSV^FZYhMoj z&@zD+sa1`6noX$-wfIKrAsVZN0yCK`G`A~aNrQgs zpGg&&z%*ki3FZrfk?Gn6tn}O1Y2jilK&M`?N;y6IoMhHo_s0pab z1c|(k5%-e7+*pxYL;zeelIHLtH4MaXN9E)T5@rU>=!NRgBF6_tD*|*sVImwpQC%ye zs|0zG*j4%EE=9?Y=ZQ=hz=_mh96`Bn#3*6Fs2UD@0Mis&CP~NZ9ZoY-RrBxADfWkIfY7xTuf+5-2sx1N1^a)!h#tJP8Rm1q(2w z-tk^CG31{}>>voB+HDvjwm15wyxlN!{~Enw-RTUwf;v6}yFB$Rf?*@Xo#vLFLsq?$ z=|Wcb{ExkB6O>(qd49#H=h@iqhPfMgDQ^@3nc3AP<>V~yQZu@?8~Y;&aQ+as+LGqu z*C8BO@6Q#1rh2|_G0|`)c>ZBeBDw0+w6ehVP1AIgP|u)S(ecWo_W~lMlJ4fit=R3Q z!MZ&~U3$AQ(j ze;jKq|1Ym;Ttfl>>kO`s|EH6_=>-P<#>r#cx31I#AP_bY2!#6@PHjz{4NVN44OyHm zTx^Z(3@vS#9qi0UHE*<4Cg(_nn?p`j;!yo53X_yA!Is3L&En0Wb`s6h)FvSCK|E$6 z9QXhqY$zEQ-|TgIhv(g)n{A#7zp(Fct99mStPoZImHsUT6$T6xg{rz2P>8e!&&mSD zf8KWKp-Spb<@|}=6V^ZW#z;@2)Z0WB9kQ){^D$!F+sPHrr><20xkqRL?=(&)Oig5j zbS!X)zXfud*h(m)`5+r z#6|)rEPgC6cWC^O;lH2-m}NYB0Xqhw*JrV`hb7)$S_^Akcs^TqFjbw<3nIUf!bPpn zVATzx!x=DUz}VOb5xWS3a7&itNnfuVZ+0&s!mzA`3b)`?ad(TosN*I2@87*B>O7g6 znVDIowoO&8H8wP)WF^#iNe5DPArw0dZ=OFGb<_ptapMSl^3j$A=nyinQj(HxHgPiULr>5eU8EQ*k?3g_fhdtJlSGJwUM=aa@vCAiGW4KCwc~Q=gwpSZzM#x$bN||_& zAM?}Ro~Ss{?dWO|(rry6Z!%}YkorEaIkhR<-4-f-u~|4=q@d@0uQoKpF+lk42W|cw zfiveE0kO9NazlA5(8`cB&RVSIFxn`|d2n>A(wDKa5(F`79$-C1fLC76a)(pmr%9d0 zqi0G}Jh%QWo0P_CESiL5i&;NK(ial}OQCqf)xR`SK9rII=0R&6IzBncc#8J0AN$H6 zH`b6?Zfn!b7@YHS$JBhFZydaVVnsfoMyj0XTQVxkKHEN>AJ5&I_wVq=GtnN*r3 z6z9imNMHqgfa@MQHdM=l@;&SOqaJELK0a7@cs*(9;hJZ4Qd0P7no8Y*f&wCEE%~?h zYeC6Lj@rvh-Lw(28T<`&ITuql_V!|Fsc@fLiv?ZDyt|u{`G5PZ}0gs`s0~_z^W0Gh!MhP zsmtXCLs+ze4F-Kt3W|AkJhj|Uli}g?5fK`95)!L-xP@EMZw#t9C$^9$Q%tZD5-77f z>L_-!h5?p}3V`&Co_n;`vqf+;uJG5ir`hq?*G{O7P4h028F`?39ehg;+ zJ_L_QENx>TeV?9}*FNMM$|`pKdjbfum`iYQae3UotwD;{%A{^qM~8H&Y1?s<&%7LGGcz;0kJ+=?CE2^C^+T9n zn)kU#{P7g64$sMivQc)2%+@=-<<0aX+|Sa?v?b@F#x!7PN4T2T_BJV=&Nl;H?`r~u zfNlVpKCze311sC?0L8lflaed_c&!_dGcB6@r#IBW9x zcK1Aw&X~zQ_mRwsFKUk#gF-F79XRFiJj+m*eZD~&kvAgmBKm>t%3dj(Veg^)?oso4 zSF+zB>!nmiRZNUfn(boCy+5Dl&cESDS}+hHy;EMBot+)mFCfye%Ht>k_TM}i7f{;y z9ugYLVxPFfSMh+gx(M~6T)4mc#g9lm>cMkt8Kr;fe6_3`%f4@)-B-E&P5yj5q9SMF z1r!ZA&27)y@rf0@`Mh@1i^e}^y$M(vWm=M^abXv41w5OTv6;H9w)ww*Et*}&`^W{1 zXesHgYRD6c7CFsKxJ$~0oe`ZU#0Sk`07ujw^P^t*Jn12YA3jn%gg0{w%romb8dBUo zJUoPvT-Qhrw8w%rs@{iSDqRE;YA#i_|o7L&RD!-fEST7RX+SsV- zfoSXM$Dngq$9aF(apAZ$SiiL9?|A`qsgCaMWZYmJPgTqgqy$jAsbSQHt#B(7?he|<9L0?OxcYs|*Rro7@i*=F@Z0Bl@b z5)*y{yKbzjc`{ONabDiNfU4m_#6!Z>7wDg>%PnLE${U5TqcE{2U6V>#CUhSGpQHBc zr5LBz;*Z(H3>8`|-N^`qMvQC0*UzGUOp2>Ta%Sf7}!!q#ma{sYrl)>9)m%p5zWFHqSm zGCcCTnu;6U{eyH@MY%IF@;Rmo;6P1Hy^_jh-Daeb*VWZ!TP*YJKmiTSiVWo>v{WLE zmgpILa5(!sq?@BTyDA>1$N2aipdG$!Z3(NZs_Hze-ZE#u_?6b~`#H_&yT>Vw+mtXP z=cG?SC5Z&3(bg4w?8&{k4{Dd!Ki2i?AuBh4kC!_v+_(08~QBJ;hJz z>c|ktU~;U=Kv_+fn8Asg4kVd>RLAQsDLq-uO*KB|Q*aQC0msB*6Q-dP-;Yu$<-NnR zovZg`agxe3m5X;)v%{z;@H)O?gxc=?MzBz6Qz050SQ$({kOSfi< zegdV%eHK&P++iKy@Aj2y4C=g4Q3lD!{d;CJ8OvqjsA2fDdV-_;1R*vE^C8t3XIVLv ze&zFivWcoHimKml1z~Y$jpI&HqHQ!hsW-VtV`_hyz*0-_h0ky`0(}wY&<0+ME{l!C zI~wcNU@dHh8An{2>qOy@rq9N}`pu5>HxA%5v?4&7{>zc*r(gGzUvU)QARBdtfS?5U z`QsB3#Egu?ePtEQ(}LT-I_l`jNJ<)5zMEtM<^*_nG;esL#Z(dzscQX7^HfyAmdnD= z>MnPoY#wGlHHw=-0h7~EPyIOv0pBNZIR!({d8c%Is3H{jcweF?m3ExWDIR%MakIif zWIJ8^fw)6FJQo=r&nA8_mhe6=-YxsYwHl8YQsmQfyw$ClK;Qr^`9$cwLSo{10k?gn z>*x72LtW-on*3cvF$x2mD$uN$D2UzX2Uei{3mq9gsowrJ!2Tgaz}B9Lsm;y9Ww*V9 znkX^pNg%lis6+BcE9@A0QBgd7!c$dLYufZNry>6U2ML|T8C^7ovlR@@gd5z?OUq|z z@z1l-f&KDYaz$fZkQPCS33P&OXc$M?=(32%)>V?5D|Kt}B$?bTuclPv?2I(NxWz3Q{ z-c3}odfmaAr+b&G#Pt5D@)MWtUi4zUh-YE%VKkyWKEI<4_*F>l#AY_c!d2OQEoP!A z{MB>E(AD@@_=Q+EnNLH{7P%sMZ}?$aG@hLeLLTo608R6XB_1^yaQhyGD>qiyM6QDy zq*=S%5BTKOthD*9)oh|QwdUN~M#LJWxn^&^&*^QZP>m3Aoje!Qcfy#G!RCA~MyoLA z+W6$?j4(c@A#tNAmmsGipO=*YQu|{6knCcl$zBQ_x+P!yy~PtV*A+t|J)gf(-s z@tYfpAGkF)29x(8MMfskjys!f*}$EJZc{w$?eDv-)d)M^TxX6BU8C^liHeG{3Bsd8 zs!(A>MQ2S!Jz#D)g(iQFA2RVhF+j*5Q7W6RP52SfyYiF@}LJ_n97(Dg|p`ARKdj|VsFOD0X~ zP39+UcV9uG4MOBE_BIQmxkviRH-N}cyMbYry-7>7oNN&IQF&&vOKbJwY~1lD?Y)0LVyGE(tl^?PmbZ+uIrjQ(I4ogDk_;1NS% zk}-O%=$M#{fXc!v?>Wc;A(?q!f1lFCgm_Spa3*d#9Vj&!T0zq!&fbm8B)mnX;f@Ah>TTu8sqVu!&PI=w)637r*PZKC;0|_pS)q zeNkZ)g-WunlF~Z^olDcx*=14Hv#_=Lim4E|r2#TJ{~dRPyiV%i(y2D1HGU0d4Z9oM zhfQ)l4V7yezKq7TRO~R3#hF_OinCKpzjB#apOl-z4|ThR-rk@_3;yQ%Tfq=_AZsY3 zWFLKHM!a)Fkl(_PhiiVgbv+bYO)O&~Jv}d-_UchkP1V*yqSJu&^+hvlANlT}FVrEb zsJiDX+SDlMW>&R+*Su@)Qbwxm*gL`R|@|i79;RGyMl&H$FT(00#wSiikcRu5hR`jw7K0iiJ%7%URsX;$qqkJO*p6 zp!xv&@X7w}?ru==4I$7K;jmMTp8>NR%pY$Vwii@WW zjg51ZFjQuj6r50Y1zDd0C&qiXFff&8=R%w;cTb+wBj-S3pWcb_BaIO-6JXNK0&=b-{_GO~Z~hgQ3s&@1dWUN=~dPw^vxVxY9aKBu*Wx@-3E5KeE%i zb)jWGlYDj4TjNYgNnv<=e7ryz$1^h58H3r)vLqPItgotnPq1+z9`=aG7r5wGFWp=r zJmRC~=+E!g^1ZSW6CLZ$B%Dvw(vs?gRtEL#otddA&;%B942_J$YK-pb5euYEnc?6F z5;@VS;~)7_`O|4LF7CWtBOUo*zSZ*S!vX_Kv~f?5eOkR|TmVhud!z5s`-8FQHFD?Y z6p-FOz8Jl2Nh-q{PO@py!eG@1YI7>+sGT-qZfO0bMMp|QY$|+NJY^I}tQ1x?`n4r| zwqX$xpm76+rKR0~g18jlA5`X$a41#&woUBRw!4oVfOS zZHt789M6xRb=Ek}cWXFemPdo1o7&h2G{Z|5p)m@q6GP&Hh8+c~NjDG9iVek6BvrMk zj`l;I?bg^+hWf#ofx^@Ib^}C(HqaA0Jbk#DN5aV;nPm;H)i{M~ckLxef8zUI+J$Zl z0M2D^h=kv&j_3NNJPPOz!K~O(3i2EY%NWXz@byL_;04Ed-xns~{7lJlOiD`X(cx59 zQr$cmgWDbd^=5TJq>bs8h+!UHa07UJ)*TvQoF}}<_wvWUz?Hxl3;;?F>GXN69UqD4b)#Y8CLQYBOn+-D?by%{ z4>$Tr1)|+`A$yb+4Rh2``U+OLhpTb8!id}3j6ik>hda@sn~wx81?pAU-E7YvF3$?p z76)QhTduyi#caGY+QP&Xh>UC!4Na|yH@=pg3`J|~Bor^fZW`xdp;d~gfo}Ly1I&fs z$5zx=+AXZoS|+!AzBw;D{S7NrBIH0em~ZB()wI8LV(a}m zf4Ohzx$q4~t2o(~!@s$?`NVPq1nfoqS|6(1RuZethC?R=7Dv<@~y{@0}|U-`>gInF8)>RqgfE8p`JyNjVS^o#1}aJW_m1U)4u zhDoH+>tZ*YeT z%`vd4;Z5wCj2PDsA1r-L)m(4y`&jB32D-*?6LL0u#Bmziz87f{>ZItRX7rDg0WbAp z>2+US%;JU5C4Y5H>_+IFjLnrsbIO{7TUurg!F9YhX)4s(1yO% zE6&NOS_l~9W(>k-L_x7bx$meUko^P`2F4_Qt%=6d-EBW7nnmW`eSUkQZRpO@CHfiy zb*vt?r_5CYRnjNu>`Q^c5;|;2GC%vv%S%XDSYm6dK{`)-UT|<`gM%Z_&dw#K3u%(Y zXJh#tLEoJ^EaO)GG&fitI$oNu3?YZv^=X>j6BE-BEpWe1Y$1hLMvi2|!|B|bWiA{9 z&m+RfFf=T!Ml-6i zr7+j!(_NvT8`*F&elUxzJs);Tq5~pgJcfkxRn65mY^6bc(v6w9+3?miU$}_*IvQA$ z%X0l^UhD*+X7LVmSAzKcREJ`Mpbh#j&%3}?h^zp`?12j5jT|cUX0ar0?|3MR zb8SZw;`1~AD*g7GNJ-IBuY^A@sYup6%F3z)4GoPT z&v?(F-U@(7>zmCdOMeF^!OoJm0kgKrW3CTF;-K3|!pph1C!$^M?oQfUHSf+K-exm{*TTx>DLUYXQjO7H*LIr^)Xx0wQg2ebXNBLM#j&~K-Z cfx)!6iZZaT3s^uPtk)wH76hW$`Fr+%08Lpm6951J delta 55948 zcmZ5`V{o8Nux^ZvZQI${wzaWsTW^ewZF}R5wc*CLZQHo}ol|wI?)@=;div>}nXa07 zrn~>lfv3em;3>(1L!g6zfWUwRrMoFe-!itEf`WhyfPsMECCTj*0)8rE3jNH;?j3hSd&vspRjPPeof;EM?V97T(6@%U76&6%vaP zN|k!jJmGjVa(se$4XTV-m5`g3g9dm0$o-wkT(ToviQCA~>p3Zf+jk02P*n{(7)BtZ zgvJ%>y02g*T-|ZX57f~3l=<{HVNceB$Z|KKw}koga~Jj|HjMoKoc>|agA?`*LdwPw zUF=zhPG)W1@!_wOemR4sQO!?YbCq0q?h1u6RYw_~oH3%ErHc>MrC$c4?rQK#f<)Fv zwXR8Ue+y)8D3TFNVCS}(FWbP1kpx(nMmE})^Z5{qLWw5dJpug?Sr*x0dT-gA+NWwG zK%IvPadg5D0s33svquC`eKZ z=neS4$Rt&QEhGFFp?cA0;!zk7kkO=ga1y|QtOeyW*PwnGDV(EX>ahfJRzjUvXK|(6 z3^s8R3>5;ji8oPGbw71q#@*k~e0V{dso2&as}lS^VD4fp9)EI-b;_~!roUf=Ty{E) z&MP(dkDxSKe8y;7c1}r24xwM#=k)t8Cq^~*twY<=l|lqn^=~$r1{BgJ&zAJI{Cz<9 z$9^iqHvL5dn5&{oe5#f%vE4UHm!zG&K_@}-b&aqjQ;mao4lS!6VvhHk`9f9@ns7X% z_tMTbvy^Eo_~U=ZBjAQ}4AV|<(x_kOM&7z}rt`YV!)yFw6*z*81|fdAw==P1S7JzK zSE?MsPXxjJI&n3KcW0Vx(#DzgSic5fvDO9t2zidX@G52zDJXzdTHp%lQx~|d>Q1yF zJa0>uU=pNip>iY0&uXl;Ycl7->z0cL_O)1FY~=fQfi>&1$3B^q{;YLGcS{b-pv?L) zst7T5`GmzYRHoycAm7|X8|IQ)`9sX)^ZH> zDj@kv0V6e3@aBaQ$P#Rjlbxh4H6}&Z)JLOu+S0$l*G`v)yH~-)a$&@t{{wG%M&7P# z!*W?F`qa5(DXleu?sS?m`>wH$gT~NnF{{JVzoo>o6-aqz|C7-(H!8rT+q14Shgt}^ zg9#2P8V)Sf4@GX3gEQ1Hj?5FNV{jqybO(Av((}1V@qC?2@^G)VvD5|O%SVZbyMH~R zHRDLDX=0$amU2ZcH!+57SN@&+vN$L#4X;Od#5>Pm+Zm%?oOj;@Gp z^R+HDX0|)4Ip@%<%-Ca$%X+NQEqBYddwi9Sp_o-#k4T!1)Fs9T`WB+2pZ=B^{B zEpv&{Mk>M#ChQ(4Wv8u>Kd+ylBCPhIJfrcbiLg4`qLfLNxLL91g zA;hiyke3UJ2R43YwQH+BCM9?E=Kea7{jA;PH+NMY-kmKAgE!{ed>9kn2|3RmOlVKC zUOuV2x~)v{&z#kE8fl%*P7G0r%d_D;?H*DRtDWG5Pz6tTNiE!@jZW;Q!Qd~rPC}d} zI6JSG10L9xI=0r8^zi`CB*8-ppIbEKKOl-6Md@={2yN@N6R{o zj@x!wS`s>abuw8?&WM?70QrJAi?{~Wm1e>C(-{F(vh;Rd=;452XD#*trOM?cl0-If z>{xz8aGb!e{M&Ll18~$~iYg4ei^REpLfigA-(?S?%mK*-15v<69r=hgEnZbb>b#RJ zBI)?N{kvzVF+tfA7mV|S=G})At5RDR%m}kSe`wTGWUYA+;-{|h;Txea}_SF zm}fiEm+_0ZDu-7}9M|tH|02Af5hy@u0EtTmh!V)DE-`0ter3aOQ ze{4GKDC-@*hux$p8B-`sRG#}{B&l~3yZ$95q;@mf0}fFpzp;1cNHiumC(}350$yP`o+cjo`?^MEeN;2*v2u$>Y2Lqr5`3Iaq;8m#ZNWlSIOaf*>Qd z1wWt$sbfMoJS;}TwGen*5+g#TDzCyZw#^ig$Cs-|a|)7v@fV;e|WLRbbwQUr1G z+c{pa@XIamP#?^sF4aePYwSiKes);{A>DbsmERixcQSYHTxTui5 zR?~LI&_;ya%*8O5Lo%(mmb_3i=DTz;!>!1zo6bjM}zXk^7Xswm&ntCtjE^q~Gd z&?gB%I4D;oNw*L3I3SKWflk5IyxnG+A;1mK9;)2DW4&^-nMa%Y!9W&)6pKZK-&n4T zlL<+X!4^a&Exzm`@waqK{)I|{ld(oN;7*;_$NBma7LEBA6HJ8gHb+seLC4+_sb>2>HuC zzh1rqzvQ*j_t~$;N0ZT3Ry%{SCNRC}YVFylUhm=aBAx}>n4pb9sX?b^V1(EYowcK) z2>wocLxPd$H~)*Cn2ND37s3uNlX6zLtJJQI!z7)npAh*(e%%7(gI0ir9=s`7-Fm=r zayS&11~G~CJU2M!Hq+MkZX(MFad|B*q2Wq{z~@~Ud-&^>&DSrwpz#YrI}%#JzUHfC zRCMv+;T!*!{IpB^N?%{4ZWkSWL0JZ7$GVX19 z_wDI!<_!*_G1}ex-l0tLSe~~_bSjqgRcgO_dT(ZPqfdwN_=tc9AJ-8z?9s%C?|uN% ztI*@6RivAUC%0ve*EuaVPw55;;18C#e!jXl`)Xp9Jih7_#hzGPnlVA=9cy`ezG{m5 z0+ynfVRmnm9G+nHVQ1cwf6K>C1gEgN*^5xMcZfY-be>&3#0Yn9O|7H|_{1JExMC?_ zP`0*J2>9XQ6X{n%8JMWVp=Y}-vUg6!HNE^!)B00Lc z3QGc?op*?S$5zpS7vT*>PgFHWogRKiU3*)D9=umT0|E*_To|#fiHJ_gwj8u7m_`AV(s} zE84R?X|x$@z1>m#^}k+Ac%?IKsb+o1c6{I_F0Xh`uZ@wLro*<`w+2aZazN`44vrx zll7*LzY7|-(?e57=E~Nbgy$B^(4iD3{F%Ii1|IyATt9BCT!Y{ubpNL(TFEc;x&>woRy(%Y$jo_!6=~L|`#&7Gh(lpO1(KVnF_@cOBPZK~|JE$S zy-6`bLZ8Hz*705si<=Ac?7q3fy|y}jqLHleD^!v47)7|8bp}OC*-6p&%vw-wYp7Li zXy-dt%siqCuR{w%ggkKyYabqMokeUK7Q1qtRF2ei#(tJZ*DeQyw?WM_9o$^@M$;z= zQM+j(ocG$BEdd#`4+qdf8@@IgZE{8Mpb$JyJCyZNc43UA)gi8df zrse_xYEM8VXRqEYJ#~gJxWvTBNyKFiS|>NW*BRqEoh0ipqqP2_0Tq2q#AN(T@e1Hx z{0iN=3c1; zzx4_-T_TOtzM*`+tnEJwCY`+ne`UO*%lmf;YRdb+PVMh~1aiK-2qrbWnY@pK2WIVm zy-@*#U)ymbuFlt9w{t54e*~ZXZs*EIhDHJfUry3Sj9E_RsNx=PzMO}PNIqZ2E_$bu z_TENnzqq+F@N*OtsGvVarpl7yzJ#yDmp`21hAtEjO?}aT?!o8I?zCXCua2JdXy#qU z7dcPY?4s1$1E{-$?X-~_UuSOaXE*2fv3=m&-B@0MGUzV)V zE!ann(;EP8=V16bU&j3jCkAiIMjkGD)ArxKdbh|v1?_Lo_+O%L_`jmRwm+!)({`o( z0l`thJaaXb)oFArfunAsrT1z?g-3@W2(!j>070|MJBIu7OPlOB8}VIJH)E>k-vz4IQ5{1tbOO6_!ryMLCo_Pbi?X&J zG1Y&p3g?7SCNeqnu}PF(!x?QNMN zJ-#s7-fC^JXm;4*F*=p4>by@|00U_L=54@SsKxPK$#nY*Np{DF()3MtIpzHA-GgfM&hxjl6>Xegoj#=J{Xg zhr2&N6K1eU+Be?XvWdc-j_KFsO1{xLtuJ zdDal1e6?Qj-);tFL}@wWhb4RX&n0!Q6vR=1-JYA?ti%MFqHw6ZMO_U(C=zfd_?#)) zeKki;3D^Cc^b^5AnwirPgaLBEJ$AyR;tF2sx(;EpNtDG{WX{u9p_y{1|G>nzx$=~; zPM9siCz$%EQhn=WmncF3$&1de`}{tjVBti_m>nN=Q0soY>K~oD8Kj-i}Ow0;yvl+9fLfk42E6apSo2}W`kN`@s<00jw1?I zYjjc}@|h~^#hEg+(J{8~_v&s16H2P^B5hz$T49D;UIgTGl$F6Av%qwMXVG0OgBVD% zBav%hxeBms3}M|SH3=$Gu26+Dd=`yNTPpj%{*@&4GM8ir&#UfQ?&=hUuK8;e;J*GF zw0>$8aWip_3I+F5AOYYPaX9m>qU1m9lM;tBfa8H{7bx1g#20L%>V&^$CorH|JBv7H zjgTm9x-shNbnm;%(mLOMGl}6g_|x_CGU(aR&n4I#(kPhle2L%dC#KGGhUZ}VREYyc zOE|2Ynt;)v?D7!aMkqg3OQ9~$O(j;Jj0((4eO8Ik(MRv{T1~aZ=&%b4EJ!^Oqu&RiN0n zhRWMQ)i9TYEI2@rFktfsW&ic1QQC7xWek}QrcqCO1OjTv^)dH0j}y*4KqG3W-{{qQ zLEiT!W4wuqUsRd74O@M#1vV&Jr)$8hYu+$NrWL~Swee-uV}6(Xch1(KK9A-8Bq6jO za_IRDoHut%*==Z}awOQb%fg;|5;K9%7pJ{tz%Sf%%>Za{v)q}Xbkp%f*9pYeQ}H}q zCL4ljB=sxR)A78wB$!12P zlkWpBwg|}ZB&_!i+In6Tk=R4sOTZ>W0ONbxuZa!vA)2@=g#Yn|Sj>zffnZ{SIGe=R z)QVWo&|=l6mdY4olEq_L>EYYh>lA}+JCaIR(oD+lx`ev|UpME%2*J(61qa3k>#!v2 zOr=6uglKUNmQgEupT@j%W?val7@2C$LrAYA;2PoGur#iGaE{3x)!$Ec<# zv6};>;0|=GY1J84*apux^8V2* zdFUQ}t*RAD`<=dS7 z%HDY7GPE*1^6+G4>hfa4fg=^$)l)*}7?`Hrujv7z7frb;%Bze5CmFS^75e$S$fmKJ7?D0xmbEKTwdQLy(o*`fM1DO`DC(6ujm z)gZfst=`+^c;OUs=S$$hG6`=7K3wNG>E|obAud@*?%Bxl^cIpP^ohC53sJu$1*}wR zfjlC1^FNYaAphlHp;yJ+I-+mJ)$FW9fR=Kshq*#^$3wE<#*{xIyC z`P>ZqnUoC!E(U>uE(0N@5?w}YoS^zWKwexS6tTeg8ePqk8-vo8(K!%|M%)EX4ZUen zTDdZg#9DG{9?=qaa4UB;qq??Y0Z3rszH73mYUaWf7~puxJIu-**|C+*fAyqvCCFkB z6OO?x>)*Bgt$I}3goZ*!`*5Rrx$@cRJV@V@5dQH@>MGDN$?wKP&v9P-6Ga`jz%U}F z8Z`D|s5xCCf~B%Poc&SLi{s4p_iR#(yH-XDafg2KsMCDXRWV1HP#@2$otYRy0vI6-A z+V4MYcdfzB%WI_p%+tFK+hK%EdL;*h;pXV_7K!I1*y2BwN+~J^XhmK8r*P&AFru6%Ul#;A&_QxF3wS?GPTpJL+6HywS(Dd#K$Fv zpl(=_V{}tpn^f-+kFw{1(IN*wu<0Yci~I}O7ON#M_iBUx7WE)QOGO}!`1P+uBe=`N zO1PjpDu1|GRd1y_Facg?&CxM?Ch*g;B8_1tzGI`xiXc5(B_v<*Vei!7UN|8@b;)sY zyh@0Q5{(Q^IY>pCu&qx}Qbs>ad>S|`aw>RaA~}x}B(ZW~NLeKaBw3UxK#Xzr9+vXH zkr0J`D7{_K@STU^O_Loa))5soCWK^Ui1Iore6M?vQ6;~i1JFNQ{gY`65hz=Tnx@jD zVfoa#;>9U>-y7DEzOq(5XoXvEqJ~{t3y9 z;#q$%`%Tjl78tKZWWim3R)z>0py9T1gusve4PFz-M5yx9@)-l+S74!bSQpF&F}dq* z6pixn0Q9$bStxv6SmppTQufeKPF+R{V`i1w*E-b`eWjIPHOeAw8~O{%4386?S`cd zuFu}J2!N&aAB15!_9%GnZd89aAV>egg8lm?u5tq;sJudZ)8X>tF#4OkLdm9<@qI^Z zUYIJYr!jQR0!=;H!8r>Ajqyn54&dm)7YcGoj3uJX?&1)n*}9jpl$qOJ*1Ar@F+ z{Tnvn(`tPrY$=W~@)QIjs@&nzjiI8JXzEHi(mWyQj-;pgS$6rMvi~H>4vA|*F|sht z2#t>4x;ARzXds443Ax7}L@{HcfSKEX`3c7d)Z0+Ui&ExUW7oHB`6+w~Ztm4|ly&`} zad4%|gFIQJ-DKb$h-6}1DLOjCKA{frX4fga*F}Z${Zm+Ou(kmOTBh~Ufz{CM_r?5j z!+b5cH>zKdpx9$x1LFY35fmg&8stRGJ(Bph_fFKDkK0Ay*9%k$G$(ivf<)WHEd=IX z;LPH=UbTs-$w1s2q=aAEcUTr|1h`Zvi!f+7kVE0#hGyYj;94yRp{H@0D&}G+I_4_) zdM;&etNo8l6R`m&0*j7;#R9eaW_2MQmcy;QQmYOerZNv4F|x`CcR1{@h#mQN=f$Y) zK4Ds5$GHJthM0;(;p{r$1$_op{2>m2S%=ZciWYtHmS2kL*4hh%PF}POeki?ld5YFx!<%JU+%2)UkQ6X&yw_(9 zHIU1BNuMMeRVe(`O?;&7?2z7DDk>ova#K}R?49UFPg`B}=X&zN3sn>0Y6;-c=lBbE!2ks&b6h(F1(3X>C!Y24Pr4>t6XTC*v9tkUb^kPZ*^1G2LenID z;;?$u5yKzc`&Nv6h+*k8ALn>i|BO=05f7WhXJ8fnLMcDoaHmpq0Uic4W z?v>^QbU*MP6>xg9wNAo@$Th78%pcKj@D|-A-Pw%SRJSQ%z*d>Tb{zRG8}M-;3g#k` z_o{@w%jcRfllCd`gXoh%nep;{pcitN04)70BVXhzF%}cLQoj+=;hfvgb8l+D<93Zv z#3Rx@c_cV1!DHW$%shb|sekM1jx5mZqaxZR;{ZPT#G$Ge2QZ2sE{PHz85b^W2#9}r z;~07Cg1b#`JWms|?Iuru1KOrJU_TTKy4qcmMhA@7w4Y&HyqY4->e@v+L4(wM;yL&j zY9LX6`MZ&=qto-c)bNFKnEl-{{&B(iQF0+Qg;PwFrhF7jSl+p3Hiu3XrwJ ze(`E|@k=Y!M_4hUW@nyt;5S%d^OD@-a&IL@t(BV>D+EC#;>T(+wZEq%MzDNq$rWwt z$wO|afdFS0mKECFC&;gUQe8}DmyuH2CaPcavQJmoG05bpgM#eZMh=6U}50`Be z4JO%;^7G>n#o^LETzPz~^8v~_;mw3>tC9Oae~{IV6(`{jlQw|2olOXV2~`jU%+ z{ubFO&8RUD7xcv!1yR(lc>LCG@HgvYQGaL)qsST?MW#cYis+YHWW>JK1@1{asi_t*O&v z>20cLmJX_HqtG?-*_lS20VhMz-MVCLrxkroQ{VNR%znwa=$K)NY3g)xSdzx6xPM=m zpKU~fZ8Rm4e``H!2wN+h`<#L=LL;SJVa$$t*mt~eBA6XZDHH>BF9Opks zVd-%j`k`uLmMUTvMsQ$b=0=G9Z#J@sbwANp^F|&dac9(_lla~%MLVi)!Pz-TZfEz$ zhv6ULg!G$&s9$0U+6}0o@sS!ph7P~)N1k0JoYC;P@u3DT_hYOE)ul0tjjfO0n=|}1 z29{YnJL&?HIy{zBgd)?pH&JU;vOO)_|uGjv#_jq%PYou6Z+ZsiVyxZ@B}obDQ&y~pN?1H}{k~tzDc4;c9+71md36P=7D=dmMHk9#b*K!N4Z=7I*zb?m09TuGvY03@x8yV$)nAU zz5v<+;Q8;}@;cZ8c$9x=+2J8fcL6-{ey}o29r+s2XIs~FDow)*x!ioVXS!iD2)6xI znL=Xv;H$F{^m9JIK_}8q_rYZU6gu-_QRX8WD)ROF&WXKxl81H$QHg)@>yE%;%4@GE zDd9X?4AT7B0lOee*)?+xSL~W;-a`$8r4Z{<079=tj-}9?90D_%KG~3UJ8-9ht7Iiq z0@@bW<%lpmq7Bd@a1FB?ipp7Y;yPxp27nXTgL7;Y(;<|z<IJvAd@Oxs%>-*~uh%$UHHlfSi}-ki>e?|RiFndThCh--w?>}g8oSDi4$y1=$Z3$TxQq* z^qnvxyz>J8d~bgkYyy zu?~iVJ7)@4NT+H6X~*xjCnMY#`2*}@RkFH3 z^ZkDIHzk=YGi_(J`Dk4q&^l=~)iU_E)f*M6AN{z}IK=T2p-rW9*@l}^KBDt{%tKmX zkAch=iWFV>YL;VcMhnEZ{KUyLC?G41Lef*%Mj%71W^oh0KjW4sejx?&Y^|%$(oEM( zhltt2%VdI$`=BC2plwRcRv)g@|i}wu!`<=J~PM#4H*z^kQdfst(q>b=jUo%*}@fT}t z4;Pqq*t$RNzV~^3xf1jb-+(L$|t9uAFavFmpYKc;_fg<3& zEjGIWDt&H0DhrW@f3|JA-pLo|)LeL>M^cf^tI^!u+72&5{)|JGoBuM+I1;fW$7+Rc zA<{(;9On0CrfK$5c=l#XKCaTlXle>(3dmr_3t(?Un&RRUWge5#3I|}J23l*AXhej! z+18Qv%Q7)Fr_a7hH}N3YSlTzWqx$kJbaXm`wmqoyvP4I@d90}X)ibvpB;X$7EBN_d zco1y@nXIlPgNaF{l`(ciGGakQ{?X~0q!X42v=xVSIv0qO*hW{-@+&04+B|C~t4lRw z1R`fd$@DOf47koZ(#G7ub%{V7(4`m0-;DGTh zU2hf@hM9t<|Dp|~LqF`MzvDB3z$5BU>lUAEXi91?jQZUv7)k}tnQdZ2|2 zz~aydqo&H`P*+T3hQ!A6R3JOH`y~jU+6Q?tyLt5SrMIsc5yGbvs4>#Mrw`Qgcgwz3 z^lZsXqM5=&qVE42rt-!q3v}yYAYIKeNo&7;=QC^7J5xA^FbpCb>l#^~L@L(Wedz}= zox21~z~Cb5f}Iuu6edD5gsIUa+r2=q@Ae>w5g2VTvbc|SYQWmSx3miM6FaS-kZ}04 z9mAex&F(Q;>hdEq*eU_bw)=9at1%Wb&krVz#x`;(ZB2P*Vap|s zK8P5Qi%{u+TpQWxI|ieS+cede3_!gQApNb)BG9)cMr><`Cc%+gjFg z8TI#1)WLKNQ%%zHH3lP%sb+{?0?_>Rh1h&|h$gaff&!kfRTNxz2-YnW&4OWyp!N-v z`*}MyFR9^jX#9%=a=nTQ}i*>R^cJ;ifhY7gT1Kka6SCW>+fVLRA`?|)_( z0(BC5up3CHWi7GbU?1mlmrIqG&^jOtls3-EmuBbU50@zdUW1_Ivr$K|OjRL!;>poT z6qd~O(u6Fv6O`AGvJwX;3r}xmE7RFP5Vc?t$SNs)V#IsXfvmq<1h4Vwr>L*ju-Gmg z$?o9-yl&M{ejr^muj`%Tm($QyC+HvT;|7?o5&B;DI@Q)f&&KV)&a%{4M}FDh{;?Yc zQRbpCduU>`rrC=;=AZ%3hEo|mT`O8rdBmTE85WRA)ATco(;oHow#-U)Vp+~8jyaIt zJ1MtkBc_tg0i;8I%sHov_oeHA6o|fuJ^?+cDGH!17*65OaCjgA{B(cw)>H@rfQ}N- z7P$C$DJBGe4niuyyo3&g?lcCZXgLoL;dd3SomKh*f^|IOBAz-SfBK5XFkpLF9brAE zvSR3&Llzt@_P{_WtmMx(*q+*QX66E3E6B3}4^W-}fN0g|T&!k8)3gDESCotK+|lX3 zE`#r1$WuXnSI;ds1a7JHEAQc*=<~kqR@B;E&w1T&0p{m2R*JL~5c?W0f!Z^yDH#zE z)OH^Xh%4U?;#jDGWQi9OXljGq$4VAUED*GLtjTKpPA=$gugju%hfB zJNjB6PNbG>Q;Y=0D_5@1hI7yd{qOyhf9+KFXhk@t`qwzg35G3`5k|4zcgB)q+=4%RIH+WTQiT+*+&1aXrR8Qh#@T^ZOl>tU` z{U9H0o$joRW=kRK@Oj%^PVLq8!z0(q|DMU|=F9vTtY)!KangC?FmupYzh6F@(>Sug1wBmNe`@3@EY{;UC* z{?2_>!0zBM>nXUHxB;1z#-<0HgG$iCJ5h~SU@Y9x51?pYA;IG5KNVwahy>~X%p%R) z^X|ML{6#1){VAl>Q1a_npJKcCFcL-5ZVH<@R(7HA%>7DiJgD{dpKaA zt&}hmNk^m?xI#|1I-ez9UmRL);#M3^n9AVZBYjJDww_L~p7&~-TPAbg;(M~E%LLHF zxR5q^8RW0javTr;-Q^n|R~W-ji=b~GvOKG9$V0uqv8wy=d=&DwJc9sV4gVeS zV@9;Q?;oeby+*ZBWSqrMJ~6^GQnczEi{-D3~BjEqNt` zJu4^vc%_F*Jd%&r(cgH}?$N*>?KQ$rOq;R8eqol`1Rs}%LHEdTQU9bIzgQp%TPTxI zw+{!0%qVCu@1skY=|geNW^+=jUy6)XOTWW%Zv6jGDGYy{?;jJtQNAdGq|Gwl-nkyV zN@W>}M&T(;h9>x*y^QA0*|n_%D?=rCniWzcJ^;Y;aocB57JYIadIDJEjdBWYpdiVk zGAxvJNNT{q2(M7qRhcorV?KjMSTJeF4F~L+fYH~ye(Tx$K1!m&-vHI@tciEjbiT=X zjJzFqmxHvxP^VJEU9LGh#sg=Quh-o@B`xZ{2r|!euS?o*>yU&!kWqFx@IS3_WWZL! zxd2_0NJ02u>dcaaaO@)@pN^9$y?dn36*&kSE@lQAN7~q!qz+I}zZvmu{!OUQ@CVc* z2=VuUc=?Dsw``_siSu7VK`@xaCFYn8$W+HS1CQ-|e~>|fY+k0M4;)fqlview^5XyH zU^2NFTLbtf+jzBn2=Qs#{H7%)T9C}rp@6cR)K|#4QU#6U?Tj|<-k4zNetZPZBnku< zHc!@-!B4ZC#<7iJx1U$(cOb9@e}rC{DO8C9eW0^~EzStmYlIofCo1e?#WT@POCJU% zw41`1lR~0bDSwxY$Yfz6zQk-GiZqH{dBYY;f2HrO9AJF*!Vhf;4Y8cQKL18pT>zpR zV|Fhiu)-P?mC<^=IQXk1x${=Eg||D~^$di;=WA!MzcnthN*t;-gRl!Tu-~wtB~Lj~ zBJkA8(FWgAT^7UJY}w3PP-sL_O;i|)?Uhi<-48q^+05E@n?6jA>Zhz1C)i>7V??es z##st}Z>*2aJm!9|s?A~L?R5LNl?N=rk0al<>HR6o*!_7MXZyR`;B2)x`QKcS+YP`3 zo2`y}5|>p7eX!^PK7M|9-JvSsSK&^76FK65U;HHXz>9fXUG94@`K`FBpZ8uHNCN%% zu4)lX5ZY_)Zow4vW*&BsC>~?S>v~Sd`-W=n0*}{xiN;12d6c?A#x(>+`U+IZ2;dbe zlEr#+3NJ@pW#?|oEH6m9QdkzVQh0c%(g|0G#H375%V>I2NO{bg{cZJi?`xD>jPdC} zw2~b$^dq$S8t!vh`O?q>|6VGjy(wwNTy zRv6Jf8NK>IYgyd|iROKMIR!wv^3}fmcT<%!iwt`eXU z0hqjWujF(vHOxcZBqTBF9Nlz=GfZLbf5r?SmvCu5=eV_2W0Z&%$MS;B0^Em(R87H< zA(0cNQ(qTMC51hqj0`@h{eLjVHdXO`i$w&5ki0au+gouGS)FQ4D98{>d{}$_+1C*6 z5g27~v-5mv==|IbWC3z0T#xKV#>!{M6pa?RK9{5vruUk|qMHDh0vG*1y z+$>wN!KMBDN}Zn4+3<5A=-jglzj(|tb>g@7{dcQxkEIs7xKk2&GkTq; z)*O{0%9@^i@_)B-SCkjlGVggV<(EDyt_G!y9pTO@8elHozE*|z&d)UruY<|eVlvb9 z4VnC(v%0<&5&=(-3Haxd$-O?utRJuPai3Z5fuFZeL^lJe607Ntw0+r^hb8Q}b$l6x z-(e#z8$OU<7U51T^`~Ka>6HAUr9}ANv2w`DtLoho^Ie$A9m@3*hY(dh`ig|z`G|IY z4@9Z+=QNOO4psmOXO&HS4MHdr(L|<2!tOZ7W5WYqOjcdS(jPFD3YqlnRgl z6HS?TQf^k=o-hzp#%%o2!WY)2o_M+BRnUD)e;pGT#;&{@(7U4sO#J zGajaUe)=0P6UtgV&ootZPpLXSanjuqw+cf&Q41+Xv?)ta=uwnGx3UHNH?egOxq;qf z*fZ>w9`3PttxqS=w4dSjud#qAnhk*06-YSOwRf58scO($y@PQc4xp1u&F}d^`EvEE zl5GUg&})*Wj0&MsSd3NCaQprFkUyFfKtjG0t_vx1sA+{U>PnTx2uy$e8Tv_Qi!A~Y zW5F{1FwSgIf|e$Aw#Yox@-@In6ak2XNVztuo42uy8C`EhXw}d)=w=*@(rf%D>Ag}h zf01Pyd#IhK=VWQf##q)Pt+r|4YZ?<5bpiD=PBGeKi)I<`w(4J33TtB-Pcf>2cQH#3 z-YS8=OS4SJGpI1KHxFyGoy@K>%7y%W+^$3nNA>mlzK&%)D@-};h12fe|7(<4 zJCcn)Q4w73=-9`h|ABvxe*Mp4mn18O)~7@H4%@$(DTi@m>Ej#{_xtAm=Zvmj7w2%4 z8M<2*=a6ZJnaH;!tStrSFzaEPuGq~cT{R2;i*pN!!X{Hh@EbAHGqC*CA#EmFy zLx@FHB!&(Jys?{7A5>omJM5J@Y;d`(jON_Wil2p#(ILY2@GyE2AB4#@RSEAk0^5(# zl*rH|JT99LsGT$@l0yw+bnn5U;Aen%V|C8v7s}ScdF&YhNLAWoY52p{ez#k4=fW?) z%6FeOhs8JW*TZ(x=;o`MZ+)%G$j_dfuwq~>iZdHL;%5H1A8P)%FDsWH7`dbvAO|#g zm0+#l&ui?VABfcFVZRS8KoqY%gFn%9M;qfj?=s_6Q}7&0k_tGllzn}j)*1nGKeCP> zSaEr|D%%3}BzEYb%9F^!?v@QbR0dwKYOIVD6-D8GgObB&8Zm@S>$%s4%!xSM@fK@5 z5rv3(4z|#kP0F`C$>lXagO$cnsZ*zaY&Q z^W#RMqVooJ4j22J6kq0i8<~J1Ls|O4vypN%45bDJ+3GbG8sY_Ll%;u|cN<&B=MjhL z7y5v(%&oFa<%-3NrB*TGTO-+7{4)x-cUikBTQi>pl5rK|#afPs%9|?Ul>$gcUWk~+z@ci$0Tmx9cXAx zPeqa@Fei01h2L{jYlL!m|NU)7c7}8K*aVWs`2;U|_NC$V`o-i89_PNEFu7=I^mtDE z81MAt9l>jZ75l#agB|`=6DjC~*E#hpJX+`#u3&~4*EAU_NifgSTgn&h07qH_X?nN&h7R1g-5^o`y~Rr0#AHiE%oJ+d*$a|YmC`qBL7BlbUkQt zQD7K$IL997jPrE0C$qh!U>@v@bfx?+vFu!wq4vEa)G~zV5I(!%HfW>iA;d_-=_TtV z+8GPe`+ED8w)>Mk-`D)R@OhHtKk8X(kpiqmNY=tAuX3z8f^$I7WZptJt}<0MM+K^1 z@V^s6`M0b8HtWgx4F8%hG51v19>_w^24CjPd*2BBdGfrBEE!C>e%FZe>w( zE9-Dmb>+{#~Q|2}`Z z5T42@E}lCu5$>lruilsCWJ?n34P^{Ty6`n0dYJId--T=z;ICQh5qJ5G#AM2gtQhhi z!U;V0EzK?|=cQHX-+XtUDgZYEEw&GYYA78%KU!`rm(DN~GQ#}uOrP@6xfk+!U?`Kd zHFEfx4l^ycFHzqN7uSco6}Ll}6qp+Ok<=OyS>g3m!Hnt`P6;p%QVqUXoNdU9YFt4{Axf~bs9 zcP)*z?=l$^DnBRdf7R!}!bn8#oLS*`vJ7Tf$ZI<|flJ0L>?sVA(%}sYK(wzi7UXL# z5y2u6;=b+!3*he`VFy-=l%Oe8At)8TNHyYC#hNy8xxCQAdFwFA zGagq5!$=m8T2&U~DUEN$$Am~zNZ?o?($|s3)0;qj6(yx(G6j%2hm-Wl$T+DyzaJ#! z1^1VZcNM@PKUx*Y@ga4v)%6YUtC@Oo@X1s&t(ferz>JNjaeCNFC9Y)o`VKR%D?^Z4 zZX zWbFYr5eYITc{$)6wXz*aNZPVSWj|HK&wEd#gioQ$_fj;)%0<|>Pfyx^7JgLjn)D7< ze9la%z(uXBz>8&-N*qP+4U-P=zoAP&r8EnP4$`D74)!p*o{kt`r=m_=lZsRN5Cmfu zX&rwmzh_RSP}n%DeW^E~lhujorFpz`yY}GJ^#O9jYz@H0PqN4U_Qh!7R}vm+bwAH9 z&27rfIP0w9`?!gpvCJa-b;oNY&vy-ym1CjH3=zxgCc*Vxl3Y6cn3uk2eyz?gx{DrF zI6F26hQlwsHz%|OjJo0@H7E!%ky4xLqWiJjFnM`JN|GoHcRwSCwV4AE>&u`Jn`Sua z0&;@uAJPHYqiPOwm=eSK7fX{~{ilbWJs5cyY~$8(f<+4xdA6q?3-!gIM;ZDfg&5&_ zHnJ7D)?-h>o+T5-^~JL(!$vk9NJ=ZhTIfcXNr{%p9exV&)nU9epCv{xWeF<{y`b&S?z>)D1JyO;;f< zzd$s=kZ<;WR%#Ykf`1yXDRev7lyzpsF=jMaO+s;s*BAJQ0czLI*XVx@3?{)cK}$Vd!1OM8DKnKsk+p_aDZ>pr!h-{oqb_H z@*)cesOIA9adRN}K17As*IfQP0`b5e9Cs)tY|pQQiVOv5st3j^XwNH4Tc2ro3KVCi z?|}xH&3RU$qtFwT@Vuti;0H?%)>b!Aa(y8!2>h8iVqb87jhJKz)30p8NsbHZ*8(`X zR^5&rb3DB7X1Ys250`@kfR6Smx5$RwQSktV0;8y4hK%IekW8ZfeZ&g|J*l+DZZZAh zPbk_-nvhlgk%f|7s0%FhA@oN zJ`!J*)sa%8-W>g>dUhd*QtF>uAxt7QU+&c zN{`Y0(h}GtQ&It>Mr>91SKtAH*nLBvUv>vCz!MJB%*Yrh%S~IKJm~DS!8KP@tYjB{ zRV(T4jku1l)M8_(v+DhBOKPn2XRs@)r#imW{QCadl-E4q2qBz4z3NU+Mq8shxmIm7 z;r3xnJ*5FO>*@}BTa7hareqaNbHvp@wak<^S#A-oG~uw^5j2I@3!qO|pqks|2ldKv zC(8|mzLX~%UJ;6!<4z$EXO6f^GiBd3P|h6|;45v|v+4=E`iG2lg_yQNXo~gWsk0Ji zGS+xH%Tr6}1KW6BHQi2ni6aBG`XWpzTCBw6YSbe7iw2&o+0==@^18y{v1Ci;cCMmo z;eF03>1#}Ri4)QR<=M6nQ(i};kE0a7LTKg=eevIO`1p>vwtjl2Nd3N=AzdL+)^YNy zZ_S8nhTIiR@*-}gT=!H6Y_f$! z`*DN7$KBgG>bdBzsUmEl)VwYP3r&fVrI2ivYVWc~3xDm+0EZ&s(Dboq1G_W$Q|QN) zR|nle0=eF#zwvWxVi-7r?nMU4_UkdvMKu5m`kSO_Y9kV z9Nfs~7i{Y>{@6({39T~z)(j6iGte0vRiOi&L1snN9jwlnd6s zZ319R?VTRB!tRVZjpFVMXlB+v=(zBpVM}oa>hJV=XqYmPZq+%9*~AiaJJWb`XlYGfvkBa{2ub$&&ZmR|n(!VQzqim+Pjm z`a=%FhU%6#Gga)QPmGoY2%CDdU4g&A!uZab_qC%M>lSC>U zS^Lrcp-e?05@sBBdlXZtqpo0n#u_nRv9EHj?N%KZV!W!rSd#vtc)C32zP~)SHwJo(U1=(8tjP@3V%Fp zkSVHQbtDA!7$QW=6sd;0u8FkM;6Um?aj`0uBj|$ArZ)p!5WDnaD`KtSAD~pJ zX3NA{F`8wHAlv2swk5bhgF`?c1(+WJZRz8g_FF)3_Lhn9a_(q?`rzg<_1=gQGZmj55`1%?L&$70Gb_knTUQ7sMOgF*;->LzQKWM?t5@Bo@L0 zf!`V+=NEMQ7kqotRFfq6O&1HbaH?5kQf+*yj#Y9X-u{E%76=6TLVj#@EZN&{A7t6KwQ^6cdQ0eTG~*`hiak#JXvPWv&3 zYIX8It6!?9&YzAQgeBFi6X@&Yk3%F&-EU(YR{n(@_@8l~{2XIwku3G^RzJSUn%CF`?3vxJap!wo;AcrH?8h8R$0dhFue;m#rOF8HSX&cwy(Qex%m7~{l3)830RlnEk8j+Ft+OGb@M?F72(8Akd4W}G z)AO83W;wsvePTTQCdQq`zw}JaZWABcIg&E$hj0b2Iu#6Cp4E&M1Or2 zk+79)@q1m%u@(PUURRE zB$=tmwHW<l2Oj%We@4vq$6qf?3&ymsYPy!ISNykae^XC>+cFH1Kxak`HQhF@Fd z3~8wjiw84N&1#KlrKi5B^>0r|DyEx%`255US>t(=FSm5}Roze1f~AYbC@$oAcB*V* zU<})I10ye-7`Y}O!hwK2A8lQbRP4T#6ou(j*VOfjdm-W|unZo6vtdg7hW}ZnNhuPw zZc390snyH6op}9smZQEWQ|g5<=T^#6@ZuW0I(*lrUD7EW^EfwiRkCbz@y z758zM2q!Nyb7wPzQEbCDuYmT^3fw5KDmJESn7$-U4TC66AD0KJYx=240?3uDWG^!_ zXEXRw>qTm9GTz5& zL`G*zosL#8hhHxth>oU!FsY~p9fHJZusP~2AwI~@VsNHz$o1nLtGA)*e*`E zP=>d8m{fbvN2g1(pc>0v?HVXIa0tBZ@WVosbv{#>MLiljHWx~i{5fJ zD98|RyGI#`XAx{lLAH!Vsojse7;U9N?iH8FXq*b5C%_V5p9G}2&Ej76x|t*=OEo$t zh|95xuv*bZzs(Ow!8|1Kat_N-qPipuWW_XRLAJ2=a(Aj?XB(g{x zyH5=IIkHl!=?qW8IBYLJ$L+e6Kv(nteTin&l|kihUUsOSC?F>_@HaLc4RXK7xgjRI z0(h(0?`g2P?vq6%6SH#f!5=YvKns>#{ngjuQP}(iP%?izk~nMF&w64QrJ`2aa(k%p z6Wz2qH2QXDCN$E5hSO=4uuHu4qai-8=T&&cH`p?Ou;^-kQ~t* zfN1!1&an8l#?p8**Tb73R>%EmO57A)0|=tQE@>qfQTaNxrn_;c581{>=jSkV-4-;| zXLx(?)Ku!X!$c%ASh2;cz|QZd72=rFR-cjtwjhtD(hf9)(TKS0cygu?uwyf;*#=jJ z^mXU1)&$v9n3V()e>oG)pvZmWsL5jYHwe-}(y&wEpCk6qep^T@>iu3i&19A{t7>pO2Oz zHB9SM&S!$N!RwNtInA;C*7DZmrND{(S`Sr%%Y8ici6ARxg1m5oxbc1KJ(R(p$!or* z)Mped`%Tmsjf?U(I^jEOzD40}u~GfLlsHW#;cL1cm`$9z7K=nXCNiwuzDX_eP#$yZ z=*kz|NWJ9r`m{&|CH^{RH(<$-qwj`B#OwG7adY5;8m6jq<3uUFZ{L0c`%D*G_;=f% zAkak`xfF2v*@6|u_|6kpTi%YSNIvK4we3IEU~bz9ee!-e668@l@gy#I|F$M1?%$-~ z`MM16(7xG;Qi@Zcw)7hux9FRx^pt5?BgT8t6tH9Y5sV-jMMl{c?cyL*i-cNJ!&`aN z5j?mMsU!b1C@NW`9R3rr|w_-^OOm$)cp03FSASu8M~kF=3s+l^*8*tR73N)+Wr z&N$%%Gh`qCWo>lLua_XuEHXosXFQw4gKQ^A5(jfyWsP*EsUS<5kkS$hyrGTk2exmb zST?^aXhU6c+9!+eFY-hNC*Zje{b-V1z(+Z*C>!s0H1~Jo=ns;35Jk}Q=*f$|Qh%FV zrf?qPCRIOtrf6?H*v$k3+`%)O4F}3K7`xHMwEGLmjPKAmk#3TZAytEsOW?V61Ha{< z;8W|A6^r2SjA#9z#AnA58U1J}4q()S@(n955EFj<&@3Ay_P4?#M0Qi>q??Xz4U}BZ zLuG-$ym3>$xjijJWtqmf;ZVM5_|we6xOpx(xNnLT?EfxJ&&ZLSup(wa=s@BdHWQz> zp;lcP_-grlAZi;Z=N*y1K{BuIas=Z$ERG^>PyDJ?U5ILWdK0D^yo56NXET2n4$Cal62k^m?*#6 zDEbR|UJo3=U3E3WdP_d^c^LT8j=sHOf{x(#=LlT6V8F#|WHi3;OYXBd-iJLb~p2KritW1<$L4=G#YlouuEW z5N8!M++Cv9V5w8*5D!8KMO%$01$74 zMJ2Y&ujt)f6OT3X(Ue6`HdV>N)s&e}a<+-=QdC(!J>JOc&Iq_u(#%ooWcDToF4ewh zE3YqAsfG$805@-rp8gieL^0|W?jiN(Il~VR==-my);e~OD0?;*bA3-u3vyiF`Q~5@ zXsg`J_AXCUKQ+lCti-Owkt>Sy8MHtIT4KeajvwSV%dvNc-!pZTfk*AE(mz2unC6As z#8DhJ4DW&K#kLAB7HVi_wC|mQ@i27=ZV-|&ZW;ch1*V{?;wA>n|FWcrI7Kr& zTT-eTy~Z9~u97C~g)R}!?AwDT=bt!ku(F6-<{>@qa85RoaUW%EYIL%lGbiXqEz9r> z&af9K-bZ3qx{L#2`)y%p9$R0~@=X<$PW@uxbG3gB6DjYe}=(Tpx2bbMnc-!$fWaNomk z#e7p5k~oVz%T4UzKl}7@#eo0tIC^Pg{kqq?(=XXG>;8LrG<|Vz#C$eMAZFiVe?7iV zYszc6McpZnBc^V==o5+PRFdl`vCIQ@XlJS(z_dzteY0D%_dbVSI=x zWMH1TGHPX@$AspPxjHe)^b@ygQCO(Gus2ywixFP%t=m_&EsttZKA-UjIn=w4TdY02 zS$sQYeCGwb$@}`}Bv6q4QuT=yaA#WYVUjO^vj7v{cT468HzmmClr|!B7dJjq?qZ-`wzf-V1Vg28au5p+v{F zG@_@c7>;)ewrLxT^=x3u<9NixD=IPG|B3QTpy=@)=SCL%A!_IMF0k16X~RE}lAYU6 z3pzgW)R2Zu+4Vz$#V}JXsH9XKsUh5Hm)B+N&Gm-;FOs^ASpx;!2h2yAzOM5*=8GZF zllN?ad$ItYd_`YcB&T<+O+Z!dt3)ybDC1fCPsTHcDA9k zD*rQ5d4`kI%aIKsHjB{IoH=GKE+^*l{_RD|P#d5x)HCOYw0a`6aU3+jQ*%BvR$_ID zLwirU^Se|2%I`dopZfhX72PWH$etfl6Wa2hU}eC=-uOf0dHNO&ja>QtxW<7G_$nDK zo{nR~h>RQ@&+j;;M^Lo#M61j=jYrEB(arqI-9?ku6mNXDrR3Sf1i`BCJI;5JN6s-_ z2}EVs0S_lZmAM~!4yRs!=B2)tp7t=pE`VaUG8n7%>S^}5t?=@1zL4q+^ynD5f%2b0 z!OFmnCD|PPqas@AtkUV;`Q&XpeQ)E>H~_CQz~=VuI$3~5SE#^%NbYJryj41BSP`Yx z!#0-4ZqlJ-a=%;GqyZk^I)c6ObmKG1JR=}7(SVT^_U#iy62%+X=}m4e`Ad9Ux^^hG zu+Oh=36hDDQ@1nH-hXnTKeI`hj(((@{0<~a!`Bl}o)f=uc4GFYLr8DQ3GX_VJX?>N zE%|8&ql+}d(SAAmS0*%?rc~Zo9yx?wXp-0q8Ooxk08ywg*2F9WdDL5M$NJ4a(-Z7l zFnT|MN?4VvznY=&YdA7(Jgz>}KU1NdW^%q(AxL5$`4I0PfdyM(D*+J85cN0Xzw8d6 z0w_zic3HY~2?>>KH>8>xYQJL355t{*@m>V~%7EqlF+U_1H6Tm`28S1^Qot|sBlQl{ zc?kC#R#746CWb98%0}Uxd)G+e(&V~)1IG%XUG>p5%;NWr3$J5`&v8%g(78?F=V($D zXlrhkw0qYuV(=dOy{`aQc>Xf;#VOxaavF&)!3)Ek)l{5S=yzdeM7#d@MAFK(21u~C zp9oK}8q*|Z`OHBV)eY?HSUMSw2u$)k(72SpS;Op@vu*RvYoVy6>`-W>EKq1g^T*q9 zz|6vuGA1A>v&KbDeGJXcUP8H2+bD1kcN4p>1HEbZ?`u-x@u+}H3lqyLbkldfJg+vV zf{+t%nm2q~11Rt+h_r`3oTVGEZ-5u<|x)fQ``L@=Q6opC;KYmB0w1oVW zl14!Y{?PO#z{Ta)q@J-&a@H5a&*cTMI0nyGl zXqn&nN6AjTJMsVkY7$q!w`C16;P(-!=$D6H{|do?%<=u0{a|UIC_F~9ge48&l8WkL z7R4bO&)aUD5WRlv0ym#9IQT4geU&dAeRv*9YwUyJKs}NPnD(Xo{-=~gGf#Yl6iKvS zl#raeJAwxqK|H}k%%$($-%&GeIxevXGg2jYz)C?|)IAOX&Lnc;G=!5$En8sWo97?G zVo1=)y7fXi5*T^L_4Y);HjGR3>{#YTaUfN(RYwHOSBzuRN6%U2QoP5h+ndeTh=j%1 zSdGMQr7haV>vx&z;FYP$#~TEzsZ-+tyFe_oN^x_N9<|S85%wb zC%H$=dS?2Sk*3)=k0v)&SufQLAy(7(Q9)ZKL;+3pIg`()-a^`+`W+J!ffMX)6pI}^D zVT{69k`9|w^fBGvYJhEJ7+8h7Sa5U>`gQwNNg`Tey3rxJS%-d#a<+Sdj1N#!C74Xg z`)p15W6c3dN=W&$%pqNIseW;ejONJMK$L}iz;lfCE}y-VyxBp$9Q0vrG_ny{BtnAC z&zcf?M@0?Q1_BYQavfGK4s5MoJ{=K9qMH&Zyk!IV-W?@llc+v%se%6bOAiI;;a~Ht zU#2^(8CiR8(PXLszDr!mgFe85&t1r*q_TIjuFYRuje6`$%>2^(3NUG=I@+b;wxXur zoR_6%x6gS3TdCq`Zx}pV(BdA-`(DdWF&_g3s=2j03Gy5qCAB+S7fQ7|pYoV9cKJMK z!)TK0b9yY)&v8wxse852J1lB=wb=sn>OZS?l;|CB z`IAOh?Gl?1HOc8^@3re(g)OMuQ>wU4xujb~Xd_Gc-E#|d*HlUhHtF>=i;v4)*J1oR z!d%ydp0$Rb)COw-#!dSYR`*02-U~wmn2Pe}&ljd=Hj$xvl=(i8@p*_Hq1U6n-_{oY z-3It~uSb26VN}j+c0281)c@>oLNxxqI`14Dvb0Cytbo=I|2mnqq(cz&4SvXwkeAe= z{kl96|Ju}AK?VXCcxR{Xq@tdc6sSr?V?)+emXIhpiM*mx5(cB9ITC&z2+cGJCCkSk zD#~Sb2F6yz3E;XncQcJ=d%V5ShC@i7B?KpTh|nQp>9;whH5(^Bb1wztnP+i^8I5Fk zo_&jj%^;n8Mfox?s}}fM^r{2a_Jzqt791Jh7}nKH?ju{ccNC*9l5BmK1uB8R|=XpSActjZPfs&LE{H=Z;+H_6GnTK za|Jorf}Q#_3Lahc@*BdI(ExP(j4FHk|(B=@M0gHf6mPn};mWnEbpYhJiyS zTdeiT-Nj9C&RUxbFx^$67F#p-#aQ^p zET^o@8oOA#=9l;gdU2@S(5kW#$dW=N~@s*#;E9 zU;;D3{g9;hYLym%TAn>UN)HM3e8>~6G)4vr8%hbB>OjS|C2);?e-!(;pS;F~aS}*K z!4xnz85t6~VR%X$8e>uF92)p><%8wrHRaZooRHVnl_J^5)h)wE9A)r@^p)iZ6%B#q zK~U-&1$l!#GSX!UD(bM!0W#{aTF$iUuz37Q<&bM7D2_US95zHbJ-Cn!)uu|aj%h$x zESXxBGhuQ-B&Fv;8=s#woCg*id20nW(yEYpfT23+k~(zY-$wI8>1grT!15taCyVs? zCrkCsirM5yYRC8@)SovItJh%R=`a(8+7b!hzP5mfDA5zV15C=mixPWhcB1%+9!mZ@;MN%vY% zNRg<0hvYsdDRSKNv|~&TTf^&p5AQ2(9{qzd7GMIl{_^woZNR%{)%RTr`GF{o0X!)A z7XE1kq+dX$X-klNbclHM1ho_HR6$C}*}ZPwMxW5v9Bw2Zp$1<=G4O2!jDn|M=c4tN zzQY;Kq*SnuM8kv_5TUN}BpBy$wW4o7DXLe_f<=&mgYWVWf(cerCA+C}M+>RLI)B0d zzcsGlmMpn;(d*w+U4mpmSQtQa3JrE_$d+O5{rS}$* z+4ECaL8J^SW!3k%B)~L@+;o1hS}ym)nT29Z3V6^t7NW6&SQz^b4l1_#^k;z4bR!b= z`wcdj!<-t1S}RiNJL~(>Z&za7jrah(BG>HT6!*Gg8*DsvKCsjH)bw08MC+cC32bG3 zs<3!je#(f6%eewYqicTtJlzDtXd!vHCV$rZ^Tt&vj&)4nL-*xMMnL~M!Ipv!zm)|o zZshwN=&qfA-Qi|jE_sD1`hHT5;(qtoc2AIG{s)hXWW-g$niyJyUyh z;6R-G4Yw2Qtg1#FV-UM3j#b^b`+Hw&e|f~8`$VOwAlO5mLzErIRp6&AkLzTP&->B9 zelA@-e9XclrVb{E262MRQA*k@867waY%FAaVQ6tKq_V(*W3aB>yn_OG{H@=P=e%IWc3;B| zPQp3Q?90DNb0wEgttQ<3Vd9}_Q>&Eu^Kd`v9dQX+ase(<+Tv>%PUy~&`tR{DZxOyL z<>ArR#*jC9PQM0cN9S0=aW z1eC2X3vu}TF_5?H*6*^oYK70~UEtx?qR+;g5q#zSB!PGetGUsQD$o$K)iA@{>8eId zJh3Pd4!EFy*t*(+&r%aOgVHG3xgAJNNmlE+ur3pk^|z0SOHzfl#)qj)OEE$sW#~MW zDYNe#b4<`q!x@(LQ(mE}qg~H&POT%;H5&2K%F|@dSmtoNfpImz*!0FV6V9yxj$eCl?25X7|U1p_-R#a4&|nt4L~z+@EBRt|7U;Ed*!#EW`!7#{Rsi zB!hRtmhmPLy)puYb{`Q`Bz`+_${Oj6u@QJ(u9F74dW^tuv2y^abH;n;&c4b$YeKA{SK) zEUez!L%$*RJI9)-_mb^6pyt>ZPGhs(c4MjVQ3O>oCM_0QgziplVxc4;-oJpVhx3(L zWq|K_`j7KKrG2Hdff?6lEbl3p#pO9Lav3aaKQBezPnZ9%kHN|K#9sD$ka19t4 zMLK~22=&iL1BYd<$tU{b+zUz2_ALd;=gq(XN3w9n)Qz+;E=zC-V>vi!c%zBD`esgL zi8V*?tXhMqy*2&!!N0xy)*k>-dYVV;LGc5 zpv!(j4!;YTOg_m60d7x~{H)Vbo&4OIqP5%km!tl3a}4w0-x)qj{V^Py|J{K&EvP-3 z>wjkB6SX%87(x=1dF=Er%;MR~bHl7ogY*2#*32GHqfvEH!FXV}v#f|nEZ;7|%A)7d zMtqb{&f<5rpH5*FXOC-@`BO{T(TQ4XMH`=>RoVqMjjW;NdmpsB(OLWRzN9pklyfR& zBes>PkH#)b7%{TuK%58U$sCJwkQArhQ2*wgnHb zqhfk@NO&Gg`=oQ0UyZ*u6!@XP6BB7m-ZV?n#RmUwUlHiuE#);aNKyi=%pX$w4iQMr|Av*1O<4^`FJ+9b7AIF$-V&10()$jq ztgkBxRK7eF2xm?G#6p=qCZavIm*x?_hOh1gt2Kr}JvKT_5FS5J zu{p=&?vKv`_8<5x@Lx@6{}=fz@c%++$D}sNrAgWk@nJfdyyn=xh}a!6c25LEG9&!t z<7&67z&=gwDVKZD^1nbY(IV+MjFw1q)eE~Zy6%HIXX8SuIo0lE&NQH(F)cP>n}pm-)>tJtqjUHl~4j*O~+ zz&|bKl@}eA1aA@#Z59LWf{K%X(sKJQd-d}J?C!kL=5yKW7iE|hD&+kG9-9vjKSjfy z-yr;n#96>=2tNKiGg)gA#W!s*PYMZ4($;|-29=0OvQeb1dvY9Qk^;(oYEL(pin%)U zrp15nnO@^{$)|utAQUmO4A6MLL?t4_`AN~uh2VbW@R1lL<&+UwR+6~oCou!Vq)e6A z;+e~hXZ3#{r&1EGYR*q#X2NY2%57F?QB*lNqPh$}rw+;LG5gy%=?qt7b>M5Z9T=5< zcQ?K-Nu^1EHt}7TM-vd!<&STIu@U=~Ej7w-G~Fcjo|F%WjAcEb=Y3qv7%$+mH0o9vNUsj}7O~1F zj9hQMJS`ei51_OWVlsi`=X0r7!7*2@pP^y`5x!n$U#% z9vK^0eERgz+R4ONjW&}isNlOQIcY4g-!f2f?Q@j+iRTdtlAt(wtw0A5`(2R1v^@^6 zy8553l(1D`q)r_Yarv|w`@x`$4TU4X?3F5^gxZ5QvKm=b{H3q-DP1XA*kjekj|MV~ zLSZ|L#G@oFh&0IYXNUAsI?&Rq^imn}#Rv&0L^9CQL0?paXYB%u0Oz<46Ym{M7r#VU z`5uuq}i3RR# zG5kT*q5D6ruEGm-rk!Hkrym34uSTtyc7eZ3+2q{$3MEPR-TMv2e&|SRl<5C{!|7; zQqSng`os^Wo_3~LpAtokwlFeAQ)Of@=~`l&a)^6V4s}qlMM*i8i>hh>$K+zgS3xNI zoxDUHqSi&5){~cRSOAoGb`TQHOb{Q2P(FydUNJ~c@d-75=cx%3a0(XmX*9WKGase@ zQ)XIA%&gYuKr0%%1tD&SH8N1IRrd3$114~!--Wt@=?9A7V2;PsS8~O5%Sruq4oA6k z9g(=p2Z42YOgpBz_{2V@Ig}Zom2$o*O_8HEYoA_2Z$389=<^uM!*jclXy`^#XtJ zFI~1t>wim^1^zQ(_WzPD3;a*Q>>3Sm-HdYD%O7R-|Bf&V{HMz7{~ci#_)nGD|9^$q zQP0}3z5JO{0AE$~6O10M$>_BFzgTRmEe<${!`{aIn;`oSdfRFXgHrg1=w6R?+NNk& zfQT!9*dG=P5@TDy<<|MR0?IQj+^!je68>eK_pko7r@dkbw60njIxxEtf2%5#U7Sf( zXm<7GL+QN%1X~~EKf~K`8i?#K4mX3u{sI!wgcio62HO}f+>vbMWDkF0;W; z(@Xk?`bc6!2_%2QqNW%;ydrc+$gME&j*^lY9C8@7=y_HX^=NgNqQ9zaIYGrlcRN9a zl0}~lQ|)JY>)x*j73ICw-|~(~h3A`SzdC(aQ31+})aJqM^Hk=+LBHGc;4rAgM_^55 zkXbmYA^znu-BUX7&1%Is+N9eiaLE;G5@ws^@b8|^VsZ(3iNzzr&a9#P?iAHYwXosb z|EjW}2GeVq^P#ho`{x)3xmiA39qfm4*IibuW~o_Nko*)-E&KCkJYPwd7tzsWa~p^Z zyq`pNShW^^Hv3MGDTwjkmD&IA!fcHABagyknH4z_$G4d`oAYD8)xqS>^ZV)#ja<*0 zl+m|FBl=j-t@7Szd7w(9>-Wp+F6gv1D{u|Pm5e~C)y2ytv$S-IY5Xh_)v^^IS6Qaz zK{`4Q(d1C0&|evbLo)ay zL4PSuW@F4m3hPNc98U{w(rAuU<}p0a;@gO2z;S{Y!VQ;xf^!!#8JZjGFE41ZF`yH~ zbmEZ_>mTjzAsE zz}9Rzki#-^A7%2Rgk{7$%(?@q95dL#(SCJ4!)f_m7!Oack`e+--LAj7H<#UEv`4lavCPE6 z6tmWzw4Lx~`{H)B*VAR>z<)`SP!~rL5#C+cigyhLLltlD0?Q?yc zs*wr2QoBr?v)qLyQ(WXq-c6=|x&nsgmhQ^Bme#)ZZr|Sf;An{O3?RaMO45LjB=}`T zfXg8#_hF0`{LXpUP~#hufs@OcEnw(}!#uVhjexUAQx4mwCii=^@4%2@{z~<|(EJq_ zf^5T!+Sr?#^`kI3uv+|bY`C>gHA|5gQB)?iQb=yqk_5VW;K9NMQRD*hLx4$q_U$gc z>(~2%nY|YiWp-$Wnu3BuNF4c~l5xz61c^&I@tHXEue7aZQuGn_pn#Idf-$C@jPoy3 z)f7srFzR9sxd#|$3f~%<<%{24!x+L!oBZ6H8SWiu7cclCI=h6@H2{Nq4TDvD;};+= z?ZB(KWSIyIvDmfthceZG4+2bwD1_X*sBT{-UM?quGX0kixtA&w|G4iBUK(t&!|odbpV{f;b+lLk4jlO zX-Kg8pWU3o6t~J&7fRE8c(0Ubt+axTl%T;IoWsP-d%~}xL)2O83a2M+?TxAwF{v5( zBXm0XW8)TB$icA&`m$8(wri)~uY&6Ldj*XH-EspVd+%IkjAC1+H%yp#&sf@SJja^( zAO=}wtZMFxn)LPxelY=cpf{8KttTN986ud95;$!>rQ8itslAr&zL&m@nD~Jip4z!_ zu@3J$ezoe$co$8inbcgc^3x*DFKzWemVm$}Lw9w^i{_cyD(b-@cLE`9>RiRBs>5hB zc0YB9+y^H(SDgRO4eRH#(>89{85@#RvvQT#AbGG$6omfg^Dv;+9?P;7@*r|4dPD~q z-_uJf#S3n%LcVt`XXjX2+C|8&AvAK-oj`;jeLiML{|-AAn;3Ke z?9M_`s08@&*gyc~)%UugOIyq(*N!bRuLiMDQk0I|9-G+p}cAqARSBE|? z-QqWe>1l0>;$(Vz%QSF*x6f>6XiAEK0A`o%y@e zyi~#PD!+BLt*(Te9E0vKqr^>89fOtM%|lI#t=1LOTPXsIDsBXUjOvAHZ7B%0PMrp# zx87KlzV0fr+nb*gnc6-e2rDB9^WJ+F#LFueS-o@sb6Of=-%S~zw@Nj)wv&9D?-Mq2 z7qW)4bG#B?v9}@hdLtv5V`& zY@mzP>?Z@|W4K`3i>j&BR#9_I28j+Z%}g63`V2W=t(wZUtXGniROXmCPF3dY`7UGE z>c^V&&z@#?B|zcPzHRSSR5q&ilzucJzKeKrZ@W3|jfQhOd{_TRA#!x zo-sf8OvKJa5ZHP!w&_-qt2qeUQdIYFPID}!z#rhB6T3NA0Q|(`((>Eq+y(MsiNV}u z;*xQR(MdvBJ3D1>@pg2$axeiEJ2Xu*fkA9NE0g6vrsZ{bx~bSQ5t;Qb(DtU7-)@_z z5er&m6E(O(RPbp#Q4+Wj2h1P;ge@3lF-2Xb-&*7QAUuAoPBVWCp1WFB%l|EV?G5zJ zXms9lbu2pq>5Ya@)$bmZsSFHWfG3mRFIQ7tXh#(_y)^ht(yQ!BrSls2WwGIJKS2vZ zI4gW;I|oz~7U%6?0>qFf*j9xw>NFae4}{q(bwl)rn&3{$9!l zml<>b>|0-#1{5sn;TU}S>1?Zd0Yu2^JWWb$$rjNV?CfO%p%z5j7_x~a&X-ZxAMSbJ zzixZJ=E&+1i%vD!Z$h4!a$SJmHDX`aCa$jYQ!l;Q8zG;EiNc(iso!sAFpO*M6?$mx z=(W3IPx7AZVL%T*wH+V^e~Lhe@q82@4Z3#+-o&_~ZmZyq)t~A<82miF-FhD5lI1HI z@1V-mv&nLoYaxOmo@X&j=cLM{Tb3I!m*F&lqg!5+lm63GtxZpuNU|+4WuwXr=u`Uh zN|A55(r%LW`V(<5>r|3g$+!z5zFE$y6y3F4x&?6x?VsH!zX!p^>M*|z-wE(MCINYV zSK!KCT*z>Efa=$dAi^BJ%}=8DDxVYFxRN+6PLOUuYPodsg@HF!S#Ru4E?MeKp1u%m zOd@jEb|7QBUxniiSShYVpXII`BD5{|NA2t#9-xA2g_vf@@^( zDuQcP6e@eQLSP6x&En>50^k8rxQgKKE8NQR(_$R3Szo1HCF_#R>9)X{q@=mKGepr* zK6ujhf}aIKW(AdrNWsHD8wEuH%KT;~EJMlMWr^cU(>yW6A~(tA6WrrH3%o-=!`-j4=X z6jB$o3$Y%)w?gaHBg*G52UYaVk!U`nRGg)fg@;Lz_61@dt0Xu+U8vh>&u8-ZKb+r1 zMI);piRZb)DCw9D9#j?mm{ZT6qSMH&`;;3Rp#1ezZk0sPB;|@-YvaAZ-kXbAbnnEG z&S99xOwVcpin$gso+<;N*^5+{cY?pU9z-J@yYhKx(vISlVt)RZ7RluqH4!O+D%xSm zWpey;qiNKaE(j@w#cUr%E0*BOi^X_Qe{SJJld{q zHONX9nkW_c-J4Zl2^GnJG((IrL(I&~jEU`- znVFf{V>_mpnVBJGW@ct)W~P|d&-1&wdsq8vcVB7$7*(tLw5Bv?boz6?U0nr*Ca@P9 zQ4Kc-;K?FVV)uO?CQUm^&g_+dvJ(nj4)HPF1($@nf^?W=>6J41CRc;~nt|;$oDMFz zfV@}IUgtIMyO!bAnSAg9Y0+xe@(d-n{S`6tmUe|Sxslr&1AaoFCxXfT)$vj=>%&G7 zWxHoj5k;^jBi4qWB!bCAvgIWuR?jrhF~F+;_&k#)Q6<&0y!{G(VAqj<#&?C}!t3z< zmArce{6p`N_>iE=$>H6U`?Zs^`L#vnb^byZjbiaH_J@OGMr3r>&E|7f1^Mc)4yHt` z#F1vry`D&M^5P%r82HIo9@g^dXFs2#Qiy|T)W;*e`2HudCNlqvtib;ZvzFI+6@azw zv1+&r4b9$58@m^TcD!D*Hh7;fuyd4FxxMja1t!SJT>FD!7AW`R4!ETbh#{b&j@A71 zJ;z~ARxTS=UHfKwhBP+0WBlAE-@Wr!^jBcrQ{I zMM8OArQg?uh7(|j!B0^ll@^=9N0%5a$R{=*&nf;4OZengSE|_e#>rPaTdGL*LxQke zDz)F}=+XpLW;m?InQ95Fp{CTKLE(a8({v&V@=mDRQCeu)E<}r70$x6Nek<(7#2zoA zNp`Ll<^9&w_dqfS2+t3kTlOe%4Eh7>uo(++3!YaDT&*!&IjWf#NOrRJV=etW>36)r zx?>dFmOdz~)_fkTt$2YsJoei`jt?s^lcHU{TIvT(thusqjQzA>sHvX=ywvs^%|&<5 zBc4+@TS<)UN(E_1a{AS=he29q8*$@L z=-VU73%cqArAvj(RT+P193y+Qv>jF5{xG+H8kr$-A}cxP6QttSrBlEaRs~xQ0!PcO z)D$x!IR-*!pZ`XLbu=W0tzdw&pktvy;q%pn$J8_ecc<8{g@C+I1ZYTUSb9OkQ=XxdxkMAfu_ zX1?LYxYz@q6$=E+gmcyaR^~FisP;1&d>Za=!X~V5FI^uuTq9zkS z;=R5cSOT>n2mGrh7(#}a;(=$@={hDTA+0Kc%?ce6Ahki2{5Kx$P6`#88QD3t;*vDV zYg2k4|4U*8{x^`7^gqb@|0}Tq|Anj}TK}Js_5W951^)Mu^*_X_&F6*C1QZlq)yE}j z8x?pFreE)f6AG%t_ALHGpw4+!{|%!5@@ZqV{6Bp9-<|6}CH`Sqpz%N4`tO``*{&-# z0r4`6D(U5Q1N0mZI0IaFga*Hg?uMU&lWv#Aahm(bdNLL$z~EPF;dIhI2|8~7bgTT= z96}1&wzBic4}P< zRs4wHwKEXir%uT}`cGT}!mg8k_~ake(JjRxXper@7mD=6$-*z^x~ZElxRDJv?VZQt zL8En$v%q~<6!r7posU_9)59d-Jy1?J0-b-@PGY6dkGs5K`eMWk6jI=)u&ANOM# zZ<^gI5OS!J=%nHiN$ix)C| z0gXoRqjd8-MjaZM%Ar|9nIK;71EZl`CY+!KDB&=)%AcWV)t{Fl99v_+=dTZl8Qyz6 zF{j%PU6~=Pq=j-6bjq~~{%S8)ghMs{=*XnCE|ev08!VApP9^^A25o4Ot93rxm1o>J_s3!LZ4 z4qWiurG_KS*8feX1IP+B%_*_}4XXczvEacupV$hdWx3R-ucpf%G;_lkXZ}N}hZxKw zyp1sm2Pw>x+_duln0WUK)~&`E_XU@w$D|0TjdQVMGs*9&Gt&gGZs-9zDE;pIEw5?3 zu+|L}Ibp2Koq|(U%SftD^m#3b=PA@NYiUaT2vvoF7^BOfZ2i9rgs+ZOcnHg}Ky;&l zjb;PASXKC+Q|RC(;Dys5=->g>8p^c#ex&Ah3Il5|%B3p#~wV z!0OlA=cZ==wm{^Rk2{Jqp&D1{0kw&Vwew{QCjO>(B^Lm`1_{jxtr!@Mf^sDk<4Z$X zKL*|%<>z1a4Gg=9wkP)OLS-E%_nVj$5b|E-um3^;3V|wUCkWCFf&3GsdtYEamj3q9 z^pMvu_E1YfX{$_f#Mu7_X-ZsPjPbS8@br+2{NfCk@0d^*D&*yBRH=1Y+!;Y`Yv~rE z@D)|kQaXM_p(1_DZJOMkeHC90uPz~hQ z{=;wD%#Q$`C%2l?AmBAXyKi3Aq3JR9aX5k#m^NQO^Yt?KS0fqT&uVVQLY0aDY!jhn zmabN4*;xGg`^bz{UuMCZoNENn3AQuSY4T@u-!DEbGMs)~-WUO$r5#)SzeA%?Y$@h?tALo7lpzkI$Ia+oFA?An& zMy(jG@Is%KAmSBwG>JUefYmsb!ew+>ulxVdTcI8TTY4w|39GFY=>C7uTV-0t2W4jmtWB5(D{j+&L_&kEDm z%?Uoc9(%}*Sh7&2)Bow!*ZLo7tG+RdXuS^9JZw)R({yE;`Yw2fO~9t%$r3?(`FsEH z{-X0vrOQVyXY<13Q&QTgQ^0Hd$HZs+|2`V@TZ*Vqf@9-QAYQ~zxtJPSUdFHYD{aEd zDK)Z+QlH5d2l`_s8x^!}vLZTVHh7;n&LSw@MI103M47(2DPi`uN1xU)-?bi*pGv(} z8s3@_MOh`&e{eMd>s!3~$L$y1yIyJekKI3OOy2)K>1M?1ng~T~ zQ20k{Rip#*s+2}$>tAIH5(!9e8ns6{5ixvpi20aHex!!x^HIkpN=b;#q>9MLu)0xF z$6hFqzS(9y^K2-59^n(f5L2uIP-v)A`Sqq*%|>`XH$>4Ul|Dmi{X%m!gYt8a$a@Hy zDO=8jE1rFxUb(^Qt>wh-9)8nrU(9KQtty=`*@C!4vmRLEN6>1Gtzs0+htIh@(Xlrr zb7WH%Ji=K?ddxQWh^M{sM4Hc%u{-@nV04jiUFxC&ig~OKqHN!nA;x5Y!EO`fGX}(LP{k#h8B{pAAu0T4C`0_vH;cvR-SzcG^e9 zrxSjD3HQO+utwoz|NB}^;pFtt;X*jUWMuYq6)po8#gjMh*On>ZBC6o6q+cRTB4q=+4P~TK_O+X6GuQK;%eL zVb#-D!Kp(dpFN-gq6Pt)QdGAwbVz&#z3BEH7t`CC3A3IK%7mJp^)WdN(Q_>D{Zn|?}i z1_KUqOE#meeIj+>fQYt|9oEq^wvvKu{H<;thn{-X9LC&8g$LhrS(R7Ci8El#?C+!B z$G-HDHiMWx=~Qp$Tg!paN!_@wCGRsze^%w|l_K(ARk&+QIV*F=H;?1;#S)K;1=Sce zPh^G2ke(u^zmfjPKgbyczHmQ1jxWBOd>!|07^n3gpb!57EU$95kC7s~misysc;SMY zAn1DU-FqD8Yc+BUiI_&jtCTk7bc2DM-kB7_Z&1aolu#W|gL{_RCx9+f)hIG6)F{eM z$n2Nxx%rgb6oN3SX#%c|^>E9JWb|3sVFUErFnPSCu-U&GOr?}(GAjyBSRvF)#hF~` z(3f_+I)hGtM@qGqv;4%q?t5}=7kxDUTr_{Di)&GmwA>%FPo5uz)qg_thSk3G$X53B zQ@z+-l6CW`j%a^dhlW!VGj8yjsn#HBlZ+=$Nr?4^Q891WM7^Fn++{M8eKPz?2K;$* z%dBZN3vGk%APF&;q)|>{0O_kNqSu|pD$?#C--NdVv^(P3Re0rRZIr9$>S%KE3$-m) z3JTX}NhIW7Ma=aRd`}Jgo&n$`l=nv`T zOuyp8Y<`#l_U6qJ5M{Ifmy(vN{#2orzW%h~=v1QabOuix`f_QUc>LpITD>rCgh${}N}Vw@+8H ze77xq!c`XZMlUeRVCFTESBEUC5S$PijKMqxJilkGQOiO*D#ShUM4F-QkP^vQOn==o zBH0I!Ai3O603*#2$T*=b>gQqWx~;9BRSmV&Y))}1h<3wc2R&h!yaCU*qrhAFu)o>G zO#ZxdjuKR8EFctRgr=FOzl+s4QXrDVoA%f$cgkc4f1Vnb(a?ySjwS zH)&gTtwOrw_cCZ7rQt=)kF0k!fzH=kh5+EN#h)vQAgLL4ggNtiW$_ckozBNtPB&!J zo$98;6uiKG0gqb&Jek|Ehp4_k3FmMg$Oxw@Ig3m-&QM(qLi9!TFYMQZ*4Ot`K%~&BnmY2>T4$3`EV%7*5B%QGGv^$<@pEe1gG%hWaOlNK?a#RZt;aL#a`R>^ zJycK~oVqQ?eFEWGM)2}&x9)E{+jHTFf_>=JRO{v0i3aslpXX~j_`;I-e1wPLj>(`M zSc}-&EDBolPX8B-C@I&UM8^kdXsdl)U>d=&ouQ>HTKB28g8cY-=>C zwTzgJ{7gESoyT2BJNvJm`Y)!!6OpB*QT-RO{-0{A9o9c|`)p2;RzLo!u9p3h`wyjl zzNll4xK#ge?4Mqg|H4@ra39*KLJ?< zm!cFlwfMjnmF@S1St2k)OZIIGg9;W}&GA!bg+dbJ?9#ULb!1eAp&|k$K!a`aR~Y3* ze#N3}8X=1I8zrV)zO~V0C1ULA$Ol3 z6NBt1&DXLLB_2-y7C{?UBo!&%5Z0170cwN@mPzS$2q*#8ni)nP$m`0GS%eT-4!_5b zr_H$cbJHlN*B^o*H!pv29&~srLe-~38ybovczi9+0F75kVQQhFx_44On(aPuOgx=s zWc*T}VgAx5bfXP$!i4mAd9$qad4(FGk^WFUSo3*YPn-13JTMbEb+ z&<;o*G(^KwVS`lgC5`z>v169sEI0I8CPj)5W{bXEjH*!i{73*1gk(-wGQ1mYpn&#T z_T347HU3O@KG*Ocp>-prz|aGc0=o;6%7jD%s5u5D1AhX0wsN|T9Y>^GhNoYK@0>XM zkJ9=(u@Wb`HSQ8~)~i#{8qy>0JnJE@1gZo%7B<%?t zE+X|c;vrl262~zdi%&l@mF&qtANYEcpy8Pu3zO7`@*kCT>{DfR%N3 zuJS^yoH<(gh6jh&U*`TdwoB%7?9mm0g3^T;d1}mk}L`beY*y`H` znTvZS)D}4K!7%xx{>4d!utbbU^;4r@UBN`9E7rS!*(SJYD+*uJ<^N$&$430crA541%D5#N-o@B^u%^JZlNjaK-DtOc!z0*QI2@h8;r{S!P_zw594#dH&%zCt7rvW( z!d|C-9;e-Ir=YH);@+1ktPB{#KVg7KfV4{U?~aK&I|iuwa!vmh8rw zOFbY1f;{5ga>E|Hk6zIh(Ys$y=Nl*8!TWq8=y9_z)X^sKPkV1PjzPAA_qBB>2?*_I zd-nc&qq04Ec^QPTJt{lU%pf5D_;twJT`-F9pU;9H4<|uC-(dXryyu&%OJd!3s=qf2 zkH@2{fec83jOX)7SqB|$K;Fqw#Z;1)JBT3M|Cr1EznJ^*Ial_JF23)#%_4@&Cimtx zOTCf(6b9M*fBow;)%6knzdQT7_j0$N(UX*vBdRKTx|rlj;jXoz>=&VOB-O#Y6$!xJ z?0j(PvK$3AA$rEuu++2iR7RkYsK_F9-@-voRai3`x9fAPg8OrfT$4>&-ePCCwSAs49;O%vy^-&!opKNu2vb9uv9@g?(`=MTeISt71;XO;Jnk7=J{l0Bj#N=Xt{Pj z8QZG?zNdlx`jsrA34Y4h2@*1=r1F<$sftaWb4x`A)nhk!!H(imz-ecXI-{wnfJ>B; zex7n^a%$e}QOYX^laToX-d+7+%(_*_b1H0_$u&UcXRzkoS>dg@BIP58OJrv=o-w>} zlCE}J2e-H5vrzYH1+{y6%l(QTc3Qd=OcVuG+%L%~pMqKie;uwvEfRIx))nWz*(zStNhjhgQXYA&7~tbV&l4%KY?tj^ZM1k7cmDM^@l@+T3!i$ znRx0(?8w8rN^SC2cA0357>#-Lv;!+>NM>@y!D^mgZGI{-AhKo?iz_y}$-c(x6Y{5< zo|?MH$`QQ`RcmMJgl}fa{6cfvVwOu^s`XbFM6H5YycPX)0o98>kP~^uxR(aBHR)5z zXg4@%d|0Ilo3PsBN|BaS#gMeDzf-9BNOXm(+v!JCTW0YR2U}#8t6b0t@E-PWRtGy| zmY(CkB%yxS7Q{+l$JSFB$_-~HtxuY;v>92G_G-Ibk~JoPQTQ-zu{RhE6K~Xip3-`Y zrPb--2{k=d26}7RYj*sPey?F!W$||28rs|5kCG+{3xlYP+E^V~Uu`i|TqNrBj0Q8m zEj65}=%tJevfx|Q7LFY|h=Np{>l|y@4JM|2QA?KB)WQ!ehouQ)83|zf`E~eEUafa; zk%hCA@sFsMyC@9$7x4WUUm`|pghcQO@raSW4}s&#wl|vT^M|wjfWh(iELtWXd)ibdU(cb*Br47 zhMc(*9I&5e$H4?I1*+5Tc;jd?PSKg+7Lekp$_)GwLJZkKrwXI)O=R=Iutq^{d{}bB z$W}&FsDRx`$RNmW!-=#+?EeEsZ=AGDm9D;sWy!c|%seWaS1Lv&KzC;0wczvxPaILq z`D`M$Zg3oWa-C3r7UiOea-5x`sEv}yqH*wn5x8ArB5D~|4@|c9l&EA znphG#3ue@_8|7WCe3L`N`XM^C3~!8oF8Ba`m|oYk(mzpa%fsoHoFE*T2&-l#so~%o zE)`~7hJ^{!`ryVKk7vcBm!NKKzs#bNk@GVQ!Cs+!8Gbu8nY$3uq)y0ldrXYeyVftf z;dB2nCQcSCB&BL_Ayb-tNZCPy*_S$w&NBhpNjva*CPu`>0xG80EG!;OPVTT zA1{U`QlH?Lyj#{NlysJiMUmkaJe^JMhE zF&BNY?T!~GMiYJ9Gl=SL87CLIrN6(%G=b{(ty#U|+rsI@59Bc!t0&lrDW1X8Rai%O zu0RKHC=S<#a`ziQ#xcabY}lP8y@E;j?N#EaG)5C4mmcS>ujAqB`MFTdYHvWWE>MyNh5Bwlm-&gyYyZ|%WPlmSd@ zC2MvUoOg9e0+y<}U2 zwJvGC;0`=%>Zk`9rl!(_jo|zGDK8+YjmgfsYjdfw&1P0Cb|-Thr}AKJph08*Zj}Qjfo@Cup7a@EdvOUx#AI; zqE-yMF1{?S%NlqY_HeEiPc|KkZYg|F<$TcE7OZMrV>rFMFmQ)txGo!G`;@88`4@-C zVE)wKoho$*AM2?1wtdpJovMw{(cHy618W}4IF7&OYovIYi@MXLP< ziJg<36WY67(yK((B%h|p9iT1JQ{fbzYW$H7s;U|sTr2CItQ2fFD2u%O_jp-nzx1lK zQ{Ya<-`sV6=kDp9h2b>lk0ABRKH$ehkEQ@31W4L9`G>&VOG<(pZKqvh_{nsMl?%f$ z_&ChN(U-{2!b=oI(<5*_qdXttfu@>ce&=~qGnfCw+y3wb8n}Pw0`r=e;;eAkGpU*q zX-aihNo=BK*Q+}jjjTgfX$7>Rwedt%y-TAm?(LmCF4-BZGEy*7R}%u6HOIK#f1mdO zcAcF;qF|T^g{7{;(}Hi4wQkCqXWNfpi%*Y~I_^?jm~ zf$cOnR}zYEq&mf)dx}SNopG-98RwU6dj}7Vm6ds|l|oO)0Ik+%uth@MEKP4&5=l{q zdsCSH2*L~=Qn7a5tjX=H+1mp};zb$XeG)#<_;dbOhn5@a?SXzP*=^Kw5G}ZKx%CiY zsps;3WO)DdZ!Jx$p(zZLL319ZPqp-^2#Rh$DipIur5hQeLVhLF)hFr3=iK>3D1A&j@82^)s>Z`elstV8PY4cER&{hKLis}TeGsK>RisfR|!)w zE%yd8KR5fKIX0O2zS@nG>*hY)CJ^`-6m@-W_B*cvglF-O|4OFR|461wvMWPw;QUz= z$DT04Ais~&>CN;uS#)30#8^$q`7|I#dgTN6tkVtrpur;B*q&2$dUN`6h6p_GuSpaw zxQA!VD;v(GFMU964bcyvA#|tbU#~VC^?jCr?t>z_0P%z1F{BiNeM9dQ0)En2q1vfe zK#;Bq0VKSDLFOwvSB&=}2*wmWtsY#aC6SV$%Qhd#P&>hz6D$Ui!gt!aTapmK`q z;;SY-k_VG}LqUacS-&W#y`EB^6}2VvfI9P$7o&ag@@x9#^T8~Ii0<<=#DWRB8f$SG z`(LzcLpe5)bPl;4jT?RMp()>Uma}vn5;f>>6cavEBf~t!-r3uKCw?;L=cJ8L<=u=P zi{rQL&iat;6{DM{VA%SVS@|lvku`MqAchW1nAOT z+Ay_XPLen=WPU%=;f+eUdUYQQIGoILic;b~xfbXiJ!ZIy1A3E+p>N+6`uU(}o@R@> zadLuckq>MOxJAsL80KbyU7d!;u5z}|;%1$Slv-b>Zy8y`|q9TP(mRn#h z+sY3{C7dH5&#f5?)-->JM|J=Qh-A1}v%MMN4cmM&3FWz0@{V8|T&x;P{Phu?X)B>^ zSA;2XSN_tmcAs1WjScBj>bo%#Nj2fE7aL=p^4G%dd}cjHka#P_ru44MDi~M@E~}umhJKW z+u9HG%t7Vl5)-UGV*ii-3LcBfi)|m6^U~fQ19HI+Je%x?xZemCSTyxxhvR~Ua3@eG zBTI&x7{zocQV8Fg$%$m(w=QNO!nxp$C}iM~hnQUvA84VbP|Z3{N;}Z) z=901Pkj&aDZLr*Aqo?8yMvKW_y5uk+yIQ6xV6d<*PA>~UYmbkzGI(4@$L}LwYYa!K zyI1M^+jD+d9Eq0Ky6QNdI zcq*xsoQXCg9d9NUY@Y8aOWI;JKLtU?>4GsfkpSLO%fYWeV&CR@TI{4v%x&Xmd9y5& z*rte|uPu)?Bt9ZpfCuz7*^At`S`==fNob^rGvzWC`XQFtX(hVe^13Pa8a z7N(%XnA{cQb*Ny>pteoIgxvZIOM{=Up}HgHjn1XE_*&tudq#?3Zvw%`o?AfE>dJoR zWj;0yQHG6$H}NwVW%;p-e*fvOV<}hrITEJ&#y?=oEAn~ffW$SkGq&YYKg~jZLgnw* z5iacx9C#}mX}xgc1&E=fM79)3nS@v|_(qCEFMbzhlE`(pYR&cVpJQvq>NWT4Wo*kG zROrEc6=K8YZjZ*&-HtjQ=L(gMQefJeJkVu+hsFaoFFH}u>I~U^8$%2f^K+ehiR8md zkSDrd1WSjL0p%!KDOLodpEzU}js{KQG_Cz*zkY@riuk7KpCPV^Fz!oV@>uLLbTBZ0 zn%FXKHoQEz7>e@Xd%rQ>{-fYh()&(6QGSr~EdCtbpQ>Sr=qBL_@-5vd!Zlpv9Gzg< zXAz-b4?9U%#_Bs{{m_qGeRdl3zBb43!a?RAFXxvAeEGHW82H23uTo%l9Lr?ka%E9_ z4?EpCew=5YhimGxM$snoMjBlWWuk*;t51gGW=UJ{2FdI3iPFjQu1QeHT4pCZCA_S}|JFo{O%4 z`LO_6)z;CzIv3tPW+rnJ;RD=DX8GXiLFR3C7NRiH`Q&1*U^Q|aRcMxQWO9ol15#9; zM)*0I?r1KiQwxf*1Fje*eRdXko?yciJHnq_l!CxvZEN5wn8t|}booYuHMvo^bbw|u3$m=nOhjF!>#ADkLeDO-V=F zA$}~A%&-7plg=%Yn5u~re1hpJY3s$IFk#L)sgNj+Q=?y$^{Sj3V^=46fs(->S3Y;&wx&rK4YoNptxd!7e_ z-?~v^b=GR(RWY_yIj}|Fh4VichD8#fQ=>WWNXWkdUs!(7<723I{*bnT%)WG&08#L{ zuDV)A;C}{PrbS+#u>ab^I#fH@&cDGgElhD`JI4?f99{fI+iW=R8~dTv|CHaAco;s( zG)`Q3a&o;zB2}WV&LAs|e@IK0^y~e|>Mm)vvyK15I^&n1kaK}JDQr6JJ-C3k(x6W= zq|ebJydF?um|jqf|nbrpaF~XpI4vHh6~GmER>D{s$l46kIiW5$Vc4~5qT)C zd%47!_^?4dq5R@ULt>52_8>PkWN4{fZvMVNF)C{&hRoEH=YU2xF)^9IqCrvoK0xIo zFkr)p6yi}GJ~T|?pe8!OoNL-B=d%I!N2uNq+oMIfBfe%EL$-<;sfB_}RNjrax2j7f z(-)!AWRy{-Dvm;r=g%@TJn7jU>=LbI13U>lk2_doiy8aERIiE>_A?8xD`@R{bDBW6 z$T0snW%hYqciSc{=%;BVj+grHai9{6?BUL&E{RnS(tc4tX@B0!klyy$j~}R9E;5(w zedTb!0Y|odtio@|-f5eU&hoAzl1|6vAVO4vx00^$sHk8%0o@FxF0IG~07mUZ3_3q$ zEa%fp!OS*8>{~%21SeGy1Htj*5kr2-IN>s3*$Yy1y@zZh7{KSQh0f$aFTw7`K!2Uz zaq}6x*s+_7TyNyP)NlO@n_-(2$xCD~&$w5zZdh9t8FhM1;yM)IDVG8p&7(tn10)>a zGZS6vI!1v*Natbidv6jh0lSbwv(fr85L-fY$gC0KZPR?&s8>s^(;*vvFvw@~;6k(U zRT_IxpT@>1dl1&Y@b^3>3an7O2BBH%P&?r^zLE*pF}H9#H8QL8@s{c?s1V$3GEqAHYy{GMueWhSHj|X2%$Q%D6ldyA7oKL^PW=2TiG+D;Y6Mk z!u(zk+4^}mhqrhPVx}EwidyIj%N@(@Bh?unxi8a+8V17I2D#2yjRD$C4hh2Ad{7*e zLJzqPx4Vy6P_7cz{~;|i37)eH!N0)?>yM*<_PmgZ9uac>BA8Ga2?_k^E1{Wlw1k@I zd*xjCYoyahDgq*aTsLJR@*7g<7bXNDr)n47HLb|an{7igm`$i@PWiaU`NTf3 zW$H>;0u_#JYjS(TJbll-5`?Dd>i7ZzIEja@w>EqGb_)J#@Z$(Yx;iwQYP{UI6+bXe zyt**9$+jkIo(~r=|K=v?bK%TyB?_S$FHZ78#N%FdpR0ATffKlMa=K*ry}eCrlF| zmIgdQ|6Nfr$@B+#zJY+C;>YO^5df-6@~!wSK?(+D$f6KbWDpP%pkz?_kVZ%12GOz6 z@n{L++zA&KP+~1clri6ggDP5|FW#UpYza=`YZtiEydT^jU*@*KwWMR>lQXfv{GzF8 zhAsUsJJOJd_@A`@sK!EdglteAw+a)w<#7v=*H5s|4cW1f zXj*J2?BJ2gJ~@PB77vY4m@jv@E@Iy|+FXw}nKUAXF>T;kkz?|Sm0u(1;^;en5rkd7 zIwj!HgFK(!hLn$%mmlH}k^)faB@C+}w_h7G2#r#MljY6z4;^S0I%L;&lx=ZaHw_#U zQ`zFOf@c3h91ozXd|+aRokP#^UUxId;II$O(fapb4p200kJe2`KCug(IC`ONOkyAA zd^HfC8Cxxa0OpUTPZQCMoSsjlsvqRy7gt-(&=kA9VymXoUld}TGyx7wpv{tc_uDrr zdXhAunV%c#OnH7p`%Xz0_o7ttlqcU$9h+>Vwv z9ui_wtFkJr*W^rm5nzOHC(0LrjPFZ9!th;@;8%aCyk-X8l9CYEqz?8WN&z4e0k$7* zAo1R9x+w=C_~mfVZjRC)dqjt6sg?A^q(_~Auf^LZ;NmAn12{{ph>tp4#w+gLp#Pep z6#7!WTCshyry(CFMLC2~`1o!PP+U7UBT%cChOuy7w1DVU3JZJw@ zGVX2yt2#)sfPx~pv($Ob?Z(xWW59sX=eV{dK0Iu+_X+whUdMA9Jjw-;)o;8guYGeJx8=^lP;TNZhE16|vi&Im@x4c_>O=6@M4HsF&C-L{py5qY$ zqKvX+$9!R%kU&9rI6P!^#(a0WqNRyA6ojylEJ37*pb2woUb;uuWdD3ao^;JzO*eAB z1C%memhV&Nk1dgKOf$8peX)JSzZ4a}EXYE+nNH)ee6o#zh9&$TRgIklAcwJwGr1bK zE*fUPXWlDnS%)@p^7|tesjALLK3WPaJFe+^14s7vje+LXAaZncE}TI161YDn*y=Ivdx1&@Y07gvy!+mgPwh)Ck& z^@Je<{Nntw(kXLsQjc2Z$ylmx8MIP6D-yJUC+Ia#=DGK}QkPN2>$4+au|be9#CQXT zS$H(aH?Xhv6aoUBKavR>)|Dh&Pv?mMwMO$>C7_fuR&D0x$NM-g=rd0>i;v2(8i9cU zT4g1D#&m5@)6 z3=1RoJ2rq75uskaji{57l9C)53DKx8mCfQmx85sC%T49&2M@p=Tj_d_mPCXVF9joM{~+HGvj4{k5Ih&hvHh zu2>y62@0KNC6VKoC3oyc5a$e&o4Qz`9M*{7DBGDh*Ar`d2_w>YMLEWYyA!X+Dl+8d zGe_>0CVxD__EorDqvQ8P{&mJIJ0;lxQXO_o-c`5;)ZZxec!#ByR%qz9|a+qNNY{ci-=}D$C1g_ZO_8Azic1{&hv5 z&7T61!s}>U?yum;NSl_K(AS9!p71+49YI_-IyZ-33^%vodsban4QT5^~PmyTDRjs z?X&qVvZ9=oR6lZi)m-byHBwVsM4WpeJ57U?Aw6SfDk!o5x)Q6QzRDAlo~+(aPQC=f_hjS+MWO-kGo?on3-ukUH@( z%6rAb{{Foq?>wdJ*qjed=h1uGK`rFgs^#dU!j4x@L_}m@nE0)0vlGE@2^j)t$h4loya0E6HqVA6)Y$7<5{+qMBStb#3U` z5i{Pv!8vE_(5oEVl%`3O0DaQx-gpP?#kA9Ead)Goqf5$Qy$p*Jql~u^9lHbLj-sX9Dy_lpRaH?T zCnc|7#7vW6qpVQ>DEw9yASEL+p*Z_U>Ni=u>)L)AAqc)VY#dc}b0x}%jlF{iYGbZ1Dt05ZSQf?slOY=EVWi*=^f=wh~fHKla1}e`(arlTz=KkGU$we@L50u za7Q0aQ0bi-P9b=E19f+Q8qB+}8pPTx{0`WyxtFy^;W4eUG!m76XUOjV@(UassSlkE z9s$tY40O)}2MuBF8hAv2cLI^l&M!cKET!LLeCZdm0gN)CW$xoademg^JTF&yD2$DX zZ-bq<3kKu`YgJOC2zTvcI}um}qY2_?r*8mgKtqSsFN=1xl+oh{KBMhP39U=P7 zq}8d;9*`cPuDN+5m5C1Q?~YqO>m;{`dJy94`df_n{(j`;eINA@MD8f#zLU8+IUfzS zo=PvWHMYQwFes2pNKSI9ei517=Dlk5u{g|<9@^MC@O=>m0_@#eINe22M<^%VO!&mj zR)U^FKsS=7f_NZkaJs@iw^Z`Sewo|a;?e8tEATL4=xf+4-i_pZu53bU!uY!SI5$=~ zE8t_rV|szZS2Nt1#h6^8-qh4A@harwv|glEAEUKd85k1sV{Lo98hpXu)465-S@w9P zXwuM^aT*Ng)*-n@yKy0t16vaP!qym%l;%hM4#j7AB=3O{YOO{Ald$&4&vOO<$+T z?P)a0>crns+CJe-r;*nluA$Y7W4fSr0rY36wa>Gd-U-_~-c;%)hSOflyW(xF*{=%l zVjpL>J)X(iBwHXF# z1^Osa71u>Xw|3g(s`;52i?l2b4b);xTr4a(F3%-3Rf;{oV~+f&9%zfd1U-+?z&)0D z4rGWLxqw(gD~s31gSD-9z}wzyy0)P2=j*l|QFf{(`Thn@ibAE8Y)C?a%DAnqW6dE3 zm}ftk2-g2#eF&k!cZ1U1O!VQRC-Rs%WYDQv{|h2nno}u@Ru+(w(NoYcSy?vNfgxThJ*)r8W`;4p?uHHZ~PH?@P-=!fOs7{a^}D> z%+=_a#jqCFOn6Dma;Piaf;Qi3{v0wv!*p6Os&Ut|AO|%Tbrq6;^(peb|DjR^HnCaC z^m4wAvsZD>*ot6=Hub(m7$DqQgKh}1kG7Z?vqeISPOFDKB=d&H3Id z)bM9XN%6|SfQ`r&4o(QkHd)r&!zssJay3Z?K9WEq!!0Q@%GvW2Q02fw-<2;&KdOnT z@uud6Q2MH^R#yuD{Z)KxgUecRn}>`tlTOfVq0_=uFmu zxqbD4l?=kh>a3W^`kk@FJ2IWd24r(s3y&I<)*6QD*FKi>t2QNna6YLb1YIZ0L6}9> zb8lE&Lb54@_H2(X&;cC6Mul|Y$o4+ZGry8)&J^%FZ}{}NK~{BDT8Z5pP~liu=(o2t z$h#z%4M2to#o)3uCtf_lBNkP?rmSoxgZ`psYsqUwP;lZBV0b(J_!EZ+pYx11(BRQ9 z6iM?VaeVb;1KQn6Lt_Pu?jmb2O54VigYAv}X&_y6)YQcQm}w={F2U;kqiQXM;4eE= zHRryki9NYvi2ckHU)f}YvtFcuQE2U30QLPLo##Mw*?Ko0DiB-7`c746I8rjqw;HO;YdW_X**G<2yX^fME)upkifE0#}wVV_#U1o->!!?Lj+{($#d^YtubM_sbiT;FY*i}jg$x^MZqRB%KE94WYt)QUR_MMrRV$nVFfXU9W@%)2;A_YI-{qz{dB_kR_esmslZ@0-v%C&s3@v zesJsgToHS*$+9qy{gO_qJ6*HqhKAb_bz*q z(YnPRcEjM!H4Nfv`f;UA!gAU{rlFcvQ+apBIljm-M+qllEu`ln>?P7 zj29*#Mt>th|K41h<+B7{;^5YQjEn>Ns-08FZ@g<5mt^t}-pLiRaHfd3*-=#N;3TxG z=7-3s&=wjh{+Z6_>#Nfc-KS}(T9p_by%J+Nx55WUOnrBn74$IlmHn2j^QA`E6&o8s zzAMGR%Fr0%iP7skO=&C4wmnO9kN5LcXl!d6JJ@>_bKvxb2Qyj7H6vYWRZ%UbxF2~{ zZBU@swKXM7E^nu_bVFs#UasM7NZDb?PJNzXyGHtI@y6+cj6%CmL)Mr7X#dE*PacJ+ zn~?tuZ;~h{5=o$>?0B3fr`Z2KF@e-ntc}*A?wOc)%lLR>arUG{e>f}!@FLAVf_(LM!S{U2Fz=Pv$Ev=94h^z&RPBy zYe`yZ=^FMd!g0U)fagrTd`mc-rNF~2KfU$G@Ly+k9z&ic%QUb#+qX(%d(+X;rtyqb z0-Sv|H+i^fk{M8V1-DunFJ{0Z}O%23=GqN1UFc67kL z)qwDe16wbYiL%Tg>sOm<&?ra}YXPTrb2{8g?yd)+7uq9dyfZT!sPy4w6|FJCen-1- ztAC87j4)YDjuY3QDk(B1>ipD2{>Ef4)S42L5~;C6CLq^LoO3JsGwEmn-;)!n>*zC2 z{c-bG{uGg?hr-w|YXiu3`{LJRk~Q^E$%VYfvbU&X6k}G{xF{V(e!nn2v;=Zl`Cqp_ zJAeE{mE?4C3;LEbJwHs}{EMm^eApJX`yxXTnuw^d2%YbuM9Ynt*u8{3vbs!;dxMFIcCMYo#7mrLCvJ=la1`& zERMr^y1F?PJ?%*%Xnv#kVphYJ)Zx3bMedxHq!78MKVc}T$v`f!O1Zm_Z`H5psPN=Y zk6jAVJT?g_spIv^QO)>gDgVQ->qPa>{^jE_J_irvH@oPV#T0cm#6%(A*f=zcex7KjUWh zbgE36{5YwEwv#nyg6@^pBQnBrWYQ7RL$_Q_!pm-RoRxqxJ6WRSuyT@O-pXN=t~$SE+tz}(>Ja4j!J;$A_il?)=;N< zHEhAl*Gqk$~wbQPQG&*X|S+dERx->~&tC5gk{n>}O;4GVm2b)bqw$Q!wmW9GX zlJ_JjJ$Zb2XJ>wberKYi%(=&J4vCFH$_s4bNlZ6dzxH&-49;o&hBL1m@$h+k+PNio zrR2#;RsQa5nV&t@bkZL&F8-zx_ZCnhVKp~`d8ZGLLc-)S9wnD>&^N9hB?y)(9e4yu z*(}X#zgl*~8u^(n?3s*q_H_w`DlnO=Gfc}(il4;CHe#~*xZOW^*`C)F)t)9?#hh3T zB+d(q1zZP_PKhKy;GFlUkWo>?zhXK+rE9?Rt&DUkm#+}mKey9kwS2I#mnEATFT+?| z@AHC8;%xE$ygW<4TmI}Y!k8-l`N_mYa-oX@L)Jvb55kgmN`M$cJ&p2+0U1b>&0~0& zW}BLt`k**{MpGLMe~`rZG&>rZ9vzG-c>2~5?^+TZ@0Jqtsd z<9o_H$DpG~ru{rjaMtSTYNLi_%5UXy{QMoti<}a?*V#$B))Jo0VY9Zz4LkZ_VL)y6 z^4y+|$Op?s1?LZIXIzv`H!}%YQ-3SMnkI5bUp35bZble5>2pTZQGa^geiXeKh8PJ> zX6}_e*1u=6Wp|yS*7e#0IAXpxk2&d z=uCt&pv0%P7U|#ZqfdP8?woN%e!eFguAI-2%kC`-4DapoF*h)0Sz@-V#yX)%fT36t zBABTp3Z*X3WM(eNvbj8IJjjP=@L1qg1>5(dybvt8<1syZbH16H=`f(gMJx$0( zH^UH#&@NgW57@5SS_(Nrp~8B1nt9^H<#bvL(r+R;_j$-8G3;CsNr8@kj`uRUPYpRK z$Q4!L${|$F4tbj2??}H&aG8B!dC${k2x_}I!+EDhMw&B9_Qs!`2ZuY-l25Zq?O{Vq zs4%R=>f%=}_Ur^9^^@$^afm5>(s;71hAo9Cdra9I|n;j=Z^I@V)mXi`ofA6a_32-3@&|XoAQoa?I-Oj4?G+^@s%9K~ zYeZD6OwPA!cauWLNh-&Df!`Mxolk4`JKj(GsPGe_yN`3o*B$UOWW@>T3l_vyP3~>tBS63cS(NdeW%?a+kaGt2-b~>| zcDKKq?mdh_?wcC9MLDJoW)kXOZ#xFB?1iqLbY@xo9!`&VphmGaQc%_yMc^A|E%hpq zJfMnjxfw9F?TE1vncd84?Aj(!-tqr25xD>Zxu85f!3tqYb<$#wuIF30kigbhyPtgv zZff=yj&t#G&&;D3hidAQ~w0zid%&BY3%)&52ZV^tq z1pTCjsG1M5b7E=ltxfY&h4IGp*Ld{ZzK>LBY6>&a710=p8ypy*F3N>}piBerlUn;i zLZzb_N+c%1QM2l$PPrvrH1@D-41Q{AomKTjQcaE0GuLPMR)gceSKu7hx32onn-gbL zHTPhKBKbaTySG3_0aFJ<#lT+Wtn=`5$uqep#sIg>FJaMxo-=X+xh^uh-CJc`Tj#`= z8=BGOC3C?S4N5>9`w!{gi66CH!D>rD3@3ll(DcGFgFh1hb2w(e8b{6c7Z?Y0Ym@L3 zLqmAu!rR}6;9~s@U~r-rOzDF|_AU|-s0$C!U-m^1OmevcU6O1_k&W)^t83^V*&3D~a*t%rwNARrL= zB`9hR1bXReeGUk% m+=cxuAq}+^QGs{fz=O9gL4*VZfC`oi$XTI=9uwf*p#K4c9;hM! diff --git a/stiffness-study.org b/stiffness-study.org index 392e58f..0aee23b 100644 --- a/stiffness-study.org +++ b/stiffness-study.org @@ -1,4 +1,28 @@ #+TITLE: Stiffness of the Stewart Platform +:DRAWER: +#+STARTUP: overview + +#+HTML_HEAD: +#+HTML_HEAD: +#+HTML_HEAD: +#+HTML_HEAD: +#+HTML_HEAD: +#+HTML_HEAD: + +#+LATEX_CLASS: cleanreport +#+LaTeX_CLASS_OPTIONS: [tocnp, secbreak, minted] +#+LaTeX_HEADER: \usepackage{svg} +#+LaTeX_HEADER: \newcommand{\authorFirstName}{Thomas} +#+LaTeX_HEADER: \newcommand{\authorLastName}{Dehaeze} +#+LaTeX_HEADER: \newcommand{\authorEmail}{dehaeze.thomas@gmail.com} + +#+PROPERTY: header-args:matlab :session *MATLAB* +#+PROPERTY: header-args:matlab+ :comments org +#+PROPERTY: header-args:matlab+ :exports both +#+PROPERTY: header-args:matlab+ :eval no-export +#+PROPERTY: header-args:matlab+ :output-dir figs +#+PROPERTY: header-args:matlab+ :mkdirp yes +:END: * Functions :PROPERTIES: