diff --git a/dcm-simscape.html b/dcm-simscape.html index 834116d..b3c5612 100644 --- a/dcm-simscape.html +++ b/dcm-simscape.html @@ -3,7 +3,7 @@ "http://www.w3.org/TR/xhtml1/DTD/xhtml1-strict.dtd"> - + DCM - Dynamical Multi-Body Model @@ -39,39 +39,41 @@

Table of Contents

@@ -87,22 +89,22 @@ In this document, a Simscape (.e.g. multi-body) model of the ESRF Double Crystal It is structured as follow:

-
-

1. System Kinematics

+
+

1. System Kinematics

- +

-
-

1.1. Bragg Angle

+
+

1.1. Bragg Angle

%% Tested bragg angles
@@ -118,7 +120,7 @@ dz = d_off./(2*
 
 
-
+

jack_motion_bragg_angle.png

Figure 1: Jack motion as a function of Bragg angle

@@ -136,34 +138,34 @@ dz = d_off./(2*
-
-

1.2. Kinematics (111 Crystal)

+
+

1.2. Kinematics (111 Crystal)

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

-
-

1.2.1. Interferometers - 111 Crystal

+
+

1.2.1. Interferometers - 111 Crystal

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

-The position of the measurement points are shown in Figure 2 as well as the origin where the motion of the crystal is computed. +The position of the measurement points are shown in Figure 2 as well as the origin where the motion of the crystal is computed.

-
+

sensor_111_crystal_points.png

Figure 2: Bottom view of the second crystal 111. Position of the measurement points.

-The inverse kinematics consisting of deriving the interferometer measurements from the motion of the crystal (see Figure 3): +The inverse kinematics consisting of deriving the interferometer measurements from the motion of the crystal (see Figure 3):

\begin{equation} \begin{bmatrix} @@ -177,7 +179,7 @@ d_z \\ r_y \\ r_x \end{equation} -
+

schematic_sensor_jacobian_inverse_kinematics.png

Figure 3: Inverse Kinematics - Interferometers

@@ -185,7 +187,7 @@ d_z \\ r_y \\ r_x

-From the Figure 2, the inverse kinematics can be solved as follow (for small motion): +From the Figure 2, the inverse kinematics can be solved as follow (for small motion):

\begin{equation} \bm{J}_{s,111} @@ -205,7 +207,7 @@ J_s_111 = [1, 0.07, -0.015
- +
@@ -237,7 +239,7 @@ J_s_111 = [1, 0.07, -0.015
Table 1: Sensor Jacobian \(\bm{J}_{s,111}\)

-The forward kinematics is solved by inverting the Jacobian matrix (see Figure 4). +The forward kinematics is solved by inverting the Jacobian matrix (see Figure 4).

\begin{equation} \begin{bmatrix} @@ -251,13 +253,13 @@ x_1 \\ x_2 \\ x_3 \end{equation} -
+

schematic_sensor_jacobian_forward_kinematics.png

Figure 4: Forward Kinematics - Interferometers

- +
@@ -290,15 +292,15 @@ x_1 \\ x_2 \\ x_3 -
-

1.2.2. Piezo - 111 Crystal

+
+

1.2.2. Piezo - 111 Crystal

-The location of the actuators with respect with the center of the 111 second crystal are shown in Figure 5. +The location of the actuators with respect with the center of the 111 second crystal are shown in Figure 5.

-
+

actuator_jacobian_111_points.png

Figure 5: Location of actuators with respect to the center of the 111 second crystal (bottom view)

@@ -319,14 +321,14 @@ d_z \\ r_y \\ r_x \end{equation} -
+

schematic_actuator_jacobian_inverse_kinematics.png

Figure 6: Inverse Kinematics - Actuators

-Based on the geometry in Figure 5, we obtain: +Based on the geometry in Figure 5, we obtain:

\begin{equation} \bm{J}_{a,111} @@ -346,7 +348,7 @@ J_a_111 = [1, 0.14, -0.1525
-
Table 2: Inverse of the sensor Jacobian \(\bm{J}_{s,111}^{-1}\)
+
@@ -392,13 +394,13 @@ d_{u_r} \\ d_{u_h} \\ d_{d} \end{equation} -
+

schematic_actuator_jacobian_forward_kinematics.png

Figure 7: Forward Kinematics - Actuators for 111 crystal

-
Table 3: Actuator Jacobian \(\bm{J}_{a,111}\)
+
@@ -432,8 +434,8 @@ d_{u_r} \\ d_{u_h} \\ d_{d} -
-

1.3. Save Kinematics

+
+

1.3. Save Kinematics

save('mat/dcm_kinematics.mat', 'J_a_111', 'J_s_111')
@@ -443,15 +445,15 @@ d_{u_r} \\ d_{u_h} \\ d_{d}
 
-
-

2. Open Loop System Identification

+
+

2. Open Loop System Identification

- +

-
-

2.1. Identification

+
+

2.1. Identification

Let’s considered the system \(\bm{G}(s)\) with: @@ -462,11 +464,11 @@ Let’s considered the system \(\bm{G}(s)\) with:

-It is schematically shown in Figure 8. +It is schematically shown in Figure 8.

-
+

schematic_system_inputs_outputs.png

Figure 8: Dynamical system with inputs and outputs

@@ -508,8 +510,8 @@ State-space model with 3 outputs, 3 inputs, and 24 states.
-
-

2.2. Plant in the frame of the fastjacks

+
+

2.2. Plant in the frame of the fastjacks

load('mat/dcm_kinematics.mat');
@@ -517,11 +519,11 @@ State-space model with 3 outputs, 3 inputs, and 24 states.
 

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

-
+

schematic_jacobian_frame_fastjack.png

Figure 9: Use of Jacobian matrices to obtain the system in the frame of the fastjacks

@@ -542,7 +544,7 @@ The DC gain of the new system shows that the system is well decoupled at low fre
-
Table 4: Inverse of the actuator Jacobian \(\bm{J}_{a,111}^{-1}\)
+
@@ -574,17 +576,17 @@ The DC gain of the new system shows that the system is well decoupled at low fre
Table 5: DC gain of the plant in the frame of the fast jacks \(\bm{G}_{\text{fj}}\)

-The bode plot of \(\bm{G}_{\text{fj}}(s)\) is shown in Figure 10. +The bode plot of \(\bm{G}_{\text{fj}}(s)\) is shown in Figure 10.

-
+

bode_plot_plant_fj.png

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

-
+

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

@@ -593,11 +595,11 @@ Computing the system in the frame of the fastjack gives good decoupling at low f
-
-

2.3. Plant in the frame of the crystal

+
+

2.3. Plant in the frame of the crystal

-
+

schematic_jacobian_frame_crystal.png

Figure 11: Use of Jacobian matrices to obtain the system in the frame of the crystal

@@ -652,18 +654,18 @@ The main reason is that, as we map forces to the center of the 111 crystal and n
-
-

3. Active Damping Plant (Strain gauges)

+
+

3. Active Damping Plant (Strain gauges)

- +

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

-
-

3.1. Identification

+
+

3.1. Identification

%% Input/Output definition
@@ -671,13 +673,11 @@ clear io; io_i = 1;
 
 %% Inputs
 % Control Input {3x1} [N]
-io(io_i) = linio([mdl, '/u'], 1, 'openinput');  io_i = io_i + 1;
-% % Stepper Displacement {3x1} [m]
-% io(io_i) = linio([mdl, '/d'], 1, 'openinput');  io_i = io_i + 1;
+io(io_i) = linio([mdl, '/control_system'], 1, 'openinput');  io_i = io_i + 1;
 
 %% Outputs
 % Strain Gauges {3x1} [m]
-io(io_i) = linio([mdl, '/sg'], 1, 'openoutput'); io_i = io_i + 1;
+io(io_i) = linio([mdl, '/DCM'], 2, 'openoutput'); io_i = io_i + 1;
 
@@ -704,33 +704,128 @@ G_sg = linearize(mdl, io); --1.4113e-13 +4.4443e-09 1.0339e-13 3.774e-14 1.0339e-13 --1.4113e-13 +4.4443e-09 3.774e-14 3.7792e-14 3.7792e-14 --7.5585e-14 +4.4444e-09 + + +
+

strain_gauge_plant_bode_plot.png +

+

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

+
+ +
+

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

+
-
-

4. Active Damping Plant (Force Sensors)

+
+

3.2. Relative Active Damping

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

+As can be seen in Figure 13, very little damping can be added using relative damping strategy using strain gauges. +

+ + +
+

relative_damping_root_locus.png +

+

Figure 13: Root Locus for the relative damping control

+
+ +
+
Krad = -g*Krad_g1;
+
+
+
+
+ +
+

3.3. Damped Plant

+
+

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

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

comp_damp_undamped_plant_rad_bode_plot.png +

+

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

+
+
+
+
+ +
+

4. Active Damping Plant (Force Sensors)

- +

Force sensors are added above the piezoelectric actuators. @@ -738,8 +833,8 @@ They can consists of a simple piezoelectric ceramic stack. See for instance fleming10_integ_strain_force_feedb_high.

-
-

4.1. Identification

+
+

4.1. Identification

%% Input/Output definition
@@ -798,16 +893,16 @@ G_fs = linearize(mdl, io);
 
 
 
-
+

iff_plant_bode_plot.png

-

Figure 12: Bode plot of IFF Plant

+

Figure 15: Bode plot of IFF Plant

-
-

4.2. Controller - Root Locus

+
+

4.2. Controller - Root Locus

Kiff_g1 = eye(3)*1/(1 + s/2/pi/20);
@@ -815,10 +910,10 @@ G_fs = linearize(mdl, io);
 
-
+

iff_root_locus.png

-

Figure 13: Root Locus plot for the IFF Control strategy

+

Figure 16: Root Locus plot for the IFF Control strategy

@@ -829,8 +924,8 @@ Kiff = g*Kiff_g1;
-
-

4.3. Damped Plant

+
+

4.3. Damped Plant

%% Input/Output definition
@@ -871,13 +966,13 @@ G_dp.OutputName = {'d_ur',  
+

comp_damped_undamped_plant_iff_bode_plot.png

-

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

+

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

-
+

The Integral Force Feedback control strategy is very effective in damping the suspension modes of the DCM.

@@ -886,8 +981,8 @@ The Integral Force Feedback control strategy is very effective in damping the su
-
-

4.4. Save

+
+

4.4. Save

save('mat/Kiff.mat', 'Kiff');
@@ -897,18 +992,18 @@ The Integral Force Feedback control strategy is very effective in damping the su
 
-
-

5. HAC-LAC (IFF) architecture

+
+

5. HAC-LAC (IFF) architecture

- +

Author: Dehaeze Thomas

-

Created: 2021-11-30 mar. 11:26

+

Created: 2021-11-30 mar. 11:44

diff --git a/dcm-simscape.org b/dcm-simscape.org index 88720e2..57b6f9c 100644 --- a/dcm-simscape.org +++ b/dcm-simscape.org @@ -738,13 +738,11 @@ clear io; io_i = 1; %% Inputs % Control Input {3x1} [N] -io(io_i) = linio([mdl, '/u'], 1, 'openinput'); io_i = io_i + 1; -% % Stepper Displacement {3x1} [m] -% io(io_i) = linio([mdl, '/d'], 1, 'openinput'); io_i = io_i + 1; +io(io_i) = linio([mdl, '/control_system'], 1, 'openinput'); io_i = io_i + 1; %% Outputs % Strain Gauges {3x1} [m] -io(io_i) = linio([mdl, '/sg'], 1, 'openoutput'); io_i = io_i + 1; +io(io_i) = linio([mdl, '/DCM'], 2, 'openoutput'); io_i = io_i + 1; #+end_src #+begin_src matlab @@ -762,12 +760,12 @@ dcgain(G_sg) #+end_src #+RESULTS: -| -1.4113e-13 | 1.0339e-13 | 3.774e-14 | -| 1.0339e-13 | -1.4113e-13 | 3.774e-14 | -| 3.7792e-14 | 3.7792e-14 | -7.5585e-14 | +| 4.4443e-09 | 1.0339e-13 | 3.774e-14 | +| 1.0339e-13 | 4.4443e-09 | 3.774e-14 | +| 3.7792e-14 | 3.7792e-14 | 4.4444e-09 | #+begin_src matlab :exports none -%% Bode plot for the plant +%% Bode plot for the plant (strain gauge output) figure; tiledlayout(3, 1, 'TileSpacing', 'Compact', 'Padding', 'None'); @@ -788,7 +786,8 @@ end hold off; set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]); -legend('location', 'southwest', 'FontSize', 8, 'NumColumns', 2); +legend('location', 'southeast', 'FontSize', 8, 'NumColumns', 2); +ylim([1e-14, 1e-7]); ax2 = nexttile; hold on; @@ -800,12 +799,173 @@ set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin'); xlabel('Frequency [Hz]'); ylabel('Phase [deg]'); hold off; yticks(-360:90:360); -ylim([-180, 180]); +ylim([-180, 0]); linkaxes([ax1,ax2],'x'); xlim([freqs(1), freqs(end)]); #+end_src +#+begin_src matlab :tangle no :exports results :results file replace +exportFig('figs/strain_gauge_plant_bode_plot.pdf', 'width', 'wide', 'height', 'tall'); +#+end_src + +#+name: fig:strain_gauge_plant_bode_plot +#+caption: Bode Plot of the transfer functions from piezoelectric forces to strain gauges measuremed displacements +#+RESULTS: +[[file:figs/strain_gauge_plant_bode_plot.png]] + +#+begin_important +As the distance between the poles and zeros in Figure [[fig:iff_plant_bode_plot]] is very small, little damping can be actively added using the strain gauges. +This will be confirmed using a Root Locus plot. +#+end_important + +** Relative Active Damping +#+begin_src matlab +Krad_g1 = eye(3)*s/(s^2/(2*pi*500)^2 + 2*s/(2*pi*500) + 1); +#+end_src + +As can be seen in Figure [[fig:relative_damping_root_locus]], very little damping can be added using relative damping strategy using strain gauges. + +#+begin_src matlab :exports none +%% Root Locus for IFF +gains = logspace(3, 8, 200); + +figure; + +hold on; +plot(real(pole(G_sg)), imag(pole(G_sg)), 'x', 'color', colors(1,:), ... + 'DisplayName', '$g = 0$'); +plot(real(tzero(G_sg)), imag(tzero(G_sg)), 'o', 'color', colors(1,:), ... + 'HandleVisibility', 'off'); + +for g = gains + clpoles = pole(feedback(G_sg, g*Krad_g1, -1)); + plot(real(clpoles), imag(clpoles), '.', 'color', colors(1,:), ... + 'HandleVisibility', 'off'); +end + +% Optimal gain +g = 2e5; +clpoles = pole(feedback(G_sg, g*Krad_g1, -1)); +plot(real(clpoles), imag(clpoles), 'x', 'color', colors(2,:), ... + 'DisplayName', sprintf('$g=%.0e$', g)); +hold off; +xlim([-6, 0]); ylim([0, 2700]); +xlabel('Real Part'); ylabel('Imaginary Part'); +legend('location', 'northwest'); +#+end_src + +#+begin_src matlab :tangle no :exports results :results file replace +exportFig('figs/relative_damping_root_locus.pdf', 'width', 'wide', 'height', 'tall'); +#+end_src + +#+name: fig:relative_damping_root_locus +#+caption: Root Locus for the relative damping control +#+RESULTS: +[[file:figs/relative_damping_root_locus.png]] + +#+begin_src matlab +Krad = -g*Krad_g1; +#+end_src + +** Damped Plant +The controller is implemented on Simscape, and the damped plant is identified. + +#+begin_src matlab +%% Input/Output definition +clear io; io_i = 1; + +%% Inputs +% Control Input {3x1} [N] +io(io_i) = linio([mdl, '/control_system'], 1, 'input'); io_i = io_i + 1; + +%% Outputs +% Force Sensor {3x1} [m] +io(io_i) = linio([mdl, '/DCM'], 1, 'openoutput'); io_i = io_i + 1; +#+end_src + +#+begin_src matlab +%% DCM Kinematics +load('mat/dcm_kinematics.mat'); +#+end_src + +#+begin_src matlab +%% Identification of the Open Loop plant +controller.type = 0; % Open Loop +G_ol = J_a_111*inv(J_s_111)*linearize(mdl, io); +G_ol.InputName = {'u_ur', 'u_uh', 'u_d'}; +G_ol.OutputName = {'d_ur', 'd_uh', 'd_d'}; +#+end_src + +#+begin_src matlab +%% Identification of the damped plant with Relative Active Damping +controller.type = 2; % RAD +G_dp = J_a_111*inv(J_s_111)*linearize(mdl, io); +G_dp.InputName = {'u_ur', 'u_uh', 'u_d'}; +G_dp.OutputName = {'d_ur', 'd_uh', 'd_d'}; +#+end_src + +#+begin_src matlab :exports none +%% Comparison of the damped and undamped plant +figure; +tiledlayout(3, 1, 'TileSpacing', 'Compact', 'Padding', 'None'); + +ax1 = nexttile([2,1]); +hold on; +plot(freqs, abs(squeeze(freqresp(G_ol(1,1), freqs, 'Hz'))), ... + 'DisplayName', 'd - OL'); +plot(freqs, abs(squeeze(freqresp(G_ol(2,2), freqs, 'Hz'))), ... + 'DisplayName', 'uh - OL'); +plot(freqs, abs(squeeze(freqresp(G_ol(3,3), freqs, 'Hz'))), ... + 'DisplayName', 'ur - OL'); +set(gca,'ColorOrderIndex',1) +plot(freqs, abs(squeeze(freqresp(G_dp(1,1), freqs, 'Hz'))), '--', ... + 'DisplayName', 'd - IFF'); +plot(freqs, abs(squeeze(freqresp(G_dp(2,2), freqs, 'Hz'))), '--', ... + 'DisplayName', 'uh - IFF'); +plot(freqs, abs(squeeze(freqresp(G_dp(3,3), freqs, 'Hz'))), '--', ... + 'DisplayName', 'ur - IFF'); +for i = 1:2 + for j = i+1:3 + plot(freqs, abs(squeeze(freqresp(G_dp(i,j), freqs, 'Hz'))), 'color', [0, 0, 0, 0.2], ... + 'HandleVisibility', 'off'); + end +end +hold off; +set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); +ylabel('Amplitude [m/N]'); set(gca, 'XTickLabel',[]); +legend('location', 'southeast', 'FontSize', 8, 'NumColumns', 2); +ylim([1e-12, 1e-6]); + +ax2 = nexttile; +hold on; +plot(freqs, 180/pi*angle(squeeze(freqresp(G_ol(1,1), freqs, 'Hz')))); +plot(freqs, 180/pi*angle(squeeze(freqresp(G_ol(2,2), freqs, 'Hz')))); +plot(freqs, 180/pi*angle(squeeze(freqresp(G_ol(3,3), freqs, 'Hz')))); +set(gca,'ColorOrderIndex',1) +plot(freqs, 180/pi*angle(squeeze(freqresp(G_dp(1,1), freqs, 'Hz'))), '--'); +plot(freqs, 180/pi*angle(squeeze(freqresp(G_dp(2,2), freqs, 'Hz'))), '--'); +plot(freqs, 180/pi*angle(squeeze(freqresp(G_dp(3,3), freqs, 'Hz'))), '--'); +hold off; +set(gca, 'XScale', 'log'); set(gca, 'YScale', 'lin'); +xlabel('Frequency [Hz]'); ylabel('Phase [deg]'); +hold off; +yticks(-360:90:360); +ylim([-180, 0]); + +linkaxes([ax1,ax2],'x'); +xlim([freqs(1), freqs(end)]); +#+end_src + +#+begin_src matlab :tangle no :exports results :results file replace +exportFig('figs/comp_damp_undamped_plant_rad_bode_plot.pdf', 'width', 'wide', 'height', 'tall'); +#+end_src + +#+name: fig:comp_damp_undamped_plant_rad_bode_plot +#+caption: Bode plot of both the open-loop plant and the damped plant using relative active damping +#+RESULTS: +[[file:figs/comp_damp_undamped_plant_rad_bode_plot.png]] + * Active Damping Plant (Force Sensors) :PROPERTIES: :header-args:matlab+: :tangle matlab/dcm_active_damping_iff.m diff --git a/dcm-simscape.pdf b/dcm-simscape.pdf index 6732f54..595ee5c 100644 Binary files a/dcm-simscape.pdf and b/dcm-simscape.pdf differ diff --git a/figs/comp_damp_undamped_plant_rad_bode_plot.pdf b/figs/comp_damp_undamped_plant_rad_bode_plot.pdf new file mode 100644 index 0000000..80e4bbf Binary files /dev/null and b/figs/comp_damp_undamped_plant_rad_bode_plot.pdf differ diff --git a/figs/comp_damp_undamped_plant_rad_bode_plot.png b/figs/comp_damp_undamped_plant_rad_bode_plot.png new file mode 100644 index 0000000..15f7a7f Binary files /dev/null and b/figs/comp_damp_undamped_plant_rad_bode_plot.png differ diff --git a/figs/relative_damping_root_locus.pdf b/figs/relative_damping_root_locus.pdf new file mode 100644 index 0000000..84bfb04 Binary files /dev/null and b/figs/relative_damping_root_locus.pdf differ diff --git a/figs/relative_damping_root_locus.png b/figs/relative_damping_root_locus.png new file mode 100644 index 0000000..b40e8c0 Binary files /dev/null and b/figs/relative_damping_root_locus.png differ diff --git a/figs/strain_gauge_plant_bode_plot.pdf b/figs/strain_gauge_plant_bode_plot.pdf new file mode 100644 index 0000000..1169e6d --- /dev/null +++ b/figs/strain_gauge_plant_bode_plot.pdf @@ -0,0 +1,1386 @@ +%PDF-1.4 +% +1 0 obj +<< +/Producer (Apache FOP Version 2.4.0-SNAPSHOT: PDFDocumentGraphics2D) +/CreationDate (D:20211130113217+01'00') +>> +endobj +2 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +3 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +4 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +5 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +6 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +7 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +8 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +9 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +10 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +11 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +12 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +13 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +14 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +15 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +16 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +17 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +18 0 obj +<< +/Type /ExtGState +/CA 0.14901961 +>> +endobj +19 0 obj +<< +/Type /ExtGState +/CA 0.14901961 +>> +endobj +20 0 obj +<< +/Type /ExtGState +/CA 0.14901961 +>> +endobj +21 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +22 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +23 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +24 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +25 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +26 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +27 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +28 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +29 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +30 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +31 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +32 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +33 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +34 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +35 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +36 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +37 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +38 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +39 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +40 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +41 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +42 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +43 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +44 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +45 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +46 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +47 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +48 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +49 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +50 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +51 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +52 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +53 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +54 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +55 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +56 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +57 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +58 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +59 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +60 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +61 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +62 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +63 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +64 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +65 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +66 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +67 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +68 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +69 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +70 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +71 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +72 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +73 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +74 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +75 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +76 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +77 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +78 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +79 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +80 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +81 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +82 0 obj +<< +/Type /ExtGState +/CA 0.14901961 +>> +endobj +83 0 obj +<< +/Type /ExtGState +/CA 0.14901961 +>> +endobj +84 0 obj +<< +/Type /ExtGState +/CA 0.14901961 +>> +endobj +85 0 obj +<< +/Type /ExtGState +/CA 0.14901961 +>> +endobj +86 0 obj +<< +/Type /ExtGState +/CA 0.2 +>> +endobj +87 0 obj +<< +/Type /ExtGState +/CA 0.2 +>> +endobj +88 0 obj +<< +/Type /ExtGState +/CA 0.2 +>> +endobj +89 0 obj +<< +/Type /ExtGState +/CA 0.2 +>> +endobj +90 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +91 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +92 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +93 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +94 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +95 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +96 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +97 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +98 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +99 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +100 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +101 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +102 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +103 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +104 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +105 0 obj +<< +/Type /ExtGState +/CA 0.2509804 +>> +endobj +106 0 obj +<< +/Type /ExtGState +/CA 0.14901961 +>> +endobj +107 0 obj +<< +/Type /ExtGState +/CA 0.14901961 +>> +endobj +108 0 obj +<< +/Type /ExtGState +/CA 0.14901961 +>> +endobj +109 0 obj +<< +/Type /ExtGState +/CA 0.14901961 +>> +endobj +110 0 obj +<< +/Type /ExtGState +/CA 0.14901961 +>> +endobj +111 0 obj +<< +/Type /ExtGState +/CA 0.14901961 +>> +endobj +112 0 obj +<< /Length 113 0 R /Filter /FlateDecode >> +stream +xϮ4Ipݷ`oe˖wV2$h.->'NduUf}3/KR&iʜ1YGxl'm?3b}H7b){YlGG޷Zz?R_?տ"t×H L?Ę5s(?qZ}_q㦼=co1}˟6n|}Bq=KJ5miO_~>nϼsjc6>{Sۏ{Fm^[o1O_KCnHixK/ -šSp}Ja_|O}{pm8k|iiT/4l%c44Y*\O0bmh˟44gzKq?^O_{, !q }ӗ&K9>c [=O_{,q`^R(ϲXC/ ==YwXc|ii3-/E8bKMP'?}ii2X \k׎OdqopBoW}ӗ&{yn{ ?KCOшsjDŽ=iT/ =M[&=S9펡e1gI{bev˗eycerd!!?}ioj t*i8/d[A{ӟ44Yhw[Ȏ/dzm;&/ =Mjxn[1O_{,}Cc_BOܸC2NjOd!oϽr8F=K~Oc-c}n m|ii}IК?|io+̞唎/_q1|bzǦNߴsw/ MO/4n[o/ M+?[/#}˗== _4tŭU߿47#8/_: -=0@`#f9"?}ih9Ko \w%Q_r:Rkw.?~^G~ۗ ykZo1f Ce~^;c׷U +o/RWxT=_"5)}HEݨ;_%"wW)}dEVxG,>d9o?Nhyp}4X Z2Y?0T2?1je ~`\e2~bkdĀ +y]+S&'bz,Z2?0T2?1ൺe2~bkUd%S5d&Ā2]W&C'<~?#!{Q96Q> ~0pe?njŞ&{p?x!6߾撲1Gee7Ց>%dxlQG]+Ǝ>dLlQG]kÎ>d lQQG]>hk1'_z/OFy>)dk Qu'M\cJ>ZuI'M[c>ZuIGDkQx:Ձ>dkO,ˇ21G^w:񦂮1GE]w:[xo}2T45pxSeOƛʱxd}2޵k IG] >)dkFX}RfQZW5TxT}Rc +K[>gU[7i>*hkm1'Y7d>*d +kQ%G]J>(hk1'5W7Y>*hke1'U7S>*djQMS>GSv>dseR4EXF}2ڵjIA']*`TA=.|4؏$\FBUʪ#XAuGϥp>(PuTp©x#}|:SsX_/d=^r6?GnfIv Ж";/Ǩ=6޹ߌԨ52|oGm?5*snSxKUt3cnOw[(w۞ݨ돽W̺A՗nҿAqJBe[¾I +&Q~h}7m9Gː=:x{i;{z?//O\}[^=9^g)Dp ,⁺%/E" +Zr-C/d֖^bhWMĎJoQaŒB8Dz7?fK빹ՍigM&CY5QfvO-=vvm-ZDXo_9~,LRL`=cZ"f6{0b̚K T~nugQLxHb$Y1-:ߵDZjRkߠCUJ:<\[˾$"āܛ%RԱ Kݖn)]csڍm,pS:BZQǀzP#XF-"yYBJ8ߏM4;Li`!*6[11K1Aq Z82MC&ql*U7مne4\} Xƴo<7)7:1T_6;a@Q(>˸|n+qrw4>Dp +u3^1aؙ[} dH`ج Ccͻ:ԍ+18k;Dq€zxa.3) ރv:;rp"`6Z>D9Sgjc%8Uе}&7]ʻ(6Kbvc" v5]kaEۻhc8&0ꢶa4qp',cv3!} uV~)Y8Ԏw:O=\Wێ#V !÷g.V0D3'w +)X_}oL/cmHW[C42 C010|,qI2%ױu![L@jCž*0 ^,u÷ ".eU 0x&%-8_5p07CCKHy-v +zyVJњ#-Aqe1z:Wv +BPx."|DͷWwsH\[Ĺfem۱2y.KV46 N(>^/ol&Ƀ>DXzp}10rr|"<X$á0 A.qy7o?;NBNx@dž:DK!4X8]eg1+>^pm{tQKx ǀqlc,eQ$8!~anqXyMGށD+Dpb.ncC-'_XJ0C9(M+v |,n_ ysJ"@i"z!e/NYG p1d"xTuEx)cSD V ]yўλG :MRA@= lfNEa;3} +KDŽ!̟QcoW<$r.%-.P@U +ԴXy R¿2^vq0mX=88]1M8]2n!pbv_:]>>0<0Dgt0^WNJ:.  +֕Z6fv"t]Zy4!K(cӲ5 ,eOѕ#&N3#[xO =ˆfm&z]8_ey/ M #8<뮇kS™"0 yw} +%*NҥOLᓛH# .b ,1VʥSPcr]*70oeC7%/I v^ ]mTcB,"*(ȱyI`f K d7]xg 栝8q `mCo +A¹`k6?NT)pjႝFxՇCBg4VZ"z## $SROp| /(>˪'w?vl':O1W xU,h(5BZ)wqafX +"ؼ%r}֣؛I_꒍!71ܣ^YM$M +#mMM&x]jqV0.ȓ R_0d7'.P#p_ih&¢x1?( 5b,yǶ.h^}>Ч{bWUm3EZ"KM#O#pE\62piVE0&,|b4CI^ +uWW…Fn!!}Z|w")#zE~5|uV-=Kc\dNOAMzz&v `VL=-Twˆ*V=ѠpH3 hLLJa+åx/nL?i)I]{>2`or|QZx hCԙ7\$*\X̋Ci;P\wpn=!\&We"PύJ#m v^%Uۦr_]CC -d_q&<2^J]/̸}/1a1 ibQД v7l(C9$BV +$z_]nf +>8ؿyaMĊhA!|$A̾RY:vc*ye"xtoGZ8{[-+O}ww!]Bԇ ЏQ{z#BO0>8r2 IF>k"g*hW0%Jr1]<PrfƂL|"핉Bw!,x`fGͦ1TJmL4\}da4E {#l'-{]ԙS|ì-J߅퇯q'9]V#'RHWy a=6|"^KtYj^GLqL\> @$3.& W20c1};q'ܦɃsR'suN .;Y^\-{@:ͮ.p)+|&!xV>lhGEJił~r$0njd{36׋  t%WH" fgUbNo.rA~+` QM,Q$@)P־uQs>f-rG= ڋf>dڇ 0 +h?a bDѼOH{Wc`Y;b#XG>jU X8q d^Y8b7Y۷0 &@W1r&`2VN 0Hs&Y{ZI"[3b0 "wxd,A D+Y.iל5uAyn o5gY +144d#U4&~႙Js7I}Vm6muRdV 6l:S(*eGh?ܣK:Vgt`#`%ea̕7 Ra?X>\>Rq2g +_/-?\T-u[8q&i0^E|nڴ!oXZ45{eF2mݫ2{hXp\=2j +#Q*í«ڲ0|GEL[HU KP/UTȸtVL]سOLQ4x +R L~d->|dɆWwsyt⿲_ +V~`5pLA;*T!j8t +Wgt03ne,yf``0G"&u8Cz%jSV-9{@:]o-]tR4fҜk!E AOh`4aw/&gdHeʎ;50]}vyg)':]$=A{8t'N3]O执E* Ԛ'E? +.O +2I4??Ib]I~YܓJ6;;T[#yjL1ݕEʻd L5闤z#,t,%p?ey b˘\]m˒{*5#yybwv1& ~W&˼0Yk&"Ɠ5 ,(pDԏZ:KS3/`4|/5 dw8X8񨙢$z DMWUSt X1ɢRVODv + --k}9MgcK2.y]_)$pvŪ=R +NpA )E艛(o^BhXrS͂,tnWL3*'^EDS- +0 +˫t%(;(W}c&txug8+[20rVyyҍqIb3MGG[E=1G9bx`zآBUF2 =LRK-`E` +>B<'TtK&7D8 h'd3gCGbR-%]c +``nZs೉2*Qx*_)S*[GpR)wEȅY8@1<}!lY̑0Q +*]Kp[Ep_Q.XfA=]͆bI+MISvM +yH;K9uCӂ,mYmri+m*ˇ|ecWaS}ƓFW`xii+Q)7} +QT(MC/13l=`HAKV&xe&xaּL@ @"ºEmbN=܄4ͦ iTF'%<.;K1e*ͻ=% i'T`XXS8v8OPllꢮ{%{ Ɉ-k|Ds33D?_{O1_Zm~`g: PdIǔd֚, [b1ؚe +^l@΍\T q^v.(J0y=&3-Тu܀Tz`twYr#5Zʟ] jv.ݟ=/DLp3W\6f,"aڕYVudॳ5$Co4[ +[P<;:al0PECc[t1 ",ŏQ6LG^EVEήY6EdsO>zޥdS 7+ ke NAy 2]t+ӔAJ6Kx8bf킼ܗ]; sƵRSSl޶)ﭭ#k\LcV + 'SwPkP6[ ՠD [Ϫ +A A6v˜|=sq 7Jdxtv\A0ȥyw*5*0tfwFJ;)d2U}.o:AX`?5 LrgmFpPԼ{wLA|iʹClαC/hШ鰟n43!Q5]LP{i]s^?z,W;*/+Ӏ͘LBa@ʔ6-l3$wEY00YdiCc,,=/d`jUQ2v0Ö"UR%}s9@б,LekTb=4)bOThDott:+>PpX  `%L/.lG*K4(L.\K&*R7xG&*(0E4=͟KoDj쌞G:b  ͵;")"޸XXV`;v{L[ k-4>s,EXt>(#, jgF(ґtx(cwloe"W`lޑ̱dtp,qc|iT۶M1+`6V)bKje0kJqvF,YނWZA %}NEp:C8*tn֛H-ӓ]3VggGޤ1iw{vq;3M-ɲ@YSXZ`va ++zOUWm*vl%%f lE˽ UaP7Z4yv6{Kv;<6D?=^2rzX4法(K%EI2lv<* Nkt kgGҬ2pSli9)-ZXPiU^W98Qi #`aگ0pZZDS\-^UZUP,el9&mKFjj "*Lj{bAť5Œ3R2Q0#`=⒑*VhAʵKz,mBxbvE0LQvd^"ܘIoYF=A :a讇7H)b!?-{b?w!Rx֧6g7XC({ƴU9A~/*]Y򺻌Le[U@Uv!jX&ٗbI +l̞خb +vKz(vM(6Dl5d&* za4,#0ȨR]6.'0S].̲PԞ*~H:# +妙 pw- ؝=pt^<'#]1a"X @f P.Tֱ~h bsLe&-3س;xf6@f`׃ƂLX Onn"ݢ^S78lxUPgD4QeJ]U} )n3M=0㺳ԑjwf!;Kv \چ[<, dgn%}][u6KO̲ųF`69XC#]aXT yL5HJ8z̥H KJ&b$O%MUb$]flzfAoXשV)V*)|[ZDM 'ޚ*K,I+;}Is5\,`|XH=Es'QRe9/As !d:-k$A;G]("d’4,1l)R5ILRg<6zz$K#aB)&ҵh7o!itxc_@]UȖQm,B΄5*կbc%^b ==CMN Rēp[0tF<ǯFXQ!LԞ)HEj8qJMǨ~uKͬ\1(.tQ٬Dl +7{ \TFŎ"p 6kMuJ_MS_.»'9JUQ"jSpӮOYJV` 8WZ`H?.o[%iMwꭜ$^_̬ -T ~UI,(5xI>`K. \w&ł~-9'gs%);iw&5ݪb"$:X|CCWc4x8%R#n#%3b}}4EQuoa71|;.kiTd1ȀynFiS ӈmQrB&E)_A|ATyӈ +фVQuFR_FQ;QSid ^wL[;QUm(9oiv}4j@ (iu1;Qj#2ZTQx4]uQܚ?4 4E7L]nF̓4F2i#VQ-L w#UeF}W;hTˇD HpC4nXwH윮Qq Ө9Ө({jTյjTEb. (+j&l4jԼ4.b4^)s4jNraM8Qr4RK-Ө9iTYF-οAbD+Hٷ+V07D#/Y#%7J47D#Âv kD ҈=4F6т4 + ӨB0ﬕi,H#EF:c1CVznFa)7L_1F^7L#҅L2Tp4Hq7C (9AqKs 9քEW΍"p +9,9bZ GȤWʑuG9bPWr1!Ws;e1'W9GrZp9Rsrр#̓V9Bm sD]=b +nM# gQ`ô`ʷ20GD e]1GȸAiQ 7RW\4QFrIvZ)G0;MV6B9$g-#wWƑ%qغAYG*͐r:QO*o_!GT2 9bs3gu9j֔EWQ݂R o0Gisv7gV7ePDy#̦VQؒ.'n(G_`x4chsۦ}ax9LQqH؊9b3j5_1GX:XFsE QhsS#WsL1G<43 X0Gl(ł9b{-͘#xr{ H/ +]bzvՊ9ڃ*WўcfQ!9ڳ;#&_pp^w9ڙgs6 ,#2X9Gۦp\4qdyn8G@L#v:;r:{Qd} :JZ+K4:JPtt7#VQJ4: +:b~:nT͠#u[AGY(GFPy&(G9peҦv#3$WM&D9VJ9:N򬔣T=Wo֞D刍66/fo/4Q)E} +9rY G 9"(Gy}ȑu92 +9b$C37lrAF衙rĶ_Zg3wri1n'bB9rT_|#|*j,#M?CEraK H%i&)G0VdjrnQ 䈕B-#ւ}@hȬ[ GLǘ Gxr Vc=N| GH"J.#F=~+(>43X(qdM#Ț;6>8RD(mGQxfSbrɕq͔^ in[.gQ8"6[ڠޗ33hX]Gu6f\{qAG`7M#˴dB1is &4:3&"8ͯqī 6&rхq] gQa&sfKU@x. r$y+}Rtt9b W.#?1;QNSRhimg GB +?]Gj'3]GNO\GG,t+!]y 'ҞGXm*GI4_G$EgQ0ݘEG컦B8bd+* :3Xqz6D,#Ȋ]GQe4Q`' &QJ9ji+YD9b`-M#j̐#(]faB!92BC&QZ(GM쎅r 5D9rT(G )G1Cxr'Θ7,xZ!GL#FIΐ#w/x sʑg9L_0G >8b~sN:Q2E9巎sTw1GT(s%ł9wյ`os8N@1G^Uk+Bzsߗۂ9 +E:hqwVM#!Q*o0G*~ӡW xW (Bo0Gћ䭘D"~֌9bZp]tќEZ0Gprbv3ftyw (Ls9b9bퟅst{jK9GdsdEMJjk-#d:b:!)RX@G *a^@Gg +:۵hfQb}υsG˅sT&+9jhjp"YWi;9GuTkV5Z ,#*Av33n"M#v`u9&#v!Ws\rz3]te&tu2nUJX#3Ⱥ14Xt̠#]AGP#5 7 :,4AG՚hoAGp8Jf{>hh%XttI4tA ,:WvzP9+59jΜ#^9"Eu?WK 稐)9ʎDx-MY ȃ'sDUs2XZ\fQ9C܅syy (@dsX8GPD&X8GSFh8GUAĢsDX@܅sěH̜(^+[VfpS1eϘs3Ġ5a:#B̘{sx}-Â9n 刷߻P"ZrDC\r_9xhaqq%:oW; 4CG>^7#_!G"R +9b򙳛foMqs_G}kaKUte1}gu_7Es"_V +8^47b@ol+D݈"-#)b0M##C#%U"8Ɋ82qԭ-H7 GqSpbeUht 9k-W@*9[ѰVȑ 䨇|rk=B9bqD ';+H +r[h9b.fB9Ro[ʑeb=n)G>+娳mrH}j@Rd.?(G)rD5"JL9 D9bg"}h1Clr1GUs4@7#k 5`Œ1GQu&#Zn6+ڦAfϬ4`F( ?q9-] H[qq99A72Hy+H]*n9G8'/#MS 爧>+稻J[AGpo@G)z7':bCQ`q:"q:ʮa  눍nYG }Ȼݰvg#;QyFa #[Z+G +;r荣X`Gbaq ͣXXG':z*UިvFU,h) 荪XGoTłXGdtzt9VAXGcxzt9VṣXGcE1Y=y:G@" +#hf]V>DWQbo=<:+ ẉܱ2cEyt;VQ*ֵyd\G*}!R^R+(KzI[Gw#-ȣ"Pyz,ȣ7cA XGcFKM#dFaOȣhY U9d9?dETς<:!+ȣJM4#X]GunG峋#f{̣}Oyt+󈭶L>1h4zf-У*%o zvzyTGoF1Cť y(yAU. yDyTY7# y ,5,GQ^~&UV#fG 'xr5+DEGˢ3e#Gw.Me bU9*ed)wdo1:kUܪwC2qGl 3툾vL;T3;zEfK%3qG'Ȍ;:!Ef )2NHwų;bΥ;btqЄ;*wlw~% 'fQ"،;/f 3֮x30\4wSU ylh1c_;bC=[xGj|*;*ʕvхw4zV4-Lgfѯx^Ur3W{0f_9J }Ȋ3iU8щp!e+.%+1g_x4sV]*|&ee.ģ3[xynjȣ|tXG[GNDGbYQ xnG/B#(Tg%-#xMģN0 BZS RsWc[wyD6OWwl/"xwpWљC2! ynt"#cb&e6ZG~!2@xڴVQf/GW3қ3툖L;-DWc +; &33L;L;¾DWvgQa4ZI3IrwtB̸#"JvЕvNMב3b˃tVx;b?֠҉wT ]yGLUj1+n'QqMyG7E\ljwT`EyGJEf_^ ceL#[(wtt-#Ƅ;Vz J;EWQfݦMyc_ 08CW3u{WEߌ;6EWctӕvIRvqM0gQ^ m.ЅvĎgQf[n{L#(&Nt)uHpQmfQmEWap5g+"`GLۈ2gwqXԕu'*Еudޛb!":b]XGa3 JYG$ZXG.ӤgoctlѕuُOvy63(R ;bbΰ#>Îj0h%$_2kRGؙud#]YGte5q:bs?v%y֑pqfYc&:bC?s3T uuxROQGjÝPG: +Vs^} +;ژ)":"|Y3hWPG\tfI*:Q7x366QW )ȯ.#XQtb$%JbYG1ݤGά#(Iy(bn68sG:gm 먩euaQiWԅud 5M[WXG§lhgyF'%~'Ψfec2:jv%-udhgԑ*u3*;Cz"mɜQGaU?yΨ#6SyA 2EزQ.#u9h겮QL Ȁ,US'ԑY` QG`❮/#grt֙u%ut˔xAQT7]QGqu! uDVK sFQd:bkWM:b\va1e:7/#kFle5#ݾ,y[֑5$xe5C2?G.#Mqtf1s 0̅uhywɛud*'ja8q:FfQϬ#t%~a}ެ{G3눨vz&~ԙuD^.#&p)N#Vw[>XLgnwI1 먊//;,K'M:bO!ەtT힋"td n_IGb"pȅt;L:bcRgΤ#&&G]/#*J_oޤ#^`}!E6's!d8ؑ5񺒎L <\HGπs7ΨyqvGkP.#6lVYec`Gg n/#$ qGlÕY 'vlGB;b +UwrHpz7Q.#6x# (6չ^Gl²Ѣ uQ*/N#gg-MG2X):q:>&=,nL[Gvq]y-#k숓G{td)z"95{8qxUQ݅{IbqjH{d@.v |deY.Ξy$]GlوqD |#uYkԜxʖTcGDذ$ +pYj; Q>f֘'>b"Dc)g_GLSɚUrt!v߃L>2ZNc>blVG3[LKVxn8@94c3WEX3叻_u=.#DGdb6qj3&lǸ`QWT"=bH]G +@&K˜䘢3(EєrE˾]Gvp+UxU {Xg.:ch)'M#s#ֿd]#!=bhz`%rphT1x@{ܜC2a+F?+MxcGkBj5m]GVYu]G5'e]G(UzdE~wGIRL +=:УzIDZ"ЕyXY}Wk"ȣ`|Qzy,!5!e +BGqMt"YӒc /#πBLI]G쥻NQ7 梃xљg"9yxԭdFN;4q,GvƌxdxdtިlW9<[iCG|;A-}N#6y + Wq@;|; +VgWsδ#0v.bЙvĶ4sI57hVgAur%g{vԢ+( +YG7ryfp23X?W(0X3יuľf^YGLhL:bQ4!9:- ^XG3_WiQrE1N +#REp:ؗud);c.zzGZ:Jv^Ɗ +tf:b-F! gQ3hv1L{aY5,[- :*]kbj ^Dz3 w:bp"vd9aGѮX+:~W1U"M7hhxfMteN190fbzlA:*lί|uM%3~RH]٘XGL:btuM60ѕuĞ3(U܉uĔ:b@Pu +3]QG,}*j56 :␃2hF̬#jzl +; + %t*(:b?餆3ꈀ].3ꈹU3 Ϩ#ocyFQGlձ:b7QG} QG +K_L#"b*if;,}*Bф:b?ų#7gQQ L:bk2XM#Ve̠#Eg Ev3(X;;27eͤaXG ݱp_YGWVT;Î;(4cN +;2Lg|Z`G;,Gv'F vW{vFJWƔ)`G itWgmV"3]mf+p+ovsᏕv{"hGo#D;!XiG{lKN0Ҏhނaۛj~,#l%(μ# 35yGl_TXΉ %;ˡ+Mrɯ#Mت Ȝ(ڢLWޑtcV;wC DۉwdqQ=xDVcY0cQ6uQټ=yc#keBV +<:u&!*xG)B. 2.Mz3oBd͸MopG"ͼ#v*N.xG; (~ݚ&cJ̸#^|]CM};Ecgf\pGq!wDgvф;^ xiGBaAuD; +IunhGAPo~3hctK;ª`JvvA&q{YVD;pG;y+0ӎv'T*ӿ0=qIJxV 2`fY'&e%Z EN#xd2fQ/#۳-XV ([d6tDl$Gl` +$VG)"%ș}Dّ2eOL?bS6-uQT| q N gEcB Qf7g8?3 CIB(1c eNI=Xdm&w!Q?;$DBbs)[t DB`Hlmͣ~!Qaa|N<$vvB@lo 9(cbhDbG F '&E; ɺM0748DEAz^H7_L\l$(8c*]H:@/d$kT،O:F z6[Up" GbWa:el c#ER}N|$X`նHb>DY0=gq:1]1q4A(c Fi\(IlhLDŽIbK J{D걮$v]*[ΰlzD%q + tX[p=o,Klw+MfH6ԔݞL]JOpVY9Dzgv'{8z;ݦ#0P̶ F!o:f |)Kc0TQ:֞coA &Zp"9{xJHk@1[*GIсcSnx{//D*S&EkСB 8RJU-X' a5{ӮIVMHP>fV-+x"ˇ`>rf+/;4Ȑyp>h׷ls}pc%' fOD`atxʈG`|py8>c%CfoSw~:]Vy!ԣ}TKNA+p _>hɲ'zIz&y\?hd8nmiVFWM3>򳩕lY/A+?eQt:nUtG6U~TνG/Nr?gmF@h{I~"mfUkn}"-Qi@x'meɊ?W:)(5V +IVl\c ӣP魱gaZ|'€r" v<F}6~@Y`Fo$oztRYX 3/~֎]ms*D2>@B|V?%nĄBH ;; l|U BhJh=E ]9եBBsaD hP+%d\ 準=KU%/yaBH;%^"0!z,f@DPfj)ӄPv,8!43x j}Bۭ@2rƭ&MReY1ʪ "0P!T ԟHSq";`9iWfc `!p"BPС,DOBBx7D A5V,D +BhelH-y $4it!`ɋ %!B_d˵:E 5s'pEHj +!1<ێd !cȀ3g[5N/zTK:АsgA Fڟ5du5~nXCHC#:0 k|B+#E'҆ "t.K,߻75ğd/; qG13m$B0 +@Yz!C\-E+;Z7XIBs;:h +OEė;V:70PNnx"z >=dic55ھ(fZGB#.M&=ФvVp,=x(6ݴA&0pzrh !⭾k8D +" +[&āCe/'a<\דYM EFqÁEheH==-mŒOYxF@-B#Lr[Ċr k\׎'VAv:P.br{z]Fq-zG/Ba<; "J%Lw9t~&`dk9' +p:Ll;_@1BҰb4`EEr$#\Z]B#(Q'X~Be&fd ] +chF,s8#$o}xFhMFhf~#Xg؂'0 5B*FEiՈqxJmx"2p,Pb[Q׈EY`#]~v{} +ڈHyUIOl#DJoVnD~3oF冽O!ei,cUj#DXXቄ#gEeYN֎y"㈤y9Rʍ9Bx 8G$a̐Y-=9>udI7l=MUi)6ӎHݻ#* zޑe #46 DNNK=BbOkefyӼF([ +f =([uay"-%AXzIrqNֱж 1Gh-0{"/=I1I9]Gh:&) _˹I !z")Q $KiW)HhcVj.ݿDzkoCt<B}:{BZ$}= 2dT|hHh$|G1JwxH,%YDBD$Vߕk. $˃ڢ 5!<Ğir\. +E;.RZhs|#=SnPOFB#N@#%Zh ĆQk*!@Y!lj=!i0g..i[~4VoTI<6JYBiZZBC뼢Do\\rk*7@hKhDdq4:&V3:H@.p:ɵ\BKՊKV·μ.j|/S^J ֙$%[yqa/A\{"/Qez mWF{ -VqKTD^TM7{= I$!!NzJ1 *ߗD筺7c0ݶhc>@PkQ(0Yޮ4 +RtBaBæv8IaLAB<ĴZ=iu;dHLRi Ad帪˙`LZ>hL&'Ҧ`ZchI;;J2QsFkȄS{}uH&`D2*eBt{*jW!&.S73z5V7FUQNNPl'n p"Cp &6maX?1xm"V,((G=@ɊAi & \Mv&Od InÛeY1:z]Br&:N7sVN=|1td+v@85zS*ENRk6տ N5/zS&]3d(cBW8at@G{.5SbÓ4::iKё  ' jfHr“9k/ >bLr.^HN tEדp-w`SINlnHrHyLr""m&-yIN|{fr1U!0dGhNRK)) xN%5F'J8OeI>'LIpq=Tb@OV TɆDQ<;p$o' +ƮHF{J/e:;;ܓofhZG|J$6I|Bw +;#\v:,TOxƓ"@}BiTM>a;t>9\dv%%E= G=X)O,<>џLc.I?v-Ub }QV+ ګt6sʬ*=tj8gR5j|4=v +oC':^R9'G;ir T69}gbFV=5~UTYaIQ(U+xt*$ꠗCga Se58s@UٔxY@2Gŀ .TǪꩦVEr &M2u*+Zk yUhlA UU4^ϯ#VM5P*** ZFۄ7!jlkKgV +m*nsDfy6Kݓ(nkE2{`WzUUo)+ +r<2>*T$*&VySy@B;pɒ_@XYgy}6Eae%jٴU VhH2utcFfc*Y;;dFy>e0ݶgECyeRyY淖@+[=ъ:fJmi@ZYmtڕL++ʭ[tL+$̏uP+ T+,&`\8a:%ej`BÄ?@}e~M@[Y}Yx^"V}VH覝@BJᒛaG 2O2蟎$W۬%WwSPubQqƗ; + KnrEY;@rv*RgrV:kwN]NR^6]wî.g]_"#+fbBkvZ8'è̚isjTGBc)wWǖljڪ6nj|ޣ=j:{(p@Zy"J#SO2ܬnLV}en»T.V_Yg}TǯB;*+ˇcug5V ,4vZk76<hX֜Xr=kg`fz +5X^^U1`hܖZvo $,kUG}'nS p,,|?(Gfda'zBLahFD-eW ,,I[i强i ̞˭.Blj0,J) aar[l3ðXzxak5`XY`Xh3 0,3.,A "NVB;8'ڦBñDzY_8WԳ̆ Zy2l\+E ,,( ,l]n3/\Ȳ&$W-sXX:<#2mvaX>.= ;|룃a!]=`X4 ˜ɉ*~ +0l}2#j8Wݼe0l[#’> ˌ!{Z@aSo$ jUDvcODa!)- iw@2[EٟF)J+[l3jh-z:ΟVЁe#a!W7Z=<ѷT; aZ ,2Qjރu;yʉ}6Q ,Y?e8Xhs/ w3 2,$Vqt;Z.k`e5S8XY,uj*]̞]ZҟZ͞F:YquTcY|]g=ѡ`ʆ-{C˜H&ݚ{ z֜VрyBӀ2W(XHnm۷:XR~ +dȨq +?ٖobp35zj{n uUPsEce3sI[^DbOgJQ|p7іl⺘Vn9k;=nI_^q3b=>k/@CfI$:)tm&paJ6o~E,IY0!ɱQc! ʂ#4wBA|Wm]y8|,C*iyeHƮ= /$LX+(Ǘ O:+a&:`xXT,Z\kx eK)^XzK~=̜Ew(y"k IJlڈ7#%*OozbY,CTZE!m 2΀9 7 YvѶ̞,3efޅ@`GOVzfyƖ󱢠'2vnv1˲ҾT 2_A2k/ehis"݀:Yu2[aXXf䃍zbVP+//u^\Mď'xn2ͮ#= MglS ʏv'ʌpqU"Ye#UYemJean' pkkߴWSU!NʌOQF+3Y22WfpLvf4v>ʲa쫷 kR`{" Y6,UZCZA@+À"H+3Vm-G 2zQ7̈%0qnte7zX!+3 _U +Y1{Qe4`&VFoÎ* +2a.ϯVf]5%ش@+1Q qQzZ\1ZL7>@+qimVƦQ"l7&Xγh# +| ݪrR 2V 2kH+1_&3hFXnpq|Q޹bvͰ:62BD+ \,vrj+":GZO* ~"}y/)Zn+1D2ieu!yO+#QVEtY;0䭞Uƞf9 qzV ͫ^VyʏdYe` ;*2}W OOUFEݨUEzVfԱ]ZUi=UFZDTPe./# Hi=$&._@\qy2<_ow{TfVe>PeTWȱUf^' 2rx{2j:4p]eoZO*mhTW8 ܍zTQJz1"Ճʬ0<{>P՞r-S6vF9t{/ʠuu=:mF(,aTf(m<k9e_(ei8#PQbJ/.PʈXR)S~b<mʈϙRFT"Y5DH +oo2 +BE%yJc +0ez;xS)ŖY4)3GS-XNDL&hXe8,[àΚcʨIښ4ǔekti<Sf9e$tSCE݆USFђ*5ʲ̞,ʬe2ʰ(Pс`= r=IeV5 +> K[*֓@fIH*˹7P90$ɵTr9M2x"L,Sf8S]O䔱*ͭ"H*Op+`^*c4_ja:P%(WPe2.3L^P|-*ʌ4R$NLQ_DPFGPY9/ʌ_1 Uj`2Zy>V+on)^RJJP-:^O*ov2nyQxՆAe4@^gI`>TF6 WR 4lҜ#lMIewt@*QRYAL$aSWFnSIfa?c}P_=r=z.(o-S-*Mv|`eїb=jf*zX>CYpu +M3oaeS`e+WVs)03l5WK[ Iy70$)O䶢3ʬ<êʒ+VFIY+'kb,c1meё?VӉVFV`eɐpok/ (d,ae\f 2+I?NaVhޚyVY2|3ʬN)=,Y; djaelr'HeLaenY 2>mjYTdieEk/,,ߛGZA)xZpbZO+:6XY23ʒV_PFXY2s%VF2Qu2z}0<V2IyX/p_+:ήgaHpH+#/\V`bk/ 0_yzZ BʞVWpef~_V~eJ"DZb*G+>gSq30 +-`elTae"NzXbk/H-6 \k2sȍֳl}yGֳʖd}s50׿D<l=hު+ +:ΩhV$ջ8f= oHb|FV^#ѱ Uj`b+L%u2K(bP:T@ (;R6J+h 2K5Tٓʬ,#=TFr2ۢ@*C+?$ 2^ Ie_YS[2|88D_1t:PxuӁʌR'ʌ$X ȥ֑ʬSCTDGRjeeN YRmOHe۹O$Ynb |TF^vzR{%u2R'Ԯѡ#!mQ@*~ o{"4 @*C +;RqYv4F*IetГjDRqYNIeh\ 'ʬYfK!,"d_O*C܋r֯7C YnIõJ*C*ۓXTZ" Gru2RW^O*S$RJ*C*qd5 22心`gޓEJґʬjڣ'%)Z#S :RF.TfЖ2lN`Iej7#'9'%H ؓʌ{,99# % m:̰-/1$H 3#Q<=z$rf TFukg uYPZO*; `ڦӚz<%%uTF,IE8Ie;yR%r69W'|K*3UIe8Ҳj*c&ğUvUc#jKݵ* +LjPeN <UvR}Vπ*.-n~Qe'!D3NvfQ)ƥ9vozV)MV&bzVubֳ˛V64Gj 2wf{X2Tae +ΊL^Z!ae+Vf*;UӿGQE UvIMπ*c(y}AVc3jPe+[*;Էh[π*fj_ͧ≨2Bi&Uv`쑒FTcy.U{Qe>a)&R a@"T-*yPLh$5#ʀu4Ȧ2R|)=lgݰ_?'1Qw4K* kw:f3ʘw2jVS<7*>z" Tj&2Y3( z jWq3zTU>rR:GS3v˵ 2uMi@*0-u2ʲ;&}@ɵT2 /2ĝ>lRnyRY>?hY+)$ʸ&gXV>mTFQ0OGPY6ڥAeg8cel**cܼ͠2^ ;.^PYƘ8elS亞S=9eؙ[S  SVY)cIgsʨN(QFN| ""-j z=TF;]O*cVZ#+DR@e= F 2^H*,g OeERmF.Z<FyV%zR;@g^PY2EE*czN ԧ9e;D +2jXSl9 EDSf>K2)I,`/ܳWv2z>6 qh#W|N]^ N/^~{Nݵ$e}]}z,T r*U^Z9~[nk}YցވӃʌ°TB K*3D36@#Ác= v_K^NY-)cCv# +)ղ9eg`vY)3vs)#V|0eGSo~Z$ensYO)c'pOgW'!74Rʈ.3POVFJX4H)cAБRF{j(ew CJ +0(e8{ elX@d=` J epuf!eq[ )Cʌ}Xb&"̚ 4DHB|QFq3etRBd|d2QFQ3(#(a^< c1^=3$5yEF)8o2>j4eny&FH ge݅.0̎@!:HZMH) 4alym9eɌx.zP 2d9FPl.n^PVDP_@e!e}Tf^*,ۮHe=> zRuReԃ,jd*3W)cӭ߫*SB]L9dw Sbڋ)C{1eAb - 2`EblOVݹ)3F= η]"Sj%bʸb!]9e\i-u2nϭvzNn붨%x Plb&^P_كإYoZ*Eț%?*J 2@<>7}gO*cWj1w$+ +ITf *WpTssX*#,cz@e ϚK@@*3OV[؆<56փjLg6Bٓl_PJ^R֑ʰaRD@expX*;n3VAeo) 0l?*;~e[DP76P>״*@e,NIY_jLAe4+_4'\c@ 1A0#( q,I)qIeDĞFRRkUfjzXn\V' Uc +5э56s"`\{Qes;;GYoe@*2fRRk/lj2Њ23HehXL{RpczRm[ 2.yy<2jf!zRШ0{R \He}1u2J8ddxTf5=̒w]hXefȻw6X9bwVf%Yvr265JzX_dgmY7y+,DZm N߲2|짯l5$iNhe;5?'ʌQfied CR@+#Wmvv2RpDZr3 )zZ)R8JDZYX)x"|{hVsE["PO+[Z&o'(P[K+xr{ VFr$<ʨl30{VvZC\rG +2\JhLieDQk˰AWi݁u2ʘA[(WaLP]VA4KChJ X{F\v?# r kpeٚ0x/_QK:ZJ[@+SnQ+8igMJL2J ːyh2kd}.(*g䕱q@{ +,p,c_s2Vbe `lLeRc>`YɑKl8 ^ш,cR-2ʧN&#&fCfyl" 32ٱMnZdBgfFkY.Y=3 ,#̭z:e51 +>eFaD1˸ 1-0(hwfc+ ﯗeFRl2B]sψ,]?*~g@% ψ,(*eI=22XD5)NXFUb >#eEbYhCeP!H,1 O6k{2`dH +2<1˘W#93()Yf?7 0_eOYF +b6s2(=Y>n*^1˘7<#M.{2 2I^Bs^ 2 2[p>@<W5< v{5Q(gQ]N4w)XG`;iTdh>#0+H,ׂړe'V X,\Ja 2 1e#l7xH,Ô;}D,cfo 2ؖ?}l$QcyQ@,#.leb2N: 2J7=r_m>2&b2bU,*GbOke|^ezJ Ytwe2+1j]X#T[F$y.y[I$YYB?#ޔLq.eXAD,ct*Q b xiX2F,BbjqEEbjƷ +b[<hb%@,#/xmJ _a 8g@k̗,3p%23 +X$"8b%&ؔ&qe>ˬ)JˌXf-VٗXFc#c22oO"E^ei|f C sa7^eTȟ2݂i4+X&ga)`Y6{K!vQH}vo3 ^=`Poe,\+,5Us,3 =XUE}F`%'dӺ_ mٝ#'ZW=XFzlh,̽G`e9Ý`=;ǦvWF@;T8X쇥w'^&ċ|&^)@WfM[vE`'Yp"e1r Xy۔eTWFd+-(ڵ6eVrY(laxXfXmeh⓶֮j*P Xv07`Y O{жF`Y&&Q,oW#̺S0ˮf>nX`֕E`Z|N2d7L2`bu[̼{I^Y_eeZz*ʟ/=e9+c,el[L 'XGL߁e,4~̲r?߀eԐ]:WF L.]`xe+FԕxeJo+nƽF^aVHF^&0g9~&^¹U+^+^WV{ +% c F`Y2wMz Je>/IJw?߈eoD,[iD,cK3pC6- RYnY|{#6qfܐO2X.Ne8kD,ku_ee2n٤L2\8wqgdA&b +uޞeֻ\D,ۼ loxa$Lwn$]%]R" C'`w>_eZ6K XFlI! l'& X˷x ,Sv Xfsi,6˹z!r3 XF_c8 7F/,(C˩ XUL/h/Mf`Yyo Gby2x ؗN2=WD,)_bB꼯XV}/IJ^0hNf-B,Jk(]?ot4T}$Q#`c_e >~|#Yvf{?_eeI+Bp, Al ZvcBq4&XpGZFL#gh~.w/MвlNвr4Zvѐp(eGr-^-KopY;FhE~-^ۦ ZVmhY;B y&hYY ?B$݋-@ȃδZ3zu<3<3,ɗi)elU 2'2>6PpϯZfc# clcA+ ejLڀ-;dB-su~\}씑halwRep.ZpL2ƒs'rż>O2m+2ij:Jr6\&'rYvo\_v@.x$z5 .+3ypup޴\F4U^N8#R2:09˚38R6֓U`>9lej#Ye~ +8^^V^ |fx#ɦx /+7X /F/[p]e8C\n~k~aDeIgK^vk#<1ˬ +&z/;I؋)32V/kF /SxdGxYU Ne_l/5->3 nu:kgokm@]2˼Y=ˌRll?.@/~C3(+^v5Be[v|3XS&m@/%U0v$H/VXx^F Re'U^v@/c=Йetu4@/+`n Lesm;eU:H/+Ӭ<^^D/ʷxD/+MH/Ӓe6fy#(܀/sZw9:H/'z٪ZQtDH/;JPA;˲gkL 2]i—Q _VfL0N" 3v; f4l_ /,|&!E<3p +J&z&Y<˃"*ƀ0+OJ xv:m W f\&Yꪗ0lp- *v# sO yf J7 B>3,QI䰝`6F? 0[u f{D0c{,f)fZK '~YBa|m helm* eXH=ea|Y{Fz]egf.*eeH +1`e[KlO^&P+zYyC2lvnO2HX^4 k|e,60TH;N:ct-˸x֩Z0FD!e/ybpm^yfzYbͰU5N42Xe$ؼRiQu8N"WEfCrzx :^Vrm5Gz/qqdeX^J 2 4:_egOU 252'2"e+Re^F+}Vi/yb^7ˮo2LJ]/+zs4HОeL>eXJhyfva&xY8j=F.^jݝ'xYyt2{d9![3ˠ9S^vl^N~? #(aĵB2h[|'xxOnwډMnTL2euFxY?vDxf /I "l=Fw]R^%' ^VFMm'z0*#{| f>geE]{epۀ/<ʓ@L + 3Gd—x\eV_ OrnKx=K#D<;bO2>dzF|} bėQ|8SVT2:#5|u ץ3e%nd^>ٵ@/+h)}/; 0+r) 9l e`VeRHɵ`Vto8«nZVyfސ7U/+_Wօe/nF úU ece~I _VFzY1Yд^!hRc Ҕi M݆rme`7nڀ/c`s߈/cؔ|eɍ$] +2p*# D*^/Lcu] 2[tr17`ne22-~3Si_VfY/#]@_gJ<\ #lM 'W|A' _Fڮhe,v6nZSl89NLedֵ/|&xCFC]V]nY}Je?2̕jd%z뮎2J25_O2Vctٵuж]*t}DrgF[DY? ܈.{;'tޘ,K#Q  Z[D.[*m T@.BN5e\zӉ\F&rC\_2i-rAסM2p-lWti j6˘ǽp iQ$ 4喱(:p.,#nUπ-N6`X(owlz 2N{ɶ2<7.GlnSJTl =3fc[F%[FstlYh$"kK 2ޱ>`x)!:H-[Te"6P8wz@-#9dԲz.(@-ˬ[2RˎEtbx3@-;(پB˨61˨860˰%@ˬ![2(2 W%hQivfTH-yA42 2='FjY*c@-10N:jL̲7]^G00h>#¯FfaAdݟoL2h +L2.^:n;'d2ZFb;jex{[30Ue+ 6`LZ 2<"6,#Xe?$,E`jFi|XFPEjXvP젟,#(ؒ˘]ԻfZQgtɵWFuf(N?+^y 2Rw526@n[el2f zZ@f'$zXO+#$Vk_&K2쑠d8",0`͜Z52YVx*`ej`e3j`eeYGVF{ک>L+n z╭:ˢrQq,kmt.(,;4(b>",@7!Iu󌼲l-S'^U6s Q+h~f^Y<3l'߽9@lK+fK>`yv-J۩2*/yQۿɦr᷹$a\Pj7>ό+;"u++/etVtV(:6(Vg% LH+ VYgZYYAKZĕ%96he<3VRr&\ +OGWT57ʖ9=6G^%l r/exe'O#l!磶WҘdWxe$8MWFQ3R%f^ٺi#x>_xe,N.m ye WF昰W˛(en3L%kXV")v&ɓ\Yo' k2ڼeXeFIKf$t/B2@De)׀x&٢1n&4 ,Afq-f`~Q|f`.Zi# +]ef:.FQ߻8{axyevr ͭj[~ᕥV u{WFOgZJa"LWZ'qQm1! Hal/Ȓ}Vv2`eEʇ^FXIEVgN&XKSXقˏ'X C;#j VF'+K$FXEl,FXno87;ߝ5.D̮VɄ*6ʰ^OQAfVt56|QYe%ZLݕ*[Z*cHȜQeei.Pe[9*UF)*+GݙU<FV%Z+OK;lqG L2,)*nmdQD*ÝS~Q'VYyդά4 >-Ͽ3*c0 ,8jgU-*+nG2!66|aI9m3L,+vf7Whf]Lk} lH|xl3,J?_`ee:9^Xmf rV ,'V`e= L8ʬjVnheԖBxDhL#Z]VN9 cUWL(WR탙qe qJ͸(v-=pe/gZٶN8ե?.lĕ݆]x,(Ĥ̼ oG3lqe7 q3(1,)yH$+heT7Xˬo$5P B˥ie)iSܴ,I|XFDkXiZXQ ,;Z,+˘ߴXFii+AkĕYތ+i++֦++;hθyh# =3 R3xB 29\pY"ljZ-?FZYޤ96ʹݽ.zy<ʴ'+c7hҪq45wfgVͰ2-`eP:p˕/.ӦV&r}+Vv V5Ͱ1 Vvm*,ʰs*èv]]Ye;*45Xe(8#Jlm5άV[dxU6ʚ*cʎt̘k6l%;E0elԇv”bX)+wm6fL y͘2MV2Ŕc2 )*WٻRG志WcMY=>n?*i}{9*Xܔi|\Sߟ?P1_f1kPHo 78)l Z~qzfcK8=?Ŕ)0OHwY ן]BUKk_/QxO_]⿸o_B<>Vĥ$."yXVJCNx~}mKnr/|xs`ə=КvpҸ7x׳)=u8r>dB4E#I{Tok aCC?>4`C~SX3CC?>4GL:6???uMQNoP(f'Gۇ>Дۇ/Ȃ(O}?S?1<ۭC3R?|4#C:Iیn6cxFc ov?gDj?x)c oh;988cW:X5.\qUqqTI?q< CS?Ϳ}7?Fs?{~~//4?z1?O u?xnu%OQ?~Y߭~xBͪǏc1h2&2a?lM)sSZg7%N\o̖N >ސ#?|1/:Jx_,?{):e`xcuJk)SNg7%M<oȔ>ژ?|!e^K/`.G뉵qod-Uh}wG/qt?NI_bU__„Kx^?9\?8_\"]2'O3Wbڿ\Exvs/6E*)Rrw x@Zvo:!0T!3i 23p>^Cs.^_9yZ xG`>#Pr"r^__~ֳ)O?&f7o{;"?COo=okGϳLg/˻_ e HFrAA{y vL+ /c^gϕe77;0]T¬䟾_^O\~_ +eޣɰe &]fKА)+:-aZ[n_fן:mAsr;l6:;.Mߎ%a?tXsx_a|9}9엡 zr۩#edne~GE#Eeϓu^ÜfA+F;MTkxxش]he05vc'd4vEYÖ7jڕ'^]Fx}Ѷw]s_;OPAg\W (رs74[0جڹЌFV>gom$|KJp3Onݘiw6=^n[H; 3Ma}[}KMÙb^ 0kBf1kp j_7'W햩 vb,Ѹk*IѸ[+h7&v{V2}\'In$yܳD}n{Kv-]}F.n*m{.\Yo. 5p~5H5%vˋuYc 3Wtaն2ަѸ[^c&%>kׯ^^ WM1ext0myozJ̨O֕m_4.e!EYE\fM;R}۵i/Bmym&]ȕc_XW_n FPMr~ю2lV- sv_b5͍ۖhd)ݿd@uGޛ{Mޯ^*j%.f\m\Ti'PS Eع{N\QmAӐhon:.%?lKr.Z~yV&kz]>^2v + j {q/ .c7kTTWs#42eHM33.LeR[ubuׯ0vfZYe;W;61PV&Zg֛*~l҅~z/uʲ$LtȲ?r̴idv[βVP`̒z 5nɫW*a2g{ZYU"{JhvBZ, SY$1_5?7CIK$ٮ\T] qkުBV =m֌tbߴr_·]Cl5YA LA^5m,&RZyLQ`e32JP+m!iR_eE7Rs.rGd kکe)@ji"ʕ&UsE)ZY(ڎw>]Yz" OC(K?RQ~i.y7!)Ud=K0tI7ݽ~ez-Q&Bll +ժlNؾ VٮtscFSA>W$IS=~$Q.x[^t71pTI7{#⯌ꚰIh`v~JY +4ia ڡ'0cVv<6,Jܛ|X'vKx a)Ż7a5o{t뗔%Qwk"+K%S7:$t7RR*l:ni&'%(Φ5 ^2*g#_/X`/羵7@ٵrGr|ɥ5ɶx V$dGТ|qK6w&Ҥ ?Y0\Ew9ZY Z\,nKD8TkYø&M48+ʪWyoxl_(W䈳e wi+K~()Kum$eF^vY&-ґʢ\GdKeh*j]qNz4q繬'^2Rhf8g;5YK+ [ӠfV$xש,.\Ve? S J5=M+owX@fWƊri?v×L;gt;7趴ϝ 6M3ꪀcնi9[|T=(ޖl6lXqZΛ4j TxI#}aش]p$ T(x6_&IuO7M*Qwf & ܎, -Rplm`p<$Lk;Eh vPB gZȷ[bpH|յEUQ_n]-Cr"n Kv[VZ]+#}d[H>kV 6ieQ›aRk-K.6e/\ܚF>*kcw޿4VynͲ\']XrRlTA)k*ES.YsƤieYBLErmw]iD;h%$bJ#<< f0T"ה&iތ ޮ`ZYCk?6٢+׵hy&[jshk~yn5U@ ]Ÿ$`nw ͅ8ѐ6f&U mm"9ʄSӽnS,/GI2yhǗYnoq.H)}?[nɵILM+,Κ.zl+g)R&_VÓv* N62&|3ooMsáCqմ[ \.ȭkE8UVxaiwcV?ٷ[˲N[kVkb(r-,hAx*K]qH? +P4SZ%lٱ4kjoFUI] k},1kE]Sk8ɜWYZY,IK+Xx!{e8 zx$[ʒuRkс]@g% *˩Erm_;VM}j;hw/pMUeUvS{b2HJxu5EF8_ @9\SҮm7"x+Zh;rvΠHtmZյ{E))m:y+\Ru +BnpTܺ2W^d\hck_{g,;wVPJ>gg"Vn5owNH$ \ k8[hvC C^"cEot >Z͎fYkUsȪ7 #}[Ќ+ۭ W?fr)h<׳hd5\: J4eṜceUCL^5)qBsk︂)uOW2 j (<u֚1Q?"]QclwMU?IJ͟m\Ezgi ~a4Đk`KXWoW;erxj3  346`YyhwaLF, +?#kh"p y{p7ʃ2!Ӱn<4 {hOvY,lk; ObM(mIkjڞk~@m6߷,;26VQ]c6X&לU{؊:Fsc`*ڲ;7rH]; .{&x]f} FM cjز3zvop=1`1a߿L gWq=Bݹ)5XxR4T9Riy7{\0Iلћ^5fC&9'VƆ5͚i3&Nx|W͟rp% +c9Re ܲ?p--O _!X(D6}sF#zy m=DQ[lZ|ߖE +sk^ "=4~Q)}L\"Į-m>/x.qݟ8#f~%La"_*~35lۊ7Eoq{L 8 xKŜjk즏rJ5iX|B l6]tcT ;/Uvh]x^+MԈ%iDh9 HMĔ2.]JX?yF0E԰,iLL.m5)W}7ܤ![ȉW,{"Kv[]9m4l퇟bb. px4%*0`5Q'e`aGM"m5|(8go'i'G/_4󅽍U{3T݌ԥpjXB/ӢXm!ƫmw?'Hl$<@m@xqQRj%|o'Σ7ip%9W[aJڢƬ#&7:lƴ<tot=h.d>W 7KĪ5dB[[5z+U%-'&)$'an4ix^>n\&kg/DY1U6~[ 0'^*@1-fһLH&•w)09!Q[V9÷W8'/m:3E3jN|Cq~:-nR'aboPk\,=+4,-41m\R)j s9 sLO0rn\rݘ0aj0%"p6Mpz= Km:S;?傳6 ~<-Tۆr̴iRN;_r?_nkϻϪ"f=cBxubH0sAeh^QgX-yl`mĬ3scLݻ+}j}ّ[~mnC % +wpPXMYWR59}gĴ'|8pdjlE}8j̨4in@vX,zټL+X;c$kZHCyF +5}ӁeUF dcnHS;YlMTgζɘ~bNv iGNteiOO֚5ysP(DaO,Qq$&Oha所gN{2vҠ m4zcFlx@M&j&i<~M]}: +f7Da-ǷXvg}.89)4#ǷA +iǷx|ixxbgf}$aJm5܍eƬfͰ+bVa%1x@xcsK48(6ܚg ca4=UŅcZEMaqq"z/ȸt~}p&f_ X\X]},@jp&|IbAk;[5eRõڥ_-fEϹq &ܬK`M&[ư`ђGDi 5w5g 2ӰY=:|* { +M $GTRe^"z +ϝl}<ӀhPJ E6tt{K%%${֩$|*׉FոW0%4L)y֞g=sm;&?V]E0} 4%51 j&s=5WX\y@~eFxNX<mO|Ku &PeYm1҇L>֢ 3 }Cxޖw披'M ,cOoH[X\L&Cע ۿ-aq9y&|e7Ρni1W0 t"u.Jzp=PckwD4'= &3uxJXxڈ:<לU͑4D̓y5ğrCPjlrõI70^\mz4B9C?$ ׬ij';둼6^ =J9s<}Hxm*>iaqrG_IثvZ4k ;o A#vb=dGml|9F:ҩGL9V&LsX\h5.TsZͤl(4 .2O> ‡0lilo&7=Ŗ8q@5XH*-q8.X.d]l X)dl *䩑ُKZ>0_U$mQڪ.;8=5;i'87[2ci¬1&<ݖ i'ڧnw/(ワ 8#Yッ"M_bl7&o9qkL#%Oc9gUR\y 8@t2cz) 9RUkD]nX]`OO17߬qЎLoƱS&mUsj* 7&> +ܞF@̾"?JL_l:XH`x,`1ysp M'@/l+FGuށ=UF!=$d̤=$dC2 !=$dVI̥dC2{Hf̵dC2{HfLC2{Hf!=$d\{HfC{Hf!C2{Hf=$d!=$3C2G?$dfC2{Hfv$3/~HfLC2HfV8=٦dYh(a=C2D2VYO2GIfp1%ɌX$3d6]mT@25 3GAfjOm*5lWyo9f +J٦cLc+헲TKٮ_o[$3# +ev5lQE2@mPf6z2( +pHfQ$hT̼s23^Db%ȬYi/Af-shwsLK ] G%ذV  +쇩lA2do"-Rvk[N-FzA2[3Ɍ2ʌw(3#=X3ɌM3lWBk7yzh=H$KHf[$Pյ$3B 6=~dfE2&d0%t23$(`d^jdU̾>AfG*dZQ2Ȍ!ndWAfY_svV3тe_ 1nj3 YAI3AaYp̂Yp̸e3jcYH2 +:|1[B'W=~w{5XNqz1kc+č堟0fb%ҩk8f1sU8fʆycvZڝdYZȂd^C6dl rd2Ӟ~/QfMM+E9$3K%lϵ; @R&^. ة U2 V2 V2sV1 `W1[6_ ծVp̂+Vp?8f愺c\mO]aWVcv*0f̫+%cvd1c{C%Zc9T/1f=kZƘ9Ę(1f3_1fю˜E_1;g +c~eBcf7eٶ{V 3Βkw٘O gĬ[ fc0C̶kN1ˣUMLA1chQP|Wv +Y+҂zI1(fڰ1-S̶f3",*YsV!žWQ@ YS@295ܬ fp̷Kqbv ^@̼)y 1kvYz0b]S2̮]2 3gQj0[lbx|M0;&m` zI0SK^̢"$ٮu f+Y 0[r3&%+aeDݴ0S+Lڍa`6g?ܘ.f c`F7k7<̔O%lM +`{![0c_aŒKwf¬y?aNgfY4f%Œ[Ea椮 +`ƺW/fǚ+١3`7 J*fJV+YmV[Y˼߅/ _I(_6alK%lSVbZe(̡L3;zٿF/۬p2\oEE/[kz١?I/[[xL2{k,1['^]UJxwxe^2zm]Kl/kjzC/{3e;-lc쁗%/s遗qxۚ1c̓/{e=2i=BzeU҃/s=_|ك/s=_|ك/Me|ك/Xxݴ_Vef//_yL~K 23B<o)%1̸ Aֵ_V0U<fjx3ٵ?0 O/cak_.JY_̸f]M+f%Ey _{/;UGek2ODf.*9;KY$V#b̰&yZA0C:Kz+`f5&!',>`MJ:D0k$Y`KKVTx\̘b3+%L,^X'5:`杊K~w)erW2/fHY0 0c/_! +#`vohI0OY֢}A( f*f5 _bʔ)(jfHY0cNil@2l&c/0 +~+L+eRfQ[̾!eweڸfRfHYڒeFY}A2l02l02Qv} e_ae~*z/feFY}e_fmeMkS+_DO[l02(2ŅL{/ke,Vûu2ŕeJz,.c͚eUzI/KzN#,*+z~?LE/Sze/e͛VsU_^h-8 mFYV.3’i]aevهAer؊]6d]aetهAeYb}d]6{dQtKtي>7wtvj?\cUNUe* n )Uq.@V䲁+e3eX&!!Xg[2l 3ey&2l7 KtV].;W5eC2lШ$r%e_(L.(.[W2k \]{E.5ܲݪ#^푑WpHeVp,,q˼Wܲcen1G`-c[^r>D-k -sUeVLYW.S2- .ʴ^d'A.C0WC2i^kW-'elݕem2&5o"+%lv +e|;,a{-[BزlӼ^`bز|X–}H[[GsZ–1WÒe4 +q2˗z-۬i [f3E K2{-Ã20 pٮ^ˬÆ38`NKದT"#"d&l2ur.,ܴ.C.Ĉ{]fOtKN]p/e^ tf>vG1W[]h|m5 3k_ ]^;=evẉ]f +Wb_~ ɢ,ˎ1]aT|$eK}]]8Y: ʝ]vn.ˎtXˬߕ?wxOAdh=&Ɓ*O2֞xjA[x:D/S$. _6ET2&{iYqr*/#grڝ_Yp}kw~ٗf120NYJ0e Ae2E2ؑ,fOOe[~hw|GK/_K𼶄/ zYj}~_&; X_͂xx3̰4`fXok1ij aFT O0IJ0cf7{]x#1N a3Œ]00p3 V[X+0+8/e,6@{FavG-kSL0= 3]g`T$ fho"Y疽 M#@ 锁ljJwlp3*vGG|0cq23l_KɎMC̼iwܡ^@غ fb7;P6!C .$dM}? fbb5 bfTKG b;tj#CXz)=SFN!|M3ksw׳ f*^ 1a|[B 1/r>C0J3\z1㱷V 1XV_A>/z/+}{b!e-AVV +b6 E _/^M14 +bf` b11v|a-f-1̼W 3r2lVk?f߬;W2 +3l\0̬poq'l 3lfba+`yZf+J(-1> 1su1#lBw=C̘hlp +١|bvh{I^P̾iwgȱ;l-[A1UMљq&C9ov- +J +}- -Q(-0f{#j& ^lf`cc^Q71fXb̦K)0fRb1[ c̬_`}D4a̢𩠘snAÂbvDoA1k7x3G]WE1)f-b6@l,ʂbCNA2lYH1%njhxc6BO=c5%njM8fch?9fM'%Ƅ1mo3avE3ĐjY`> +endobj +118 0 obj +<< + /Type /FontDescriptor + /FontName /EAAAAA+mwb_cmsy10 + /FontBBox [11 -215 942 727] + /Flags 33 + /CapHeight 0 + /Ascent 727 + /Descent -215 + /ItalicAngle 0 + /StemV 0 + /MissingWidth 500 + /FontFile2 119 0 R + /CIDSet 120 0 R +>> +endobj +119 0 obj +<< + /Length1 1992 + /Length 121 0 R + /Filter /FlateDecode +>> +stream +xUmle=Ҏ{`3^wLz׭s%["AZC[خueAM/CD%:_r4!HBb  m >s/^:jxiZ |'T~lTvvSdg҆70$\qm#U7s3lxl~b{gUg +l;"9I=g,Q!_^~uK_2 +y'.zWJYN,1qPo~eev2EcQw)8fg33 uk5Uuen(H",͍!UYl3&񆞄Mzmb'LHU3vUYy1VMHi=iD%S˺\> 5'- JnML1DIO&^S|r]O>Rl͹-6Wl0ȹAсQMU%EƉRXɤ0Yk4+R%nH+0EYL2&'kQU􀪜EX􊰨$-p&L"aMXTTao BUrIU̺vua7YKn-&#*ĸ9 Ony}-4h"'\YxkC%B5nń`9U;[ֽq_.|[_ޮٰT]ɚ` +U;͞6c%Z!_FΈghyF'ʌ +hR}Bfp'ޥ.Kd km ѽwBxc[EwqrSaw0/;`l>pJv.BLXG uLr0*`-,`l^sMtFS 4ioh:F֠SO KxzGI;MJ$El-Z (;Iˎ9DHu<&*+qdlU;Aԡ٩L*=-m InEb&+ -R@feVbFј*@gKӇQ]'Igt&?H{U5JQ#TG*;Ixtld> +stream +xk +endstream +endobj +122 0 obj +9 +endobj +123 0 obj +<< + /Type /Font + /Subtype /Type0 + /BaseFont /EAAAAA+mwb_cmsy10 + /Encoding /Identity-H + /ToUnicode 124 0 R + /DescendantFonts [125 0 R] +>> +endobj +125 0 obj +<< /Type /Font +/BaseFont /EAAAAA+mwb_cmsy10 +/CIDToGIDMap /Identity +/Subtype /CIDFontType2 +/CIDSystemInfo << /Registry (Adobe) /Ordering (UCS) /Supplement 0 >> +/FontDescriptor 118 0 R +/DW 0 +/W [ 0 [750 776 ] ] +>> +endobj +124 0 obj +<< /Length 126 0 R /Filter /FlateDecode >> +stream +x]Pj0+l CԒX}q z0h[lE^X gBpjV& +:G:g} +endstream +endobj +126 0 obj +234 +endobj +127 0 obj +<< + /Type /FontDescriptor + /FontName /EAAAAB+mwa_cmr10 + /FontBBox [-43 -250 1008 750] + /Flags 33 + /CapHeight 683 + /Ascent 750 + /Descent -250 + /ItalicAngle 0 + /StemV 0 + /MissingWidth 500 + /FontFile2 128 0 R + /CIDSet 129 0 R +>> +endobj +128 0 obj +<< + /Length1 7956 + /Length 130 0 R + /Filter /FlateDecode +>> +stream +xY tS畾mZmKŒlK&» ml +o`VXIH 4-IIs ]& +4KӦ.Mri&tIiNf X}OC3{g@PA`!fm^aZ]@ʏw;-kNP]lj$@;#-KxqПZ;9oBur܃ەJjS{4T5-&?h +dS<5=5~Ey,; ?v xH7Dz"3h ??o\y8 3p +p&a X 5Pe? e~?y9>'g#u6|9L2=x 8>. + ߅M%)3excpa)ie)#9PkF>Q$ǩUJ\& x.ZlY\혛w[*ʥb^=z7x={͋:j, CJм-woW,$%x7}N |dto~6}OZQugItȅr sY!`W*s,;)LNqKXR&C%rYĢ+I )2Sr1OUv9DS%F-OC=}kնy=S'[gE~<~cݶ潍1 +r<ݳ/lкtl\`z>Sx~&1xw!2 eK7`ı 6P(I YFzZjE +  LVE$2!i#SVV*5/ybRxsS>f`/} +s6? +ܐ +B9 +2PU3tx9rytE~Ef`o]b>j7 TKدw}16Gz* :*z՘?>@>n)DOC6xO}fW֍EEnב/#Kc- % "9XJTa#^'iThhWJu +d؛̧ L^L[{.IVtJf uV[XG=6[&`S*{YxcّƤ!f@8DNR#ӱrc5ts%[) uF܏>Q3[! Tmd<'[Kv91#HDNSQ ۧO_iXTH-XEZ#3zEe 5Ȕ8f!' N`ҢXhD VQ z}queh_,fC -Gc}k"Ca0+v)t2RFLL^KRpX€(ƒͣsg%qY܈bmlf-~c"mxk. +0}y>qH2TҊτY +\r%'OA@3e$NDD5M|P %5>'CR eiďïMo}V;~"?ƾ=ieoPts{Z$oz%ﮨ{u .)޾ζ_;=I+NYb*rqؗnVrɉwj &vȌD1ZȾf'/m8֓kX__Ϩd:C+0.v0~﮹w>k6xPL1|zݨo|F)P2`rC d2wT%d3װmef霔`Kӡz{`7oPV/pë>ltfI,*V-V#?5P+Ci)Ŝfee9c˜)Ɯ3lޢj1=7˞^pFc4\Q!Ι흻Z]kk<88_vxɚdAqt0UVyaw³*Hag %qe@yH6ERjœ5;D "F)V!)]o2t 㙨1@wy3og~`vjcJtEΔl'2q?P@-ohP֓5SW:LYfkq<[\!:r18%':YՊtl33"qiO=RZ`fg?[|raPu$?˛_(G|?5C:Ia@3A2H^f4$ǩ^Q.D/E=*n^&m?>$0o_i-31q+ݳ94yݤ X1jA~=&:1dDY_VI=W,q}U!&r3[{DrlICőBk+|I1*Dx$`D,F w+q;g74{gKrKJP1sm8?8fyՓk^smߑky:/w䔔dϮuɟq}kv>uS"C)ɈvICȚЬSR7be{NghԊwyϻ_m\\x~Q'ߵ:|NiKgv⑏G +NЕ*Tp +D4".L/x2bgQ6e+6ЃfG$^EřQv,<ոtH)oL+.,+.{q[ZߖWw~+ώj&~UeSe{":ùk ͽׄkvT]8N9M̄xe%rN#/*;KH,?/ƨ< +k +3\"mؓ +LM4զӇC'%<\[(W<2 r +b0L|PKVs% @=%F[ʔ R;2P}![wwJEWӯ5'TVx81qPڒMΕ&Cum<$~2ʪCo*gښzL2Fa砳)K#":W[s\}2ҘEuZުe3[PYN)0A+ߵLQDbLMm ):S%clwņ\]93gXû驵igr海ޟ>PzʃgUMgVN267 NUd3ٙ1_"sOgzǫm΍c5g/S 鉖ӰT<+V?!$8J7zy6&dȥG-#NrzޣHJyOu3.]vC.Jw [^G3砂~&U͚Em=%s_|\S8Nz1ۥYTHap&Cvbe6+z*(Vg(hY\NO> +stream +xk`3XUx +endstream +endobj +131 0 obj +20 +endobj +132 0 obj +<< + /Type /Font + /Subtype /Type0 + /BaseFont /EAAAAB+mwa_cmr10 + /Encoding /Identity-H + /ToUnicode 133 0 R + /DescendantFonts [134 0 R] +>> +endobj +134 0 obj +<< /Type /Font +/BaseFont /EAAAAB+mwa_cmr10 +/CIDToGIDMap /Identity +/Subtype /CIDFontType2 +/CIDSystemInfo << /Registry (Adobe) /Ordering (UCS) /Supplement 0 >> +/FontDescriptor 127 0 R +/DW 0 +/W [ 0 [365 500 500 500 500 500 750 833 555 276 276 388 555 555 443 276 500 750 276 555 391 500 651 526 555 443 526 750 443 333 500 680 500 394 500 ] ] +>> +endobj +133 0 obj +<< /Length 135 0 R /Filter /FlateDecode >> +stream +x]Mn0F9"ERUb5RXܾ4jg{fIr*ۍ"y>(OC?yMKgWR )~kVI>HʶȰLw +|aX?a]߼!ًXη]Ɏ"sdMNN/{$gSM YAWkꐆq0K5m{1 )P +@9()rRF* h{iP ڃH&L#)xJx$< Hx왁سgؓYS64j5s +TW8_z ++x|w&7 `ts +- 4}h^,0wKT|~ +endstream +endobj +135 0 obj +388 +endobj +117 0 obj +<< /Type /Pages +/Count 1 +/Kids [115 0 R ] >> +endobj +136 0 obj +<< + /Type /Catalog + /Pages 117 0 R + /Lang (x-unknown) +>> +endobj +116 0 obj +<< + /Font << /F949 123 0 R /F950 132 0 R >> + /ProcSet [/PDF /ImageB /ImageC /Text] + /ExtGState << + /GS1 2 0 R + /GS2 3 0 R + /GS3 4 0 R + /GS4 5 0 R + /GS5 6 0 R + /GS6 7 0 R + /GS7 8 0 R + /GS8 9 0 R + /GS9 10 0 R + /GS10 11 0 R + /GS11 12 0 R + /GS12 13 0 R + /GS13 14 0 R + /GS14 15 0 R + /GS15 16 0 R + /GS16 17 0 R + /GS17 18 0 R + /GS18 19 0 R + /GS19 20 0 R + /GS20 21 0 R + /GS21 22 0 R + /GS22 23 0 R + /GS23 24 0 R + /GS24 25 0 R + /GS25 26 0 R + /GS26 27 0 R + /GS27 28 0 R + /GS28 29 0 R + /GS29 30 0 R + /GS30 31 0 R + /GS31 32 0 R + /GS32 33 0 R + /GS33 34 0 R + /GS34 35 0 R + /GS35 36 0 R + /GS36 37 0 R + /GS37 38 0 R + /GS38 39 0 R + /GS39 40 0 R + /GS40 41 0 R + /GS41 42 0 R + /GS42 43 0 R + /GS43 44 0 R + /GS44 45 0 R + /GS45 46 0 R + /GS46 47 0 R + /GS47 48 0 R + /GS48 49 0 R + /GS49 50 0 R + /GS50 51 0 R + /GS51 52 0 R + /GS52 53 0 R + /GS53 54 0 R + /GS54 55 0 R + /GS55 56 0 R + /GS56 57 0 R + /GS57 58 0 R + /GS58 59 0 R + /GS59 60 0 R + /GS60 61 0 R + /GS61 62 0 R + /GS62 63 0 R + /GS63 64 0 R + /GS64 65 0 R + /GS65 66 0 R + /GS66 67 0 R + /GS67 68 0 R + /GS68 69 0 R + /GS69 70 0 R + /GS70 71 0 R + /GS71 72 0 R + /GS72 73 0 R + /GS73 74 0 R + /GS74 75 0 R + /GS75 76 0 R + /GS76 77 0 R + /GS77 78 0 R + /GS78 79 0 R + /GS79 80 0 R + /GS80 81 0 R + /GS81 82 0 R + /GS82 83 0 R + /GS83 84 0 R + /GS84 85 0 R + /GS85 86 0 R + /GS86 87 0 R + /GS87 88 0 R + /GS88 89 0 R + /GS89 90 0 R + /GS90 91 0 R + /GS91 92 0 R + /GS92 93 0 R + /GS93 94 0 R + /GS94 95 0 R + /GS95 96 0 R + /GS96 97 0 R + /GS97 98 0 R + /GS98 99 0 R + /GS99 100 0 R + /GS100 101 0 R + /GS101 102 0 R + /GS102 103 0 R + /GS103 104 0 R + /GS104 105 0 R + /GS105 106 0 R + /GS106 107 0 R + /GS107 108 0 R + /GS108 109 0 R + /GS109 110 0 R + /GS110 111 0 R +>> +>> +endobj +xref +0 137 +0000000000 65535 f +0000000015 00000 n +0000000145 00000 n +0000000197 00000 n +0000000249 00000 n +0000000301 00000 n +0000000353 00000 n +0000000405 00000 n +0000000457 00000 n +0000000509 00000 n +0000000561 00000 n +0000000614 00000 n +0000000667 00000 n +0000000720 00000 n +0000000773 00000 n +0000000826 00000 n +0000000879 00000 n +0000000932 00000 n +0000000985 00000 n +0000001039 00000 n +0000001093 00000 n +0000001147 00000 n +0000001200 00000 n +0000001253 00000 n +0000001306 00000 n +0000001359 00000 n +0000001412 00000 n +0000001465 00000 n +0000001518 00000 n +0000001571 00000 n +0000001624 00000 n +0000001677 00000 n +0000001730 00000 n +0000001783 00000 n +0000001836 00000 n +0000001889 00000 n +0000001942 00000 n +0000001995 00000 n +0000002048 00000 n +0000002101 00000 n +0000002154 00000 n +0000002207 00000 n +0000002260 00000 n +0000002313 00000 n +0000002366 00000 n +0000002419 00000 n +0000002472 00000 n +0000002525 00000 n +0000002578 00000 n +0000002631 00000 n +0000002684 00000 n +0000002737 00000 n +0000002790 00000 n +0000002843 00000 n +0000002896 00000 n +0000002949 00000 n +0000003002 00000 n +0000003055 00000 n +0000003108 00000 n +0000003161 00000 n +0000003214 00000 n +0000003267 00000 n +0000003320 00000 n +0000003373 00000 n +0000003426 00000 n +0000003479 00000 n +0000003532 00000 n +0000003585 00000 n +0000003638 00000 n +0000003691 00000 n +0000003744 00000 n +0000003797 00000 n +0000003850 00000 n +0000003903 00000 n +0000003956 00000 n +0000004009 00000 n +0000004062 00000 n +0000004115 00000 n +0000004168 00000 n +0000004221 00000 n +0000004274 00000 n +0000004327 00000 n +0000004380 00000 n +0000004434 00000 n +0000004488 00000 n +0000004542 00000 n +0000004596 00000 n +0000004643 00000 n +0000004690 00000 n +0000004737 00000 n +0000004784 00000 n +0000004837 00000 n +0000004890 00000 n +0000004943 00000 n +0000004996 00000 n +0000005049 00000 n +0000005102 00000 n +0000005155 00000 n +0000005208 00000 n +0000005261 00000 n +0000005314 00000 n +0000005368 00000 n +0000005422 00000 n +0000005476 00000 n +0000005530 00000 n +0000005584 00000 n +0000005638 00000 n +0000005693 00000 n +0000005748 00000 n +0000005803 00000 n +0000005858 00000 n +0000005913 00000 n +0000005968 00000 n +0000079740 00000 n +0000079763 00000 n +0000079790 00000 n +0000089884 00000 n +0000089745 00000 n +0000079988 00000 n +0000080240 00000 n +0000081684 00000 n +0000081662 00000 n +0000081771 00000 n +0000081790 00000 n +0000082181 00000 n +0000081950 00000 n +0000082493 00000 n +0000082514 00000 n +0000082769 00000 n +0000088619 00000 n +0000088597 00000 n +0000088717 00000 n +0000088737 00000 n +0000089258 00000 n +0000088896 00000 n +0000089724 00000 n +0000089807 00000 n +trailer +<< + /Root 136 0 R + /Info 1 0 R + /ID [<0AF8494EAA0E6FF7510169A35DE12CC5> <0AF8494EAA0E6FF7510169A35DE12CC5>] + /Size 137 +>> +startxref +91664 +%%EOF diff --git a/figs/strain_gauge_plant_bode_plot.png b/figs/strain_gauge_plant_bode_plot.png new file mode 100644 index 0000000..f00085d Binary files /dev/null and b/figs/strain_gauge_plant_bode_plot.png differ diff --git a/matlab/simscape_dcm.slx b/matlab/simscape_dcm.slx index 3bab67c..709ffdd 100644 Binary files a/matlab/simscape_dcm.slx and b/matlab/simscape_dcm.slx differ