From 67071e033ae51b6a910b7e3bfa800b3e163ba296 Mon Sep 17 00:00:00 2001 From: Thomas Dehaeze Date: Wed, 30 Oct 2024 16:05:12 +0100 Subject: [PATCH] Add matlab functions and Simplify Simscape model --- matlab/src/computeJacobian.m | 35 + matlab/src/computeJointsPose.m | 78 + matlab/src/generateGeneralConfiguration.m | 39 + matlab/src/initializeCylindricalPlatforms.m | 59 + matlab/src/initializeCylindricalStruts.m | 71 + matlab/src/initializeDisturbances.m | 3 +- matlab/src/initializeFramesPositions.m | 35 + matlab/src/initializeInertialSensor.m | 48 + matlab/src/initializeJointDynamics.m | 131 + matlab/src/initializeReferences.m | 50 +- matlab/src/initializeStewartPlatform.m | 31 + matlab/src/initializeStewartPose.m | 27 + matlab/src/initializeStrutDynamics.m | 49 + matlab/src/inverseKinematics.m | 36 + matlab/ustation_simscape.slx | Bin 230727 -> 197121 bytes simscape-micro-station.org | 2671 +++++++++++++++---- 16 files changed, 2757 insertions(+), 606 deletions(-) create mode 100644 matlab/src/computeJacobian.m create mode 100644 matlab/src/computeJointsPose.m create mode 100644 matlab/src/generateGeneralConfiguration.m create mode 100644 matlab/src/initializeCylindricalPlatforms.m create mode 100644 matlab/src/initializeCylindricalStruts.m create mode 100644 matlab/src/initializeFramesPositions.m create mode 100644 matlab/src/initializeInertialSensor.m create mode 100644 matlab/src/initializeJointDynamics.m create mode 100644 matlab/src/initializeStewartPlatform.m create mode 100644 matlab/src/initializeStewartPose.m create mode 100644 matlab/src/initializeStrutDynamics.m create mode 100644 matlab/src/inverseKinematics.m diff --git a/matlab/src/computeJacobian.m b/matlab/src/computeJacobian.m new file mode 100644 index 0000000..3c4acfb --- /dev/null +++ b/matlab/src/computeJacobian.m @@ -0,0 +1,35 @@ + function [stewart] = computeJacobian(stewart) + % computeJacobian - + % + % Syntax: [stewart] = computeJacobian(stewart) + % + % Inputs: + % - stewart - With at least the following fields: + % - geometry.As [3x6] - The 6 unit vectors for each strut expressed in {A} + % - geometry.Ab [3x6] - The 6 position of the joints bi expressed in {A} + % - actuators.K [6x1] - Total stiffness of the actuators + % + % Outputs: + % - stewart - With the 3 added field: + % - kinematics.J [6x6] - The Jacobian Matrix + % - kinematics.K [6x6] - The Stiffness Matrix + % - kinematics.C [6x6] - The Compliance Matrix + + assert(isfield(stewart.geometry, 'As'), 'stewart.geometry should have attribute As') + As = stewart.geometry.As; + + assert(isfield(stewart.geometry, 'Ab'), 'stewart.geometry should have attribute Ab') + Ab = stewart.geometry.Ab; + + assert(isfield(stewart.actuators, 'K'), 'stewart.actuators should have attribute K') + Ki = stewart.actuators.K; + + J = [As' , cross(Ab, As)']; + + K = J'*diag(Ki)*J; + + C = inv(K); + + stewart.kinematics.J = J; + stewart.kinematics.K = K; + stewart.kinematics.C = C; diff --git a/matlab/src/computeJointsPose.m b/matlab/src/computeJointsPose.m new file mode 100644 index 0000000..7f93655 --- /dev/null +++ b/matlab/src/computeJointsPose.m @@ -0,0 +1,78 @@ + function [stewart] = computeJointsPose(stewart) + % computeJointsPose - + % + % Syntax: [stewart] = computeJointsPose(stewart) + % + % Inputs: + % - stewart - A structure with the following fields + % - platform_F.Fa [3x6] - Its i'th column is the position vector of joint ai with respect to {F} + % - platform_M.Mb [3x6] - Its i'th column is the position vector of joint bi with respect to {M} + % - platform_F.FO_A [3x1] - Position of {A} with respect to {F} + % - platform_M.MO_B [3x1] - Position of {B} with respect to {M} + % - geometry.FO_M [3x1] - Position of {M} with respect to {F} + % + % Outputs: + % - stewart - A structure with the following added fields + % - geometry.Aa [3x6] - The i'th column is the position of ai with respect to {A} + % - geometry.Ab [3x6] - The i'th column is the position of bi with respect to {A} + % - geometry.Ba [3x6] - The i'th column is the position of ai with respect to {B} + % - geometry.Bb [3x6] - The i'th column is the position of bi with respect to {B} + % - geometry.l [6x1] - The i'th element is the initial length of strut i + % - geometry.As [3x6] - The i'th column is the unit vector of strut i expressed in {A} + % - geometry.Bs [3x6] - The i'th column is the unit vector of strut i expressed in {B} + % - struts_F.l [6x1] - Length of the Fixed part of the i'th strut + % - struts_M.l [6x1] - Length of the Mobile part of the i'th strut + % - platform_F.FRa [3x3x6] - The i'th 3x3 array is the rotation matrix to orientate the bottom of the i'th strut from {F} + % - platform_M.MRb [3x3x6] - The i'th 3x3 array is the rotation matrix to orientate the top of the i'th strut from {M} + + assert(isfield(stewart.platform_F, 'Fa'), 'stewart.platform_F should have attribute Fa') + Fa = stewart.platform_F.Fa; + + assert(isfield(stewart.platform_M, 'Mb'), 'stewart.platform_M should have attribute Mb') + Mb = stewart.platform_M.Mb; + + assert(isfield(stewart.platform_F, 'FO_A'), 'stewart.platform_F should have attribute FO_A') + FO_A = stewart.platform_F.FO_A; + + assert(isfield(stewart.platform_M, 'MO_B'), 'stewart.platform_M should have attribute MO_B') + MO_B = stewart.platform_M.MO_B; + + assert(isfield(stewart.geometry, 'FO_M'), 'stewart.geometry should have attribute FO_M') + FO_M = stewart.geometry.FO_M; + + Aa = Fa - repmat(FO_A, [1, 6]); + Bb = Mb - repmat(MO_B, [1, 6]); + + Ab = Bb - repmat(-MO_B-FO_M+FO_A, [1, 6]); + Ba = Aa - repmat( MO_B+FO_M-FO_A, [1, 6]); + + As = (Ab - Aa)./vecnorm(Ab - Aa); % As_i is the i'th vector of As + + l = vecnorm(Ab - Aa)'; + + Bs = (Bb - Ba)./vecnorm(Bb - Ba); + + FRa = zeros(3,3,6); + MRb = zeros(3,3,6); + + for i = 1:6 + FRa(:,:,i) = [cross([0;1;0], As(:,i)) , cross(As(:,i), cross([0;1;0], As(:,i))) , As(:,i)]; + FRa(:,:,i) = FRa(:,:,i)./vecnorm(FRa(:,:,i)); + + MRb(:,:,i) = [cross([0;1;0], Bs(:,i)) , cross(Bs(:,i), cross([0;1;0], Bs(:,i))) , Bs(:,i)]; + MRb(:,:,i) = MRb(:,:,i)./vecnorm(MRb(:,:,i)); + end + + stewart.geometry.Aa = Aa; + stewart.geometry.Ab = Ab; + stewart.geometry.Ba = Ba; + stewart.geometry.Bb = Bb; + stewart.geometry.As = As; + stewart.geometry.Bs = Bs; + stewart.geometry.l = l; + + stewart.struts_F.l = l/2; + stewart.struts_M.l = l/2; + + stewart.platform_F.FRa = FRa; + stewart.platform_M.MRb = MRb; diff --git a/matlab/src/generateGeneralConfiguration.m b/matlab/src/generateGeneralConfiguration.m new file mode 100644 index 0000000..8964ccc --- /dev/null +++ b/matlab/src/generateGeneralConfiguration.m @@ -0,0 +1,39 @@ + function [stewart] = generateGeneralConfiguration(stewart, args) + % generateGeneralConfiguration - Generate a Very General Configuration + % + % Syntax: [stewart] = generateGeneralConfiguration(stewart, args) + % + % Inputs: + % - args - Can have the following fields: + % - FH [1x1] - Height of the position of the fixed joints with respect to the frame {F} [m] + % - FR [1x1] - Radius of the position of the fixed joints in the X-Y [m] + % - FTh [6x1] - Angles of the fixed joints in the X-Y plane with respect to the X axis [rad] + % - MH [1x1] - Height of the position of the mobile joints with respect to the frame {M} [m] + % - FR [1x1] - Radius of the position of the mobile joints in the X-Y [m] + % - MTh [6x1] - Angles of the mobile joints in the X-Y plane with respect to the X axis [rad] + % + % Outputs: + % - stewart - updated Stewart structure with the added fields: + % - platform_F.Fa [3x6] - Its i'th column is the position vector of joint ai with respect to {F} + % - platform_M.Mb [3x6] - Its i'th column is the position vector of joint bi with respect to {M} + + arguments + stewart + args.FH (1,1) double {mustBeNumeric, mustBePositive} = 15e-3 + args.FR (1,1) double {mustBeNumeric, mustBePositive} = 115e-3; + args.FTh (6,1) double {mustBeNumeric} = [-10, 10, 120-10, 120+10, 240-10, 240+10]*(pi/180); + args.MH (1,1) double {mustBeNumeric, mustBePositive} = 15e-3 + args.MR (1,1) double {mustBeNumeric, mustBePositive} = 90e-3; + args.MTh (6,1) double {mustBeNumeric} = [-60+10, 60-10, 60+10, 180-10, 180+10, -60-10]*(pi/180); + end + + Fa = zeros(3,6); + Mb = zeros(3,6); + + for i = 1:6 + Fa(:,i) = [args.FR*cos(args.FTh(i)); args.FR*sin(args.FTh(i)); args.FH]; + Mb(:,i) = [args.MR*cos(args.MTh(i)); args.MR*sin(args.MTh(i)); -args.MH]; + end + + stewart.platform_F.Fa = Fa; + stewart.platform_M.Mb = Mb; diff --git a/matlab/src/initializeCylindricalPlatforms.m b/matlab/src/initializeCylindricalPlatforms.m new file mode 100644 index 0000000..f8e6103 --- /dev/null +++ b/matlab/src/initializeCylindricalPlatforms.m @@ -0,0 +1,59 @@ + function [stewart] = initializeCylindricalPlatforms(stewart, args) + % initializeCylindricalPlatforms - Initialize the geometry of the Fixed and Mobile Platforms + % + % Syntax: [stewart] = initializeCylindricalPlatforms(args) + % + % Inputs: + % - args - Structure with the following fields: + % - Fpm [1x1] - Fixed Platform Mass [kg] + % - Fph [1x1] - Fixed Platform Height [m] + % - Fpr [1x1] - Fixed Platform Radius [m] + % - Mpm [1x1] - Mobile Platform Mass [kg] + % - Mph [1x1] - Mobile Platform Height [m] + % - Mpr [1x1] - Mobile Platform Radius [m] + % + % Outputs: + % - stewart - updated Stewart structure with the added fields: + % - platform_F [struct] - structure with the following fields: + % - type = 1 + % - M [1x1] - Fixed Platform Mass [kg] + % - I [3x3] - Fixed Platform Inertia matrix [kg*m^2] + % - H [1x1] - Fixed Platform Height [m] + % - R [1x1] - Fixed Platform Radius [m] + % - platform_M [struct] - structure with the following fields: + % - M [1x1] - Mobile Platform Mass [kg] + % - I [3x3] - Mobile Platform Inertia matrix [kg*m^2] + % - H [1x1] - Mobile Platform Height [m] + % - R [1x1] - Mobile Platform Radius [m] + + arguments + stewart + args.Fpm (1,1) double {mustBeNumeric, mustBePositive} = 1 + args.Fph (1,1) double {mustBeNumeric, mustBePositive} = 10e-3 + args.Fpr (1,1) double {mustBeNumeric, mustBePositive} = 125e-3 + args.Mpm (1,1) double {mustBeNumeric, mustBePositive} = 1 + args.Mph (1,1) double {mustBeNumeric, mustBePositive} = 10e-3 + args.Mpr (1,1) double {mustBeNumeric, mustBePositive} = 100e-3 + end + + I_F = diag([1/12*args.Fpm * (3*args.Fpr^2 + args.Fph^2), ... + 1/12*args.Fpm * (3*args.Fpr^2 + args.Fph^2), ... + 1/2 *args.Fpm * args.Fpr^2]); + + I_M = diag([1/12*args.Mpm * (3*args.Mpr^2 + args.Mph^2), ... + 1/12*args.Mpm * (3*args.Mpr^2 + args.Mph^2), ... + 1/2 *args.Mpm * args.Mpr^2]); + + stewart.platform_F.type = 1; + + stewart.platform_F.I = I_F; + stewart.platform_F.M = args.Fpm; + stewart.platform_F.R = args.Fpr; + stewart.platform_F.H = args.Fph; + + stewart.platform_M.type = 1; + + stewart.platform_M.I = I_M; + stewart.platform_M.M = args.Mpm; + stewart.platform_M.R = args.Mpr; + stewart.platform_M.H = args.Mph; diff --git a/matlab/src/initializeCylindricalStruts.m b/matlab/src/initializeCylindricalStruts.m new file mode 100644 index 0000000..5af925e --- /dev/null +++ b/matlab/src/initializeCylindricalStruts.m @@ -0,0 +1,71 @@ + function [stewart] = initializeCylindricalStruts(stewart, args) + % initializeCylindricalStruts - Define the mass and moment of inertia of cylindrical struts + % + % Syntax: [stewart] = initializeCylindricalStruts(args) + % + % Inputs: + % - args - Structure with the following fields: + % - Fsm [1x1] - Mass of the Fixed part of the struts [kg] + % - Fsh [1x1] - Height of cylinder for the Fixed part of the struts [m] + % - Fsr [1x1] - Radius of cylinder for the Fixed part of the struts [m] + % - Msm [1x1] - Mass of the Mobile part of the struts [kg] + % - Msh [1x1] - Height of cylinder for the Mobile part of the struts [m] + % - Msr [1x1] - Radius of cylinder for the Mobile part of the struts [m] + % + % Outputs: + % - stewart - updated Stewart structure with the added fields: + % - struts_F [struct] - structure with the following fields: + % - M [6x1] - Mass of the Fixed part of the struts [kg] + % - I [3x3x6] - Moment of Inertia for the Fixed part of the struts [kg*m^2] + % - H [6x1] - Height of cylinder for the Fixed part of the struts [m] + % - R [6x1] - Radius of cylinder for the Fixed part of the struts [m] + % - struts_M [struct] - structure with the following fields: + % - M [6x1] - Mass of the Mobile part of the struts [kg] + % - I [3x3x6] - Moment of Inertia for the Mobile part of the struts [kg*m^2] + % - H [6x1] - Height of cylinder for the Mobile part of the struts [m] + % - R [6x1] - Radius of cylinder for the Mobile part of the struts [m] + + arguments + stewart + args.Fsm (1,1) double {mustBeNumeric, mustBePositive} = 0.1 + args.Fsh (1,1) double {mustBeNumeric, mustBePositive} = 50e-3 + args.Fsr (1,1) double {mustBeNumeric, mustBePositive} = 5e-3 + args.Msm (1,1) double {mustBeNumeric, mustBePositive} = 0.1 + args.Msh (1,1) double {mustBeNumeric, mustBePositive} = 50e-3 + args.Msr (1,1) double {mustBeNumeric, mustBePositive} = 5e-3 + end + + Fsm = ones(6,1).*args.Fsm; + Fsh = ones(6,1).*args.Fsh; + Fsr = ones(6,1).*args.Fsr; + + Msm = ones(6,1).*args.Msm; + Msh = ones(6,1).*args.Msh; + Msr = ones(6,1).*args.Msr; + + I_F = zeros(3, 3, 6); % Inertia of the "fixed" part of the strut + I_M = zeros(3, 3, 6); % Inertia of the "mobile" part of the strut + + for i = 1:6 + I_F(:,:,i) = diag([1/12 * Fsm(i) * (3*Fsr(i)^2 + Fsh(i)^2), ... + 1/12 * Fsm(i) * (3*Fsr(i)^2 + Fsh(i)^2), ... + 1/2 * Fsm(i) * Fsr(i)^2]); + + I_M(:,:,i) = diag([1/12 * Msm(i) * (3*Msr(i)^2 + Msh(i)^2), ... + 1/12 * Msm(i) * (3*Msr(i)^2 + Msh(i)^2), ... + 1/2 * Msm(i) * Msr(i)^2]); + end + + stewart.struts_M.type = 1; + + stewart.struts_M.I = I_M; + stewart.struts_M.M = Msm; + stewart.struts_M.R = Msr; + stewart.struts_M.H = Msh; + + stewart.struts_F.type = 1; + + stewart.struts_F.I = I_F; + stewart.struts_F.M = Fsm; + stewart.struts_F.R = Fsr; + stewart.struts_F.H = Fsh; diff --git a/matlab/src/initializeDisturbances.m b/matlab/src/initializeDisturbances.m index 8c1a881..d7b8214 100644 --- a/matlab/src/initializeDisturbances.m +++ b/matlab/src/initializeDisturbances.m @@ -23,7 +23,7 @@ args.Frz_z logical {mustBeNumericOrLogical} = true end - load('./mat/dist_psd.mat', 'dist_f'); + load('dist_psd.mat', 'dist_f'); dist_f.f = dist_f.f(2:end); dist_f.psd_gm = dist_f.psd_gm(2:end); @@ -132,7 +132,6 @@ Fty_z = Fty_z - Fty_z(1); Frz_z = Frz_z - Frz_z(1); -micro_hexapod = stewart; if exist('./mat', 'dir') if exist('./mat/nass_disturbances.mat', 'file') save('mat/nass_disturbances.mat', 'Dwx', 'Dwy', 'Dwz', 'Fty_x', 'Fty_z', 'Frz_z', 'Fd', 'Ts', 't', 'args', '-append'); diff --git a/matlab/src/initializeFramesPositions.m b/matlab/src/initializeFramesPositions.m new file mode 100644 index 0000000..6a76e4b --- /dev/null +++ b/matlab/src/initializeFramesPositions.m @@ -0,0 +1,35 @@ + function [stewart] = initializeFramesPositions(stewart, args) + % initializeFramesPositions - Initialize the positions of frames {A}, {B}, {F} and {M} + % + % Syntax: [stewart] = initializeFramesPositions(stewart, args) + % + % Inputs: + % - args - Can have the following fields: + % - H [1x1] - Total Height of the Stewart Platform (height from {F} to {M}) [m] + % - MO_B [1x1] - Height of the frame {B} with respect to {M} [m] + % + % Outputs: + % - stewart - A structure with the following fields: + % - geometry.H [1x1] - Total Height of the Stewart Platform [m] + % - geometry.FO_M [3x1] - Position of {M} with respect to {F} [m] + % - platform_M.MO_B [3x1] - Position of {B} with respect to {M} [m] + % - platform_F.FO_A [3x1] - Position of {A} with respect to {F} [m] + + arguments + stewart + args.H (1,1) double {mustBeNumeric, mustBePositive} = 90e-3 + args.MO_B (1,1) double {mustBeNumeric} = 50e-3 + end + + H = args.H; % Total Height of the Stewart Platform [m] + + FO_M = [0; 0; H]; % Position of {M} with respect to {F} [m] + + MO_B = [0; 0; args.MO_B]; % Position of {B} with respect to {M} [m] + + FO_A = MO_B + FO_M; % Position of {A} with respect to {F} [m] + + stewart.geometry.H = H; + stewart.geometry.FO_M = FO_M; + stewart.platform_M.MO_B = MO_B; + stewart.platform_F.FO_A = FO_A; diff --git a/matlab/src/initializeInertialSensor.m b/matlab/src/initializeInertialSensor.m new file mode 100644 index 0000000..e64653f --- /dev/null +++ b/matlab/src/initializeInertialSensor.m @@ -0,0 +1,48 @@ + function [stewart] = initializeInertialSensor(stewart, args) + % initializeInertialSensor - Initialize the inertial sensor in each strut + % + % Syntax: [stewart] = initializeInertialSensor(args) + % + % Inputs: + % - args - Structure with the following fields: + % - type - 'geophone', 'accelerometer', 'none' + % - mass [1x1] - Weight of the inertial mass [kg] + % - freq [1x1] - Cutoff frequency [Hz] + % + % Outputs: + % - stewart - updated Stewart structure with the added fields: + % - stewart.sensors.inertial + % - type - 1 (geophone), 2 (accelerometer), 3 (none) + % - K [1x1] - Stiffness [N/m] + % - C [1x1] - Damping [N/(m/s)] + % - M [1x1] - Inertial Mass [kg] + % - G [1x1] - Gain + + arguments + stewart + args.type char {mustBeMember(args.type,{'geophone', 'accelerometer', 'none'})} = 'none' + args.mass (1,1) double {mustBeNumeric, mustBeNonnegative} = 1e-2 + args.freq (1,1) double {mustBeNumeric, mustBeNonnegative} = 1e3 + end + + sensor = struct(); + + switch args.type + case 'geophone' + sensor.type = 1; + + sensor.M = args.mass; + sensor.K = sensor.M * (2*pi*args.freq)^2; + sensor.C = 2*sqrt(sensor.M * sensor.K); + case 'accelerometer' + sensor.type = 2; + + sensor.M = args.mass; + sensor.K = sensor.M * (2*pi*args.freq)^2; + sensor.C = 2*sqrt(sensor.M * sensor.K); + sensor.G = -sensor.K/sensor.M; + case 'none' + sensor.type = 3; + end + + stewart.sensors.inertial = sensor; diff --git a/matlab/src/initializeJointDynamics.m b/matlab/src/initializeJointDynamics.m new file mode 100644 index 0000000..2596f6e --- /dev/null +++ b/matlab/src/initializeJointDynamics.m @@ -0,0 +1,131 @@ + function [stewart] = initializeJointDynamics(stewart, args) + % initializeJointDynamics - Add Stiffness and Damping properties for the spherical joints + % + % Syntax: [stewart] = initializeJointDynamics(args) + % + % Inputs: + % - args - Structure with the following fields: + % - type_F - 'universal', 'spherical', 'universal_p', 'spherical_p' + % - type_M - 'universal', 'spherical', 'universal_p', 'spherical_p' + % - Kf_M [6x1] - Bending (Rx, Ry) Stiffness for each top joints [(N.m)/rad] + % - Kt_M [6x1] - Torsion (Rz) Stiffness for each top joints [(N.m)/rad] + % - Cf_M [6x1] - Bending (Rx, Ry) Damping of each top joint [(N.m)/(rad/s)] + % - Ct_M [6x1] - Torsion (Rz) Damping of each top joint [(N.m)/(rad/s)] + % - Kf_F [6x1] - Bending (Rx, Ry) Stiffness for each bottom joints [(N.m)/rad] + % - Kt_F [6x1] - Torsion (Rz) Stiffness for each bottom joints [(N.m)/rad] + % - Cf_F [6x1] - Bending (Rx, Ry) Damping of each bottom joint [(N.m)/(rad/s)] + % - Cf_F [6x1] - Torsion (Rz) Damping of each bottom joint [(N.m)/(rad/s)] + % + % Outputs: + % - stewart - updated Stewart structure with the added fields: + % - stewart.joints_F and stewart.joints_M: + % - type - 1 (universal), 2 (spherical), 3 (universal perfect), 4 (spherical perfect) + % - Kx, Ky, Kz [6x1] - Translation (Tx, Ty, Tz) Stiffness [N/m] + % - Kf [6x1] - Flexion (Rx, Ry) Stiffness [(N.m)/rad] + % - Kt [6x1] - Torsion (Rz) Stiffness [(N.m)/rad] + % - Cx, Cy, Cz [6x1] - Translation (Rx, Ry) Damping [N/(m/s)] + % - Cf [6x1] - Flexion (Rx, Ry) Damping [(N.m)/(rad/s)] + % - Cb [6x1] - Torsion (Rz) Damping [(N.m)/(rad/s)] + + arguments + stewart + args.type_F char {mustBeMember(args.type_F,{'universal', 'spherical', 'universal_p', 'spherical_p', 'universal_3dof', 'spherical_3dof', 'flexible'})} = 'universal' + args.type_M char {mustBeMember(args.type_M,{'universal', 'spherical', 'universal_p', 'spherical_p', 'universal_3dof', 'spherical_3dof', 'flexible'})} = 'spherical' + args.Kf_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 33*ones(6,1) + args.Cf_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-4*ones(6,1) + args.Kt_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 236*ones(6,1) + args.Ct_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-3*ones(6,1) + args.Kf_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 33*ones(6,1) + args.Cf_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-4*ones(6,1) + args.Kt_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 236*ones(6,1) + args.Ct_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-3*ones(6,1) + args.Ka_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1.2e8*ones(6,1) + args.Ca_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e1*ones(6,1) + args.Kr_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1.1e7*ones(6,1) + args.Cr_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e1*ones(6,1) + args.Ka_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1.2e8*ones(6,1) + args.Ca_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e1*ones(6,1) + args.Kr_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1.1e7*ones(6,1) + args.Cr_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e1*ones(6,1) + args.K_M double {mustBeNumeric} = zeros(6,6) + args.M_M double {mustBeNumeric} = zeros(6,6) + args.n_xyz_M double {mustBeNumeric} = zeros(2,3) + args.xi_M double {mustBeNumeric} = 0.1 + args.step_file_M char {} = '' + args.K_F double {mustBeNumeric} = zeros(6,6) + args.M_F double {mustBeNumeric} = zeros(6,6) + args.n_xyz_F double {mustBeNumeric} = zeros(2,3) + args.xi_F double {mustBeNumeric} = 0.1 + args.step_file_F char {} = '' + end + + switch args.type_F + case 'universal' + stewart.joints_F.type = 1; + case 'spherical' + stewart.joints_F.type = 2; + case 'universal_p' + stewart.joints_F.type = 3; + case 'spherical_p' + stewart.joints_F.type = 4; + case 'flexible' + stewart.joints_F.type = 5; + case 'universal_3dof' + stewart.joints_F.type = 6; + case 'spherical_3dof' + stewart.joints_F.type = 7; + end + + switch args.type_M + case 'universal' + stewart.joints_M.type = 1; + case 'spherical' + stewart.joints_M.type = 2; + case 'universal_p' + stewart.joints_M.type = 3; + case 'spherical_p' + stewart.joints_M.type = 4; + case 'flexible' + stewart.joints_M.type = 5; + case 'universal_3dof' + stewart.joints_M.type = 6; + case 'spherical_3dof' + stewart.joints_M.type = 7; + end + + stewart.joints_M.Ka = args.Ka_M; + stewart.joints_M.Kr = args.Kr_M; + + stewart.joints_F.Ka = args.Ka_F; + stewart.joints_F.Kr = args.Kr_F; + + stewart.joints_M.Ca = args.Ca_M; + stewart.joints_M.Cr = args.Cr_M; + + stewart.joints_F.Ca = args.Ca_F; + stewart.joints_F.Cr = args.Cr_F; + + stewart.joints_M.Kf = args.Kf_M; + stewart.joints_M.Kt = args.Kt_M; + + stewart.joints_F.Kf = args.Kf_F; + stewart.joints_F.Kt = args.Kt_F; + + stewart.joints_M.Cf = args.Cf_M; + stewart.joints_M.Ct = args.Ct_M; + + stewart.joints_F.Cf = args.Cf_F; + stewart.joints_F.Ct = args.Ct_F; + + stewart.joints_F.M = args.M_F; + stewart.joints_F.K = args.K_F; + stewart.joints_F.n_xyz = args.n_xyz_F; + stewart.joints_F.xi = args.xi_F; + stewart.joints_F.xi = args.xi_F; + stewart.joints_F.step_file = args.step_file_F; + + stewart.joints_M.M = args.M_M; + stewart.joints_M.K = args.K_M; + stewart.joints_M.n_xyz = args.n_xyz_M; + stewart.joints_M.xi = args.xi_M; + stewart.joints_M.step_file = args.step_file_M; diff --git a/matlab/src/initializeReferences.m b/matlab/src/initializeReferences.m index c04196b..df9f3ef 100644 --- a/matlab/src/initializeReferences.m +++ b/matlab/src/initializeReferences.m @@ -184,58 +184,16 @@ Dh = struct('time', t, 'signals', struct('values', Dh)); Dhl = struct('time', t, 'signals', struct('values', Dhl)); - %% Axis Compensation - Rm - t = [0, Ts]; - - Rm = [args.Rm_pos, args.Rm_pos]; - Rm = struct('time', t, 'signals', struct('values', Rm)); - - %% Nano-Hexapod - t = [0, Ts]; - Dn = zeros(length(t), 6); - - switch args.Dn_type - case 'constant' - Dn = [args.Dn_pos, args.Dn_pos]; - - load('nass_stages.mat', 'nano_hexapod'); - - AP = [args.Dn_pos(1) ; args.Dn_pos(2) ; args.Dn_pos(3)]; - - tx = args.Dn_pos(4); - ty = args.Dn_pos(5); - tz = args.Dn_pos(6); - - ARB = [cos(tz) -sin(tz) 0; - sin(tz) cos(tz) 0; - 0 0 1]*... - [ cos(ty) 0 sin(ty); - 0 1 0; - -sin(ty) 0 cos(ty)]*... - [1 0 0; - 0 cos(tx) -sin(tx); - 0 sin(tx) cos(tx)]; - - [~, Dnl] = inverseKinematics(nano_hexapod, 'AP', AP, 'ARB', ARB); - Dnl = [Dnl, Dnl]; - otherwise - warning('Dn_type is not set correctly'); - end - - Dn = struct('time', t, 'signals', struct('values', Dn)); - Dnl = struct('time', t, 'signals', struct('values', Dnl)); - -micro_hexapod = stewart; if exist('./mat', 'dir') if exist('./mat/nass_references.mat', 'file') - save('mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'Rm', 'Dn', 'Dnl', 'args', 'Ts', '-append'); + save('mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'args', 'Ts', '-append'); else - save('mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'Rm', 'Dn', 'Dnl', 'args', 'Ts'); + save('mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'args', 'Ts'); end elseif exist('./matlab', 'dir') if exist('./matlab/mat/nass_references.mat', 'file') - save('matlab/mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'Rm', 'Dn', 'Dnl', 'args', 'Ts', '-append'); + save('matlab/mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'args', 'Ts', '-append'); else - save('matlab/mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'Rm', 'Dn', 'Dnl', 'args', 'Ts'); + save('matlab/mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'args', 'Ts'); end end diff --git a/matlab/src/initializeStewartPlatform.m b/matlab/src/initializeStewartPlatform.m new file mode 100644 index 0000000..3804edf --- /dev/null +++ b/matlab/src/initializeStewartPlatform.m @@ -0,0 +1,31 @@ + function [stewart] = initializeStewartPlatform() + % initializeStewartPlatform - Initialize the stewart structure + % + % Syntax: [stewart] = initializeStewartPlatform(args) + % + % Outputs: + % - stewart - A structure with the following sub-structures: + % - platform_F - + % - platform_M - + % - joints_F - + % - joints_M - + % - struts_F - + % - struts_M - + % - actuators - + % - geometry - + % - properties - + + stewart = struct(); + stewart.platform_F = struct(); + stewart.platform_M = struct(); + stewart.joints_F = struct(); + stewart.joints_M = struct(); + stewart.struts_F = struct(); + stewart.struts_M = struct(); + stewart.actuators = struct(); + stewart.sensors = struct(); + stewart.sensors.inertial = struct(); + stewart.sensors.force = struct(); + stewart.sensors.relative = struct(); + stewart.geometry = struct(); + stewart.kinematics = struct(); diff --git a/matlab/src/initializeStewartPose.m b/matlab/src/initializeStewartPose.m new file mode 100644 index 0000000..101a553 --- /dev/null +++ b/matlab/src/initializeStewartPose.m @@ -0,0 +1,27 @@ + function [stewart] = initializeStewartPose(stewart, args) + % initializeStewartPose - Determine the initial stroke in each leg to have the wanted pose + % It uses the inverse kinematic + % + % Syntax: [stewart] = initializeStewartPose(stewart, args) + % + % Inputs: + % - stewart - A structure with the following fields + % - Aa [3x6] - The positions ai expressed in {A} + % - Bb [3x6] - The positions bi expressed in {B} + % - args - Can have the following fields: + % - AP [3x1] - The wanted position of {B} with respect to {A} + % - ARB [3x3] - The rotation matrix that gives the wanted orientation of {B} with respect to {A} + % + % Outputs: + % - stewart - updated Stewart structure with the added fields: + % - actuators.Leq [6x1] - The 6 needed displacement of the struts from the initial position in [m] to have the wanted pose of {B} w.r.t. {A} + + arguments + stewart + args.AP (3,1) double {mustBeNumeric} = zeros(3,1) + args.ARB (3,3) double {mustBeNumeric} = eye(3) + end + + [Li, dLi] = inverseKinematics(stewart, 'AP', args.AP, 'ARB', args.ARB); + + stewart.actuators.Leq = dLi; diff --git a/matlab/src/initializeStrutDynamics.m b/matlab/src/initializeStrutDynamics.m new file mode 100644 index 0000000..26984f5 --- /dev/null +++ b/matlab/src/initializeStrutDynamics.m @@ -0,0 +1,49 @@ + function [stewart] = initializeStrutDynamics(stewart, args) + % initializeStrutDynamics - Add Stiffness and Damping properties of each strut + % + % Syntax: [stewart] = initializeStrutDynamics(args) + % + % Inputs: + % - args - Structure with the following fields: + % - K [6x1] - Stiffness of each strut [N/m] + % - C [6x1] - Damping of each strut [N/(m/s)] + % + % Outputs: + % - stewart - updated Stewart structure with the added fields: + % - actuators.type = 1 + % - actuators.K [6x1] - Stiffness of each strut [N/m] + % - actuators.C [6x1] - Damping of each strut [N/(m/s)] + + arguments + stewart + args.type char {mustBeMember(args.type,{'classical', 'amplified'})} = 'classical' + args.K (6,1) double {mustBeNumeric, mustBeNonnegative} = 20e6*ones(6,1) + args.C (6,1) double {mustBeNumeric, mustBeNonnegative} = 2e1*ones(6,1) + args.k1 (6,1) double {mustBeNumeric} = 1e6*ones(6,1) + args.ke (6,1) double {mustBeNumeric} = 5e6*ones(6,1) + args.ka (6,1) double {mustBeNumeric} = 60e6*ones(6,1) + args.c1 (6,1) double {mustBeNumeric} = 10*ones(6,1) + args.F_gain (6,1) double {mustBeNumeric} = 1*ones(6,1) + args.me (6,1) double {mustBeNumeric} = 0.01*ones(6,1) + args.ma (6,1) double {mustBeNumeric} = 0.01*ones(6,1) + end + + if strcmp(args.type, 'classical') + stewart.actuators.type = 1; + elseif strcmp(args.type, 'amplified') + stewart.actuators.type = 2; + end + + stewart.actuators.K = args.K; + stewart.actuators.C = args.C; + + stewart.actuators.k1 = args.k1; + stewart.actuators.c1 = args.c1; + + stewart.actuators.ka = args.ka; + stewart.actuators.ke = args.ke; + + stewart.actuators.F_gain = args.F_gain; + + stewart.actuators.ma = args.ma; + stewart.actuators.me = args.me; diff --git a/matlab/src/inverseKinematics.m b/matlab/src/inverseKinematics.m new file mode 100644 index 0000000..ec319fe --- /dev/null +++ b/matlab/src/inverseKinematics.m @@ -0,0 +1,36 @@ + function [Li, dLi] = inverseKinematics(stewart, args) + % inverseKinematics - Compute the needed length of each strut to have the wanted position and orientation of {B} with respect to {A} + % + % Syntax: [stewart] = inverseKinematics(stewart) + % + % Inputs: + % - stewart - A structure with the following fields + % - geometry.Aa [3x6] - The positions ai expressed in {A} + % - geometry.Bb [3x6] - The positions bi expressed in {B} + % - geometry.l [6x1] - Length of each strut + % - args - Can have the following fields: + % - AP [3x1] - The wanted position of {B} with respect to {A} + % - ARB [3x3] - The rotation matrix that gives the wanted orientation of {B} with respect to {A} + % + % Outputs: + % - Li [6x1] - The 6 needed length of the struts in [m] to have the wanted pose of {B} w.r.t. {A} + % - dLi [6x1] - The 6 needed displacement of the struts from the initial position in [m] to have the wanted pose of {B} w.r.t. {A} + + arguments + stewart + args.AP (3,1) double {mustBeNumeric} = zeros(3,1) + args.ARB (3,3) double {mustBeNumeric} = eye(3) + end + + assert(isfield(stewart.geometry, 'Aa'), 'stewart.geometry should have attribute Aa') + Aa = stewart.geometry.Aa; + + assert(isfield(stewart.geometry, 'Bb'), 'stewart.geometry should have attribute Bb') + Bb = stewart.geometry.Bb; + + assert(isfield(stewart.geometry, 'l'), 'stewart.geometry should have attribute l') + l = stewart.geometry.l; + + Li = sqrt(args.AP'*args.AP + diag(Bb'*Bb) + diag(Aa'*Aa) - (2*args.AP'*Aa)' + (2*args.AP'*(args.ARB*Bb))' - diag(2*(args.ARB*Bb)'*Aa)); + + dLi = Li-l; diff --git a/matlab/ustation_simscape.slx b/matlab/ustation_simscape.slx index 83e90c6dc5aae52afd0cc612878c200bb39246f2..a43ec14df7b227f60d96538be017b43c20bcb598 100644 GIT binary patch delta 83502 zcmY&eLwF|8mQ3=;wr$%<$F}Y6*mnNd9iwC0wv&!++qRSGd2cb_Ebiv+PMxZYQ#Blk z7!V9!yN&=`)|DP`00IKS4M?nmrAWQf2Ot2u669qEnUO=UKQTz$GYX^BQ;WUPI>)?H zW@2nD?u98Up0@e+hUy`h=JxpqI+xtvBKO)cgI(ALf64 zUr*xmTXcgsxmiUW;g}_!LQCSsD@RIB4rlHwLtjWZK#n8#%^xw4o3sA5M4oj?#1XPo zQ&}SYoZ7MNTcJ()@tD3Jh_g|lq7py0S_pcVo}wn4LD8QKvKT`|BCqAv2h(`Psw=46 zmT>NLi#9SugetR$hbs1*RJw2(3O@UT;_9sGn7F+_>@gQ{8Fl+1hXS|m?aKBRLP-_? zo(gIJz)d_yAWfAu0KhiLBN+o4uF!cwAwGiOO-B>A(P$GjF%f`OaUE8JLh$0=z!0UL zl&)GgXhQpzIL?bD<5~>w+T%WpyPNH6q4YoCbA?HaywAB;AC{UP$JBrMLR_^;YVkfS zHVSXty6_2+$t}6g7Wp(<>xeVo^SzJMOMJ*1V8GJ$#C9`PJjfG_%_@o>0`wIOd>eTW zSrpJ8YEL3gwbW%0hOXf+;QR?Nvn4|6rA^*daunpF92On-8n;v0NU3yph``$1zHS`j zoo-SFS6UWZDN>ggyED7}rGV0nllG{#_tU5ZmtX5x?hV{nhG4L1Gbpng|9V~nmY9db z22_+C5JDchenlVOn6xR!q+5NUe4u@#mu01ttp~2GHXp5b3`LOyVx2l}{oH!*lk56! zOypMmwVxGOo--Jzhk6(5*}J=jfirkUb)m$ZaigSikr z8>Nk4#EQ|EI5i82s7k>z`Um7@Ogq(v6tHdRg$p@B=*#m@Z5nAUJ&!6 zs7U81@?s)D1EkHZ^@ZDM)ho*8!jjc);xJh+W#656hX{E+Y}k;v-it3hE6Hid0mDAB zwtGnZ!#o%l%Ww(Z@PC_({;yK#e~SdfrJPdczjcFv(EZzSwzPG%u}st_!bu%92EhO0 z{SU=KX86$OugDQTc`uQo+~O9J&Bz!W@hZy#PNGO>q3<6O^lIWJ!d!24AKlYCPcOTe zx1kX>H@M|00YckheQ(MG_pi6bpu(#!ee`_=p%^fOb#!Y~dU8i(={DqjG}-KOJi|~l zWjQlAw4!3u8Ow2*qx{9n67$n$VxGoI@zYro3cfANbbZ_l)wM9 zG#G5@iv8%2^QH{2bn|%I5Vl8F-S||=EweYXgay3+rHR)c*HxM{>wf?QU%z5V zJpWZ_w`q~h?85M3Sa)WLNdGg4ME@KQG-T*vFPxEGEijvzfKvIV{05Id2Xki**FAOaW9g*UdB-Vp}GJ4yQ$Z0#LUzH##6E10aKnEpQ- zXhlnG|6Be4u^~~Hhz2-mHNcD3Hz4RpY3er)tD|rG-G-^AX%YG_;WbO4sw&k5YG5^Vt*RG6z;EC-NgcJ zZUpL@J593*;G*(pm}T`pz4NK|LI_n~+6y46ac()WKC$9*9XQb(9e(g3zYrmJ{QiI- zt%wa;u|4$abHE~sxM}1c(Elfh$m#A%#%_@R&_M9#KN^(a5GEE7ze4;l3=^_R%p;)& zDk}~Uqlaui)8TIEp0uBm6UZ)Hj8aHgvv;GkuH(Y7`)AxQ%XTzRncl`b3nGSj+jqaH zs5b)6WeSd|<)I^m;K*dV(h5>daHf?G_?HtjB?j;bdh;y$B-%>Lm@x^f%KF|=_0TgL z3-YrIs-8K9Rw5XvuM&h#l=Sc_T9G7y9eo^FL_Poyxe*MFowkGQ{lCoBP?8JUGAvq4 zIn7oGg}q7vV3!06iRj<;RDEyvH1L70Qc?H7qNMbFL~e(^oz=;&Zd3I8n(k=sbS8@H_V8#~p`-(M8;z@ef)NuV}rmU_Nn$xqIsUSPIr|f|;f*;Zdjh z#&g*yjAm0QL`yeyVf_KKhW9{2e=%nEyuv*mLbotgVmS0mTa@z+ z^#615H$~#;Wa`aN09=C-*##J4q)@nbydDV1{4Wp?Opw%%UjS@irH`wg`ew&5NfCMs zaTXMeC9?D>Bm_9Pu!;zHVG$n^F+=_w@f^Y&F#;*r+~(#cv-SIzpZir8+x_%JC(%xb z^OLss(7n&Twl!XUIlVhx7(Nta(56OQszy+s5@Mb`z1)q=^Nk$!3sG}bXEWf%5b5D} zg5$9!JG=y(YFr9%#zA@`)5%pC==ZzLyWZxBGW7Pcyf7gF6?V0bP__gK>CCGTe)fmn zLJrD=qv9*;svqgc9N+6n$j5c95lh%ys08yq3I~J$L50|)i{j3DYx^1SXA`Gwv-58H zhn7!A32#(2)oyOKB?Q$`Hy8t0fRr)6LuZH>X+x~EW>FEasLRJExu^)s{!{R~?oTH| zP)^ap=^`#{8=CbI!s={|n0uO-YvbIMfnlL#ZDHBrOlYzB;+PWK)zz^Slg=$%&%Njk z%Jp_$U>`r~1vh6T?!39;r2t2EJ}kv1s9|Ip5V9Eg1x`zPL`(s^+PtdD88zhw^D}5OG#pxvZX75neC?!ldSzvYMeS<5z?dLtLtI# z2)e}nc>--p!qpam9_~M|2^vL+_jlM2vMZ}@% z@jX%ZLPkpgmyICoz%*gn6Qz51W$&nMXZvMIk17Xn-<9GQ(R4t3&8Xf!I<;8Xo|S6s ztv1nj?r2W$3r2uHfGk7r*Zrw9Svrx;xeHVIoL2=61@(FmE5b(dOt887Hb6kb3{#Wh zsJl9z;d$%0Jxs9u79kG<#@tzsH2Xup$C4@1p4KFQXbFK{;m!#lKREAC{KYg zAr?M%u*ycCrDO6ZFEVhpWCi7>FR!~ZKU4`=A7<7V9epX=%0o#>+0fz4FcKb4+>|+_ zHz3*A+5(uwJd{@xDCmFl5_ms;HlMlG-gjjzOVPE;l3jsAH2LYS;#7c|OV-x*zG67R zNQEZQ^E)MpKut$O!(>VHD_g?Gt4y?HRyJ6f;`P%OR^T=tg@zR8^BE`aTvrvZq{$8# zb+_t-a#GF|*jT*Db3JS#8yQr{o8?s8PW){b0>-B3*rQr0TB48a7*ZL;*3=i4AKX+( zO_;uWXk8zfJ(Zu<=_k)bnKG9}b)Z<$_vJb&AT^^7u6nY1c^33XO;Bebr zt~wJdH8rE^#i~W22&+bDLr`Z!fR+vD_h|JTi&`?P=bYOaIR^XM*a&H5kGrd_1`N%- z?Q@zwJryB;uF#-2BgMamC8*?NYtR}WO2&A*io0?f`s2T6Qawe11p7BxdnsI@EIv3pw@>(Y3hYt;ohp%2G6 zH*dF@&7eE)9JBx%axZ5DER zEdrY7)cbE)@FLUTkg-`0T2m^pr=?luTL#5C>9Gr-iqf(7nfr&Pq!n%2aweO0cU#kh zK8yxm-ee_t0Y~Aoj?S@_O%x3k)u~;bM^p&@W|upO+Y!MfD06uO3Xs}*X6v;PCr-?e z;=fM9c4T|!&!;95I`3Lt2-X}*qDh?L>ER)C_J$bMUbmk7yK8%+F(CyQ?^tD=Yyj4$ zwP|=+TfeSgEDG1Z+?{@RaZ%a-mKTTI_SQlrPe-$b;?<-OXn8v=83{k=VvS#C+#FUh zO-S@4T@{lu!$gL1%*9Cq(5C%+UqzBb*d22+RH-~}sedKC^VI#Mpabo}@qE-9_KOerP=D>qe!rG~dI%jJ z4(8)yblZnT5-iu42kkpuaO|WUJWHqNOVXb4F1vX*Hdas9lX$TN<$R?uIQUlwk)S0M z`3dU`=DwSNik5~(`*OOKf`)=aea&GuvDeV#hkC(@;jyQqjljH8jSC440wwX6Y1ewk zS;Xa97Npa4_9QcKDwN2Xq0c)JvCAcvNEH_c=g}5lJCPy}BAu7ysf?*CB>z@hi}q&J zvu?+M8&kl~A(7R;T3=19= z3m3=EA#uX5(%p;-n)cwu(bciRR{J4M~QBx6*)YBWf9zdBq-TtyD6tl3r zAaCU}uiOHU&pY z#rQ@@L?P?FT_4-;u8^2DSOlC*iUt_>6t#4s1$0-0L86BMry2VE8R@hYy^Dj zFFR16*yl*0lgSv3;le$?I_=9;6l|0?$X$V|ir4EliI$IVGDjh-wN$bm2b`;DX>eAq zUPX2Fk<3XQCQ3-hov1Ur*^s7ml?uB_Cx-zj330e)boAHaPi2HQ^T40%#KX1Qot~my z^L0Zx0!R?Un#WnEYU*1p!wZK8x4=8Xx0>qU)j}0a_86yp}OOpZF^M+Mz&#YAqFpt`9P+ zU0VI?c&WG^I;W6V3X7MLBO^0=+Y(wz0FrLL>R72$BLVveet{Jac{^XpttX8BNt62% zi2rmRgw(r70oyfB@bP7~gGa!{h2N_-+)@Gqj*iaM5;K7A4#KZ0Sh}57Iyg+R8|UWq zwnbp6!!xT7C9>1bVMka-H;tWf*zA!iUqCOTRgu8MxR-?w?FuJ9qyQr>A#n2!Uvgg)*AN5 zykcYZ!{2^QEF-TeTyS!$MI|7rNj9!rK2c{PFtsvCuv+`Poo#k-AsgwkfH#{oY^GN9@9VP-7fO&JNx|0oa#!zIs-xUc+tD z>Y_i=A2!dT?srur;_PdX`$)0xb%TNOjy0H1lQN1ixfji_Fz=O#cac zg)A$Sa2|c>eU3Jw_YVHZ9}&Fc^AqPaz7ISfAvUu4W9vM`oRVrd^X zDd_TwiHViD!Cit?zZ)(N-#dfa^>(u8tBUh2OFOL6T$24#q2Wz+^15qSY5e` z5XXM%B59w6wA^)TB&5bu5O8i;j#q#`H<9$wJc@9c_`CZ)xPo`X-`ZPEed&mR?y;!wlarI#JFc?;tV2xEHXuJR zC7@APPbZ!3uG_@c&N2WE?Ps7VWRm*nZAw-O=i@O%3=uNF^W;1@&>!iEfNS<&?pQ~7e?>8tD0&ecV^}#Z^!YU>%vHAGs_Yer;0j^W)Fl8Zen?zEIHxt7|%c5&*3^*X1goh7RI!vg1NUNoQS)@08y=fE-^SA-POv9)?i0=VF~z&hkyC`W(;{ig{%o^ zB`>(L9A}&Ya3l_SMD>%b@5ltR_QOahXJQIBVGjc4M+>(xIpP3FV~NeGwT9XAW0_M1 zn-_1JP7EY6xbmiKxu<9`5g>v5i|!S}Q7!I5JwYDKws&H}reYtFeSUv90)Fc0;5!Z6 zdYS2K1esG-(7E$MrK0OZr(SY+&;=j^o!~2~JdpswMky5>OhYE0pid?{>}*Ff zr=B0;h^VB98Y>1d$(MA>E^c>UPnEK7395+1T)MB{F@Ny?)+_5@TUf%|>KT4t_z4LI z&j&?NK~HY-_7O~cDFTe%l65^cPSEp+&sHlrxVv4ZWl39&Hh z9{fAwfXu;@_iuRgb=zm9FC+!o*cQEaY$!wo>;O_ ze7>`K3a7ekWOO;;*2OeXB8&XQf7Qd80saF9&vB*S)EK8ZN70IwVFv>~g&W@}JdIs+ zmhs+W)z2lO>_M=Xkvu^al9rll(sS)mL-~^h$kTLA>fDoA|X&|kjPrJB1sX@osTQ`hMhwi7*+ zCi*@7+`@EgAx6`&&vWSFGIB|P|G<8nB{+55^h0oV;bwBnPX;+xRGlYnCaA6X!=+FU zIGwYX_9Tc|CU5$>Z2n!p+*RY1D9+2r=leE^M8#|n%=ptfll~i@SV#4pw#bYprX{j^sp8C0>{E9=viT z?O3PFrzby4BVHhs_VjA@Z+K=WKkJIVn=*L24A@8kB?$5E^ga8jm{_rv;WAtYFoOp` zae90VHR=+_f&5U+mP2H>wqCiP9U-!|9~I6=MBL_|A9|njkTxaEJv)WW^%O8d13GAD zcjfl2l90RuZ$}W4P&WK8de2;4AlSApW0dfbPZlixRJ;B{Xoj_WoCZh^fGm~OUK=GB#?In0>m1L8%#}W;IWNDjO2=H z9pc)mFJ06Rkf2IH#*xUX4RDc@Yw=gHz-9E1UMw_Zr-hA^zZym3KQ*rcVx*9T>J^ry zd#di!o^lBE7To1jnTf4ce;WILY7vb!@TECnPA$MCJwVI_s`O$WX$a~o!BDCwTy%@v zOFpIgE+W?aNa(KA+yp6gd8l>Gf+NrSz3Gj&;fYik;aeI0eoKGyi_hOgw7aL6vErks zyc{WLPEvGdLZJhp`dIJ=czBo{Lm$YT@H-bC6ih60Jz}ziXYAdnCTQLGRr+-uX7B6E zPd%j-(l&d4?vD<}?2b4`c6cQDX{B(~LWbjs`O?Au1 zn;Rl%`=@|_$sgOkQtDjRp@|Okk0qfe{%pMNP$U*1gsf?Zc_9}*AWvC_`jt<+^?@TV z)`#>;T2SWp+mDlTBvHoO=r7vXlWCBhWA3hLhg2X{2&nH(=a_^FD#pvA(IsocnG?pT z`!AuUW?@%2socK&y}j(|)FVrbGtR?Ob8UDXS*cv`%{V~ zKV-K4`f2F5^ySRqXy+OVejPC+$B|+FJ|@A(#e3mL#@*8f08x2xMRW^$z85<9_^#v> z5#&q-+qu_}V@-qgTpv#{@P!KyF&9cHq?8=tw3O-b@j+k(*xn*+;VAjD7)fK^pMWqu zYsL_L!(5$tjf+beZUHID^$nF4Ef!#1SP(|$b|fm5o7^hDUZMX;dn-_Lq&+f_ii#Qv zYdE&VWx^7s0#ko*XO)S8q5M(S{3MdI^)9aTtSr39l@`WS9##*$*7)fM3VPx%PJ)(x zT2Fc$le^1lCDD@p;)iE}S+YhmAJec8lYyFh=ut%_7@%8+EE2-BDs^`A3&kB=3PV`9 zZ)&?ItNmhz!cWLFB;7s5h!Qm8d)oWTp09w6J1oEs1nB%Qkcrhd8o`t?J3Rv`DOp!a zOocQIZpaHkly?LmQH8)J&(dZs$k7nWEl>72fA*zc5clo_ma1b5V1Via7>N^<9qmT> zRDo<>itt8r=pSyx#=K7NBL6- z4Hew)Kr`8Tbu*Kw;d*){CAeD>-mj&qX~mRpu~X2lkKp*5 ztIduwfVFz08gLxY=7I{YcfG{%RYpNOHva7o%oIRA#}Q%ywVg9p&f|*XSn<-qQQi5>En#D>Esd=rOckOwe95i{qCFlp0`uj1R!=7H*UZC2r~E zu!HqQ-7Wj0isgV{Y|uQ{cx4;>E)XkvLR8S#8Y? z+%SluvCn*6zY}nmW%gsn?!^CXeokcEYIK`_m(KzX#;m|SLT#ihgOprkjJ!+@A~B{G zDOua_d_Z$4#iSz2`C!4K0YO46l-_IaOy5HZCNf&q?B_(M-S`vDy(m{8%=s2fu7i~c zL>S4x0t53eU^|<1U;qvuZ~j{k1ilUc3`OVu#miEc*1|dLuR!=awdeL)dS{t*^TDbf z@vAN#6R(H(B-}_Rr}SW>dX;*iY^NFb(1gvRRJAiMIXNqKe$F0jt7gzmfpt4K9(OR` z_c7ExL?+*#i6rsP23qwl)+McW^Obq()sH8=mn!`!qS^bNbU=4AH=nkR9e1CsW5j{X{yG=`|&hq03F%xPoTSLMZ}v60zp^?9!s z7xdtATG_lFmu|=-y;svg4{V7~y}xJWvG?Nc&E)u*f=kw{$5YMe?&)+CxFrJBa;iw$ z%v|VkFp1tXUTwU&OGI&BmM$q2Rb0;c465nZ`a`^K-h)i$((}dUaYVkQFUZE;e%ecx zUI(7kmgq=H#h9vjmo#YP-&FHit$%>xf}h{rxJ(pNLa#81if(*-pn}Oi7pQD1n|k4U z3A_LTq`OQbV23uW|&0`hm?*Lc<6BB1+zT~cjc2&#lJ^GOf z9e^BVG=jie`C$j>#Z}gucq9*~8Ey=U-cGOoYYA7P!v$s`fGfCGUKFK1+3EeUl( zI_XCh>VVf0#Etx+&>s=2`1z-?)Q;$QJ#pHP*k1q|Pf<=v{!s4__}B>?KF!*AMJ_M6 z@zQS}gtGNt*vhE2WVZq;nh9tRUApqR!@XqU&Yw(cVo|{rQ2b5vbG4bV1u^c=bU(ebEZUkfJ_`!hqDnK}ci>LU-o)DO*v7mt5&M=3Hr>I<1b&a z(o$7lMfHct2{*F_ERY6I+QlSiRht$$Xd@mcY6`r=tAS^gQgghIU(X4NfLJP5tKQV- zsoi@{e75zk*?PyeZow2idQ+h34#`G=VJMlKH6=6k7}2uDgSscc>`x1Q zXNwyjbIvPbes182T~KL=cOxUY6fsyLyeQZSerPv^#TR!F=(;ip zM`A|xI0Hz4eK-?5q>Xo%VoLOhV{}H)LgiQ46^l+Yc?XnHxoQg^YYCJ7z^@OSX+R%% zTKf@*O~1*#pO{Z!WqZ0#-4L?u@QjiEC$Xy`C`1$<5!37CTs><+ech-rWiS``U(3_h zSxPfAXfH2z))?H+>qaf#qfVm!rj*K!!b$Zk zGrEFJ@Kj=q7&n`N(mQ5mJ}PNeE=F!XzP`fmceJ#9qL{2g>74C!OzHj?wN!v?)&e46 z>m2ls;GA%;DWUu4M;p^tROg_itOzCTINhse*U!xfmAv7{yf0xL#m&`m?Q5fP^$*6H zW;fT~U}2L;-)decXG?hLJ^JIKe zlHXB%7Ai~jX$SR)Tl}UWs6@RW0dK?UG|9fNVAs1|i^J6(*Vu)t1xkfWrR>(u#eTti z^&Aal377*B$3;g*9?OFMR7~jif~z45!G>NZNtVe1?y9+Ub9 zKn@wy)`|!xdkV%BGZ7veT zvxgdmHgKF`2vtqi>y(phe^gpR5up-7XfJL!{Z^sieYc+Rc~^JUzD`4f!;u}+w~k8h zQ+e2W#MQPy(ABb@&wJ?~>*a?!@mKcY(+C1$Ng%0&oE1MYoJ$QDsI>_!k0xZyrKbAz zQP-oqQ1StDwDwtNRr-r$Xt_PVZ7f26?j0X*BHg%3H?yYR6%DzN#*FmZp?6c+XeSKi z<&&=hvue`e%Pwd>WslPQN$F{H<=mu8XCep%@D`E~qoyE_IhB>5g!luy68*l}*gn8)whgeo<39s?;$>X=R7MKxvM0Xra7|A)sE^SL zHUC%Pkh-%)YKl^3aFrCdV9eCQ>dXgf$6wlbp>c)V)^}6;KB<}g#^;xk_oMYNNkp?B ze#^TbWlZCBe`4tf-L)awemfy3EF=iAxz}w^I;NxLLlcDGC}lDNIW9A4hC_?|jzr2( zT*AE${;sbP#;C~SoHaspNgM%Xt$3de{MX}6ghnj{v@N~Gh-q**QR{eA#O(bJB@P@v zcnZvO-b_u}Q6om@nNHT4^>82UZYK+jR3M?O(2((hS(~)uHZ*tL!0!G`Mc%MVdKmCc-WHG6ZYtOneA>0) zwk4b?kRA5)=}rg5pJrDis@cyuR%3aVH$m~^Fd+rr&+($O;rg(oyh2q^o(#XqbU z_HRg;H>q#~G=N%4(oVDfUF%0~@fx#H?joA#O7R0tmHCroyfgQwUC#3(C;}l37Q9K! zJM7aMIJchwlHqrD)uyFIo>R6>|4~8;p%un-|LDX-W)Lj}$2F%**B$8I6sV*>Ji_Bo zL|i4K;QWh6{It7qHmEF{S97P;EsA{WEoPe|VQLLg15Z|goG42p$V zuDx`5LJG1h^#=5tNaE04x`ukip#xzneRv!*3M94gGl*$vt6UaO9Di(<8!xP#78>T% zRmAiefz7ny#aASAAs?p%m!keF&SibcDSlx=DTPrxduMnv1>y(g-@}n~_kiTdcQ+s8 za>nEGZ#i<_wCIhkzxZ>VB=S`oI}1xp;Db>f4=362@v~H*9hxNeMEo8OuyT|8ePQ7b z>5YbaA8su$D$xX9*EH@(piI_=G-PzTs{P9cwwiU!m4QoT~nsAbDy?4Yql{veBF`T^X!5; z^cJGe*BIUPEpwSgDu-af(?!|9QvD;(zyOq?r&~(=10_z$?0vXmZYcOCU(OJ0(QNPn zU;>ulIWQsMZ`mH{n;uXRHr96Yb4ZFh3kwS3WB>=i@R0xoI7~q!5;-kpAog5ZFU+Y&o^K3 z7@w1K$vr;#W~cT<7z0)Emn^N_kB-s@fyKMgx5;&mIz4SdKyuc1xYKe-{Y;acvvSYP zFU2MGk)IkhO6FZeeq&P5H~_;&-BTgjw#*vSJ{oHOu%M9fW{|GC3lw+5m_m~y{k%dx zOG`_}3d_Esnl*BrFTJ@6TESVA;bD zjudV%9ByRGTnu#dB&?xOY6ac>fUEVzmR#SzL)BXCE62+}eJS}R{yF&tLLEQ%;@=!j z7H0(fp|7Pt=F^EtIrl;a+AoxVG zrd*`r(`mwQ;P8i*42?TcO@7|#M(e_d9|7zN6ah^91B3y@X;^+YA4S%Gfy%^;qx>#Q zq6fd`1W!1JKHikF;T(oPEmc}b{X&Udx8G?6=PtOO`PU7-l&u00$VrvF!06?my{|&~ zn*xzyT?Rp*xAIVi#?|1;%28h=1wKEiog^Y@qS8A3!I03_4BX3$0%d4GwEN%R)cVAQ zL?K}M3kF)>+P6St^?3F%fJ>;+v5?Md_>WEaG)W_Pw6+jIUJ!GF&lg7GFKg{iV6^4J zzZFGz^p5;Yqg`gT(Zq3Lnp))7D6wuYRapD?ItI7(HooRw(n4US#35!PLN zTJtoIH6kz&ENtcBn*84%2aal_FNnLjMj=>5d7r{RMG?tx+mc(ic&7>bLhr1%%eh4V z!V8J$g-|-iqb%AFc+0+sv>#u0->ZMipX`dI0?suu?CwK)-ua`I^RR27Dt zaa3%E17s}BuThpEpH)5k!8cTY$Eh!Ka*0%Bh4D{ol5}Xu-q^sV`q<|rL zI4pu{G)3Bo-d|A+Id*fN#Ew^k8EH>*fc+{>LJzv!cj0h{i_)ulajZQsMr!@*mKxIV z)ayR#6!~2F;ur8Kt#Y}0E?Ivb4(!m0{n1P-;e@0(JZ2EPupDE;$^Ie_7XZ}k2tNNa=;l1guAN-PblJE7hG*DH0^X`S#$v^ z?<4`Y>Qwo=J*`ejlwOh-uEyX^JHbkPM^&EYq@i25_V81GYjFpbYwD4K+;f^JeVqQRu6a;=)atli!%OaUB72HesVKu^iwNTJj7aHT`AZvw#-G76Cs@a>{^ zg2MF(CX}b!0`KJeiP+>xQtHOs5HaM8k-@)vf4I52rp02;$KPv{Y%BQKvmWGk0g1Ar zqvd+fRfJ0Bc=5Gr#Eg&ms{ch8MBAQ0-s!r5zEY7;U3@*Yam8ac9Y1JZ9@kr3iaZd( zT+mS!d@b0Z*QSgq`_n2t!{AKB-;COz6y!SjJ5j5xJD;e~tf0$hMEJ64433d<&wh1w z<2B2FqOin?jnU-qf;5sC!ptc$Cg?yqBr-s|8Jv%n_x%=m^^*k!2XoDzD+U~_ZTWEl zk41EtIcVX}D8r4IjYQ}KV7?X$^D0BX?-Zwkt?j=?KOarv-A7zsY$qj(>^{_&{j((E z$UAF@aeTreF~{w9AH@n@&AJ4D0z#pE87u#Mrx`btL9iK?Zo{0`yva4AEHK2Y zPOm(Fqlm=!E;nJ|n{yhr-S7czut>S4@3Ar7Z44@gwSR z90tZ6R%(ptwZ`9>G zT;tuAD353{vtz%Ys8}XPk+M0Hvf^T((v`7tgI~X@53zgAmVc$v5w8Q>Z^P60mhp+=QIXv6(X8oqN1dxS_E9KEwLv*ors z*Wc~!-SXq+seyQH8#GinX?l$egr1}dC%kD1Ak{-)$U(z zA&ZhfFq#q&0yDU5Df18oBq0U~X`w*CSERboLltnl>gVg)cj;)=(OQox z=%oT=-Atg}oi^Qwfl?32t-CyWD@r;?9dt)Dub6s>J?p z^t1=b$w5M5pj~C<P6l>3J7nWbGT5;EX{^( zY;M223S#Jrg?n|;3k05pe6Jr0T;y)<8G7pBbWK#3eP^zhU?H6&&$-WpSNDvg!^Wxf z&NaxaZOfYE^W(Xuj~+Vy7=2}rA|oW#)bnk_)~#nN|s<%cXxMI&kDaqt)ruE z@9@Ra7c+3f{8zA>{DW22nt!QxPOm+i;Q9g4EDGWsWN;I($J1JqUNvH1%pO08A09q> zQ82AFF3`7y#ReP|2@a|RXQUMMI^(

tMIuAKjqpsYsX?deG>mM6rE)N-B=K;qoSae z!WqbGv={Q3_rc}e&u?nOSh0NM1j$xSr*?z^zu7Trg-b6(OPh&!6~92*LG_zU6(V~d zBZWNQJSv#k(a{kbWYNMUjXAW($U^O^7^mK&j`9jU9U zn=Cm8?-R?zvIzCu)|(ItQ~7%A1XRT#zwU`qM?I)jIYVjfbr~Xgn};>RGaJn)ur_9F zvA{RuBY7L_JDFtSH_ci@=HFDwl&D6U4l7$CqlDlfjar?L^|7Cy@7%bw?{iw7pA ztv-oHw6}Xj45xKL)haXL^6TwC+-rEL2D&~^W4fn?5fdQLda&yIfUs0`osIx)E&G;1eHJAjR z<>6#6FUBt=f_JY|v2B?kKiEa1=K=dbymAYh4b;ZW4(Q9+qnxcmV2DWXqt@VTVSh`U zUh47d63RXGKzEB3F?*ZDfbENzUot&WG<$kW7pY7A?P@l|oXt}=AU3ogA#RITwQ2q3 z>}5K{HKAe1X~FNiS{DTW%4S_m7QbIx-Xa>5${hThwrcntkhH6_5+lpq_#0T*b(N%T zVBn`I@~w1=T>2LYD@U$FaLSdXh}(}i>UahYV$4AxPHfxl9z+XdK!Y5=Rt@j>a}m=F zb-KNQglMd%jiSc0Ej|eu86Swn6&MGoExmJm7;w*97O@ZD;sjUO5F8x*FJxcBdq4$p zWDY_>u~Qoj6|!{0{DVkocd4{@gyde?yc4b9_VJrkV4aGhUta8J} z@WQXP&M=*Uh~2vXJg5O7fV5I=5Td%A?B&9a;gaXiXx>)XN8msY5sE8B&=wmWhH43k zpJ}MyGb<}>1Q3m%DHFFZ%e1=aYqqJvy_LH4S+mK*K+>P@kt&sHMgd=6rIDdCV+(4g zk(POZ--rovKLx_2EBtA9{f`AqF3DVA!yTo$bwGOqkQXME@BxU? zNY#^ZkYVHkg&b8^+%$adHp2;%GchmyDan<`y^xK9q>f6FEmm*wLr;UE};yH7$NaiE^}27iP^Wg|#$HgwKT+ zyZh+M0A;!J%cOIexr8QOHWW-kgY#caqQLlomHkfzFK447uogmX#C>7Bx=L|ZKmV?; z>^abRVIYritPnM&4s(=*Cd)VM`c|6dL-kE@cKq-v6<`hTa*05SRz$ofY1aj3<6m-C z&|3HM@^S_yx2ftr*u{sC8y`_+>}$Z~Pw8}+Tovi(Vje$gj+thwLZAC8f^Nm_9lrMT zp&8*0xE#!{-ikq?326|1CYEbOa};MV&i5gAI$%9hr~Oeznc!EIW&OzIXWPpYyYX|b z=0ukS3~woH*s$rrcbTns)3Mg;{k3@8o;`+p^Y<%<|NQ{F8ftP(MY$ll?_#9-pw2f_ z&Q-m}H^1Wip$(1S*d(pOZ5xF9*+*G88Cd*OfBv;wgRuh|?2!cj(N|c);s)pli>Cqp zIB;dn2|=f`LL>d~bzP=;d`;ajUG2EWaIU`o5Ag{Coy)^TPVjjCE7vEoxk?4Oj81;?#*#yRAnsB9bOc{^< zlelf;9c3U#-{-RiEcnTUSROZ-!qi94CGcCrk!F4&aV9IO@qv$72cls%@Qj*nc@M^WQxJA%Yy(TO)Tlu&I*wzOgH z;oTtQt!;K>s!R`M^rdE;Y$-~`<@VvDOUkMXo)?v!OazSxE$kRF*LgKb6o|EN zm~B+Jwx>KWY6l2dlArUQ<~0k_@OffKiMS9OKlIJ5jHD?;A=bt|V~0^Po*(ThWJfz+ z{SiGKEB$FEuB8dRb3+n+d|=snn#9lAOoAl@ab&F%iZ51_8aWq(lcL;OPrfMJ;Zyyw zjFL|4D6{SZOG1O9`tO*Q*Vvwa1U5uO3@~5iZ};312cz`%jOwIC$Dah12}K`V;u~{ff|wlk8#@xZ#S>nYOsE**x7X)z}wWPrUeqS zfw3Z@C4ErJkETNa@g4iZ-Y?CcUP{(PD0c|_B1b0au{X#Nk|$8Hb<)zn{xn&#)Y!fw z)#25T>I&Dpw)=oyJ>)wTl4>sb(bK#|$t~q(e6arkoj_v085Am=;3k6m^AYWVWixNT z5y|U5hyZ<|XQ4{NZB8j0W^fnXT-JXOk4gQ&+FzPO>12ty`Tg-|!RM&^c}l`c-gnW( ziDWuWO7Gstf&TD6Ctr=ZT`YD%zu(+~Gtx+m-pTtVMtE$im?FGzojy*&ne{fyb6BdX zIOBrM0TQ`hqlk8u@ql8t==HSUm{kzK<}MR^xyEc%00e)JPTytur9$RFx$T zI3nn9dXC2SD#>%GhL)x({#(3=TRD^-;jNY_P6BP$Uw*Hc=!!*`0M-)P+C!kKDyK$T zKD#tPh4r&1rG2qX&GDcCfox!k>DHm@?7YB7jJv6=9q3IW(}@=p>MUlDe*CgBb$w#w zb`rp>Y9X4-lr&Iy<&g(roG8NJ(%4#jdZrdY}x0B4;*fOWhG1QetT-Y&2T1^ zEQ&yQ&&T=Rf&EMtN%OvX2m8Bc`{Xm~^AyoyN)eoenVUOUsO1YCE%uiJn>jhfm%C`K zo$`wu+Ndws{%)aCdy%@@G+@IBG+3Co>&jY6m1$6JhCrrgka4=~D`Jp`>w*^TH?yB8vn$U45hEpQu3Va!ph&YN8+ zW}$beFq5Z=$f%+Q)ce?LXtxlH2{uuc_6)p)jI<7|SmsPBLFrPrOz6%qcSx zh8j%woFDW?L|2&bwK%Qag^7<=15QMEOQ z{DuoLV5914u)SWg)6!krRee{CzYkH{p_T47Z+ zwXgJfYn($@yk39A-B82QM&qb#$h`oTrONZ zDIRx^H%8KugerbHImEN0u@Q@>F*}!1yK*YT2t0`B?B0KKE_XxkB1z%SyB9NrLr0tX zt4B?r8XeGJyZ3x1CgN~#V4v~))U>Zsd>@+ujRo9;AS4%5oCA?8yQ>+I z=`Sm-|1E5?7g>M3OB#vn>%Jc^6%{{oWZzPU1KN8gD?c-BZAya!f@(4_%;!Hnkht3u zBOFb5I)8r%2Uuqt@W1ZEy4*=xXG@l1LU=dB|BnwhDu-qWg~iSz>nObC@`CCAH=B$O zs~SuSF|7v<(u-Q8s~TxV4d+myM#3NSwl1~Lg9i_wXJ*5Q*;D`iy9G*-a)831>n104 zA0G{>yR0NR>w4v1Y}eug?++9|flM^$pT_Nf?|*-?K2?edNKB+84VN9Y;;W>LMRpo+ z_2ozshqb-!D4p1XHhcB;sq;1SCL)xi7x7=%XW>*k1Xx#2M90NJ4>NugU->G4*k^*y z*Z%k6B}-)qg{}03bf)~r3~5;MB^3P9UW>Ue*r1|6Eec+x#B6BAl4E&^z0FY3l- zXL=z$_dqP7F{qjg&-s}+5g~VvMvcqF_^($E^amGnZ2ru9ZZ=m4#n| zD-NPFJI=q!xKe9c9>ij{g$!B=$reR^naq@AU|@i@oM1K1JNiBSNaP@u;;LGjb^Vd% z9V#JoaY;$ZM{@KCHD~5Dr9d1UocR!@WW%=5d-*Rb3u{{7@SKN(!5sHEgoM5vZH#}E z0qb;^kT6e}5*{rifvsmf9zi7>D$?k&+Ls3TWFI6F3#ObR`V>q|9z(+)fh6VIRq$vX z8E~nNxw(0DH?P%bF%AMWTML>+Ak=U_yiDu;@+b_5vDt+M|CYHQbG8~Xx@r-FgBsJ` zH=dW5m$uH%9ael=&hp^$@Sjgtf%Si%wCkWcTp!9~nUA(4A|q1(&fTnxjGv#M;gBL# z)DfQZ6kMm77YBkY5_}i^y^fez*3C_*p`qbL!SMPWz?He$)t;*|a-2#%bB;n?ot?C- ztYP4O|9%f!&vW@vY|Gp%P}L@{U$dr#A(67xN@GBgzwS*ghtrC})$D*dD{`4fS(b7US5jn`1+n4!d zZf-7Lry_K5(PX=7;m&ufF}1XfoB1$K^MP--NjP*3*9UW;I&VTxP``P8-xgRrC+K6_ z+uP{q=v-#MNcpTrfB2xFtqy-=;j3pU*XLM>fIGtJWsBc!Xky->?4)v@lmK_WzP=u{ z`p%NmCnIe^_e+(I>3I<804gSJD;mst$j86GRWdVU%#aOF zH|~g-wC`p|$H17|*@?``%3^VZM{j)Pk^gB@@&fYfPZ-&Valu?SULSuI0oA`&lXukI zu+RSTJG6bOQ)&Iw(2y3mA<*I3jg7FZEGFWxOhwGL9DKd6W&_-Ao*()$b!9W)Dk>_# zyMd9pxVX%&ttsSb7C^hAz-F+${Qh1!Nl5P4vxaOd>m zVqt45e8}RtdM&c^_Md+-^}>)Q!yi*qRIyzFV^-}J6|c(1NFSQv0f&tS%*|p+2Q}-n zg4bqdcd4j)mU|K`rJr*k)Lw!<6)G83Z13!-04I=^mgcxM9{2g->yN814Jxgv-j0{k ziHIciXUGkd7|S&`H$zW8~*l(z!3aHu9Fg$8(C7*vCX9*h9c zl~?r7jg$hpN%4R3_3OWYuE2JOv<&tJRK(`i*0kxrjDl!*$l#d6rJNP3W#CycTHY1Q zl*d8>&p~BL_}c7ox!18dRa-e)4jf~tY4=AS8zFT)US{QgVu(&L?>BD!{!iBD6z`Gp zR9|uQSOS_14JW?8-JGb53sA=KX%ad?$b@eC}+HK-~LjUHK3!?w>z@Yy~Ilfa6`vz?ue44RVqoYoKewrm?3`ul8@&dAdVSbU`b9b$-+`F+maA1ujP*?8_pk zMSi{~dnkV|FAwm!_)legTpaXoKy-F?{xIP&DjNf?f#KsossNx1OOwh8G9DAGl9H0= zF~4y2Y8*q}zsKXyuS2%XF~1{YaD=XzbrjMrHbeo*b+|E7q*$4hke~#7qM)E45fRac zn)hEOWu&DGn?Ss{9`x`l$jfJMt14!Ku7CUs(2sxCNDB(T9dD#DI)m1Di1;cl&d#7s z22E!HtxOy}Y3Z+cG700B`(+O_AnehVF;c%Me=}fVrS47#7GUmolCYe;J&(1u_2SBk z)=SEekdShlnd{sGOSPLsq(=QhN2GDtn0a5SM9x7NU&TykHuQ)&Bsqd^Q^?xd+U9f< ziEe*D8Gg7qc2HCKOe3kF@8+n;o7?l;5&EZ5z~uOJ8*F#bcqDj-l}0U? zX1&Qh^KD@YPo6kFH7GWe$ms?N__22D&A@**J%eHdKePdD0ub+4l5o7k%I~Se^Pdym z4h{~V#k{>r!sa7I&ylfADj#b+=C~ayjB{(OCccLk7jx-*?8&I9t1JEDw6aJM^S-|Q zsDg=+vDAJ^adK*^sOHJRau1k#Ao3cjwvP;Qerv9F$8)YsInOY#vxmnUczyOoyLEq; zjI68vWE%Ge2uxd{B&fo~X3&rbI0%3!vawN2Utgb6&^};y*A@hkqLUNf+1Xj5fSn(h zPXI%2Cabu?suxmyQ;20u6m-B0YikCrLMP zrz$BWrFY;DKnx$B^Vs`Exj7u5A5echz!tyrc;7}To3p%h&DeUwfC^dhb3JZ)M zVEqN$kJ+4OJoy=8LqIq!EH6VG3P2gQIbBZyFnh!~>B9$*_p`?nHk@!JZ6@p-;k$S5 zj#k;x$1*;J9$$s_iJpAo^8N6ED1uT@a%1>^v~u0yRKNY7hHphizLF84P-MkH)>B5p zA(a`KQMPR2c(V6AgpjOIB+7q|jO-OMGO|0_B>SA_efPbt=enNj`u+LqFP-tZKj*&R z@7K6L@Av&?ZEbCGdu`g?(-WQH02G08_u<#qOsB&FUccs#jf(?ZKQAHi%nXlh`}JO-*V$HIX#V^UMG1_rD!4VK%hli@7lkrXGH|F*WG zIdP(L(iY?jEe=O2=)&z1av^dX?aC%rF((Fw{q01V9|8PhQ!o!e{z?BHG6SX#Mkjc{ ztc;G1zSVzo{=xV4O`PdGjsyy-0J4xK0?M{x`B>dNyL_9!Ct8?EYz-8epdY-Y`NUwo*CKCh<+gf6{ zb~e&U9eXRa-K70)l92URexQKnHas7b=)>rRMrv9{#-Q9>OEG_+(5B5Fz0>&{($doI zgzUt8A?EGfg(B2eLMBJt&g3gjOz3C9*eFBRph-JSL3K_}E**GbV}GN&#F=oLxZNx# zV)mKJhqO20MBMiPOl(mVtZ4*-7<%`B668NA8R5o|<1=^9zoQoC{+2`92xMZUN-s@9&THV9|5j5B3x4z{Au*ekWNl zJ$ZL>O^f%J>~RHOy6;$V+uPeyvq`r^$q`#1m$6l@OAM+TA6^}1~mjP~~ zF7yD@HyOy+a$X)yLKRLR1{lf>#)1L^P0PONl~|latr2Ih047=N{vx2rsokFylqT(O zRBwL0cOf#MrA2wrRVk8H@8z>RWf`yEGaX4+3L9nZ$E5>dG+?LVVH*a|!$}aJB@cT! zzprn(LOy>~*VORY9JpXI7$3aXZ*6OPTw^z0Es35Q!zHqeYJFbo79SE66oemTFjYfN zP9DxI778iyc%^1*9bDw&-CvI&1A{|Dr&8=ca`5m39qer#?kUg_^xRtRtPh}+^jJSH zD=Q0}6~&YOBo=bOaeLLob$Rr7UA|VqF&dhA_+Ed8+sb%TtYn>2w~UUR&cC!Aucl^Y zWf`~-fvi>2Wxex-I3L1lg*@U>fBqfvsp97wdU6{~N(MQ)C z0#B+|cN+`!lvrwvls=M&B?Vl&z{&Y^d)pnMce0rEXMjtCJ7R{-&;eED0(gC7fSH`hmxOY|?XviN97N%O0Mm~B=k+rtAqH;7yQ}V=n??SnqA*R;X z*HIjSf0^!*S~-H~OzpV@9cXNdo?0Bqw7Gxda|DaW_GA#@OEzV5FF;g2%;(h9)b_7FjgYV~r%it` z1`HDu6$P-I;qe`S0D!*wh6W}XPtl`Cj}~$dP%;Y8vaqyQIL)6CGWNCh0@^FmWbicU zyZ4Bbi_2r-OVd&gN^>cN8-EUGDx9TcPtmffoQJv(~R4@xVRPd>%PY=PTn3$N*;dj&14Zu6(XG9;;f(lYfRxrQ* zfq^16LqbTf03;&B%~ek|9W8fU9C_dV9#>Ui$cA|!%52ydy6gp`KI^m?{P=&Q{c@R* z`>OHa&Z{596Fs>a>^W*lQz~2MQ=RIXnwl^bpd=!GXl(xe{n6^W1{V8ZrX_zyi&^9L?Nea< zKqCbLzbAOC(K9m6ht~d>rY*A>t_K)Lr{S2GnDiGJrPp|Ey#p|Qt<8sujq~#INO-LHsSQU1)IJU_6Qko9sVkH=mcA zcFDD)ZZ>QWIaD+n$cj@83{7Afya$G0&M)%v)>*yRc4zlgQ8|ABpa5z(4wyDum(st< zlmmlFKmd(uKQ5-BV;xXq=Y5}@2QOc~wDa`V5s_%$S?apdEiDiHK^Q2|39zr`Ztv`L z(du>Za0ni@nF9*azpa_A0QP?Y19O4!{R0B4T^za;HQzuZm!(s5 z{{nR*d>YC3ao{^^{ircJ9zj8xl+HO%TM@&Lr$4S&U22Ww;5&wNc=t4nR&Jv{L24kwL^bX z%o|Y_pl0C3-fY!Gs{-!5tra7V1>q#MCUqr6l7KbN!O4m5cMYS!J?->SJVOhf=M$e9 z-9_iw0P9{SO}%+`BO@dI4>leHKes&NB;#w@nhQkvR(P>bVF*n#M zGIF-SH35jJ>+3UPlSNT4Es*t7+ixE#5|SWcKtzMV7+)o2Mt4!&o*a2^eFJn$z7!Q* z1w{mlc#h-r=Yg|I5wIYj9?=eu%g=rmE6=F#aDI#_33B|kLB+eFXTC2lCyT2dH~g8! z_t$?o_`=qQqEiGytIXD@JkS-BoX@^iN>fqOYrT?7LY1*U7gMJc6cpO-loAeVNe6-x z-dlz)LC#t#KR7u#bsQh`dELExH==^njF0aDzuM;Tpbr%u$-kKq_Q$K% zJnr8E)X|vlN-dCjZTiQO#%Gr1Y(0Pe{3m~P!5J-dy}=g``}X8%WEv?2t8XoK#o{kW zN)EeZmei*l#VZ{LOFP5NVC#vF1_3|qJVsgjuJTw{noK)8arH0AdX-VJQr>^e_1#i} z_iP&;2qGFZJka^2nWVXFP)yr&PYdBp$;DcYT4f11?A=_!HR!(SzKIv(1|rvmTN}k&qNHi8Vea? zQuy{`3dQB+?$OiH}fL5yV6X)eFQNO{Da^YrxZCqv`;9(;SZinJ z1wp~6=g(Q~s+KU-)zz0SD}yb(_)QGouOnMpV_4<74{~c}ZVp*D@W^}@Bx2gK{_M@# z{rFm>lo>;P_9`tcZJlk|n09}!a7b`)i_4|5>w>(z=fIbjmWq;5Q5;svr1J%qi;aoN zn8?!cgV8|k2&Z&r6JOs_Q23efnBEg4Bih+3E-pr(>U3eT=YvxVZo%F1e<4rVX-KwsFdHu-e!ym?<i?}3iDqF?J!;%>)@pvi!TpA_+|HT3!MzU~$HrV?QDLd+D3oodsHmyH=}?hxvm>xKwuBe#||)iU1?r0Ul#J zg4k7!yH9Ix$+A1GbE8|%Xt`3{cH~GM5c2&D;dc9!-5y0N%-PJr+|TEoeP6xeW%F7T zCL?a)NQsJJr+cg1>@oJ^9jR{PtzhI70K2YTyM_#HV^dQM9nt zn3*xZ@3kZ*A|e8EGY70zHF0+V+y(8aQ`gnhsCYEe&I9Q#F4`cO`g_>2U?=Wxx|qtG z&!QDZ1fX+MkV1dxC`y+FZH(Qhva2fwr0xvj9vA=|dvpjr&*PaEIv?VWC7I7Ifd^I5 zsXv$a1ap}rY(_x_Ow^Gq76#b@G%53Yakyc1vLQ(hCo5RHFG2?PP$E?w3Hsc09~BD= zZed|zRI-frr8MLY;z6^Ryw^{XbmE58L{^?(zcg5Gf0BQOU+5+?p|DEA`3Ef~B?1^i#BoXi6!)~J z21wt3w|BeNI!qn{zRCp(ftV7p9T5dn+yyY){nn&m2uxD0M*3WmWf}(%sjTruozWSvWheMrBbub7j z+jblG;DJe*ij-PLhdwqoHqwGZ1A%ObygTt=&rr*iBdFmM#MCpQ#JG7^99GFX!#R$%ddmvjDSHUthnvwN-z#9Boy~td)_7VkXvOa-sf+&*iNvwd)+* ziuBHUe#2B0^2HCxrDbHoY6PmSQ-Xt)U0xOYA!45yxrnH^|Bw||!qo+F(I)_02KoO( zQHXf6PTyj$?AQA#&loeJz)%SnxctKZ&l5P_f4=^Q2H*QqG~N8ec48@!y$hNC0xo}% z0C%7n&Vo(@$3!30pgG17(!v0^itH<@u(iP??vP!sSQOvfz8e#Y&UBF_Zkvf*xnf9C z$g+T0g3$f)-dYDS1!`$nU(a8DYbAQYInU`I_yv2_uvr$|&#zs;fCH0FDtr?D{_k9F zw>&4n`?a;TPv#<%lav2WPd9Q2I?sQp1Hu`W7bXMbz?q28KdJLR-w6?yf{Q>WHga764*zWnNP>%ym*01%?$_7<%4U|p_uhW zhPXYgmMq%3x!V{*kH7~Vmoh&e)avY1g9Af2ABEfJQcd7DA$-Xm#gPsm0nmOQHLHZf zz!o}Srv<$33lV27LdVXo0U1GtS{*YoG7QQc{yli#D*`C%WoG81 zudkU_KJE$Jym_Y+R#OAva>)11y)sB1ML>V@Zka7skQ1|g z8gjE!O<{nK{zoZKui{8sICn3vE7o86!wB=qH8F>O3XmLO=P z9>peu4CpT#_jiUQCXqyR`9Z?`UWOrpnqt@pD%)X!Xn4O&++BJXn?9A6fLscaurH~~{ zbMx;I1f3S>0aRvh3!nq)20&d3?d_`K;xWuvuiW6fNN_-eBkF$vW^oSL@$vB~^g8sn z_V)letrJvK=OrbXeBsn z{#K>S!rNgRpl!UTF!}eTB}4w+`PtdY<>kVdf%TLOB)&v&yM5`;WV|rI@fYR}4pwmU z=v*d?lHMFFi_d>n)kMXdqM~9&>@T>VMr4>xS8RJ<9tD!lHfabv6QL9v7l$7CY;V<) zItz+EwxPXW5G9@Ej?=3f8`BF#wH7VW9Q*6-f{o41hZ6A-gt`&#wRBo2ha&hrb1^N+}zx-?d@Le4W`BA%i_i&Ne&XMtdntnF@G+mM6s|HpiP%UQ50Fu!Eli+L>nZ! zP5SkvEK8Og7wMtB*qY(v@XebUa((?=&t?IzecSHHu!)jM0jvH-XHSv61XQdb2oQi2ariUQv< z!hfiG?0!i^LlUh>kX$VmhhvsS;WspP`JpPEeRd1?Qrk^%X(?Fj_nFxQF_%__sX)Sl zK|GEnl92|)RKy4Y0J*Y<1N;$nlT}UTUT(6+YUdM4zGU0ow|${(^A%dR#;+0mPHQq( zHFpl2y~OF`X?f(85+lM;B4R>?c&Zfw$$te(Dd&nwO{0__dHMKRd-qc6T~n3WFKZIl z?Clz#IR|VFrOn@<@_ob%d_ZVR(wHG7wATqDfuu-7L{jMq3Az#{4e&8tJjwUyYO2cJ zL;G~;%+5cY!xWLktSF)kz~{XpNPz`JWgICMYN_H$-umCx8IOVObDd{8b4dz$>wmQz z?Ez3iVUru1!anzPKUkx{$0kS+qg?QK74i7g8Y8UTt9~jjkpJ8*4Ai-1IyE6dK&Y35 z6M-OB#ET<@VNCEylTi{M*m*hIw{(UT@Q_l8d}q;4XNf?W6j@IGm zICj@)PBH(h9)DGneiBSVee0XKvwywMipgB`))a9lU`KIY%XvLHd0oc7xqY8sRQz@_ zL5%2FgDJCjb_!Xqib=?_6R7{5hs8tOGk@!{#3=9S{;tm9 z6KZRG=;?8E@Gv{WeKXuHhnE0f>O21s;nPc${02}<0|b|0Wdj`y2x#$abD>Csq?#CO|ND-ToXC!x zr2Sw(KHc5(9PgeJgHMl%@Vp3q+*m%h#mexQimU-iAuj=r;y?+d@$i+bA{Q;x z!v)p%DORCovr7J{u-q;*PzDUUwvj6EtB3@V(`B|Mb~Ai(aR)>~xhY8WyqbUhi^K2X z{4Dbj>=Zp$^Eu|b!iA+d#(BBdc!+z5cmsh_E#-Hs;Tg!qA7t$)vbc3d)_5guiSxND z()9?AtR~?vQ>K-&C5EL4Rq%1yp951aZL3Mb`psrkUu(K56^1*ZZ=xl{#SCX04d!vX zsz(MO1o4L0Oj&H)-x?*_P9%Tmv4gF9Rf6_2>>uV5MdRVm5@ITy3heOT|GdE_@bhM_ zM{Cy<1tW>wgPo(5>n7C{VWV_vR>nedV^BpTe4tulPpjoYe&q9Aqsn`gr7~vtz zC`vtZ;f}{C*arX^tzSgo2} zkbUz8CYIu%wqUNgU3p51)sF$-soS5a2~F>;Y4nI;OI2(*unWcBz`j%x%Ij}S3~vrf zKC`z<-CE#Nn2{rye zsFdL!Fx>d~MH6)DyIWFieFbtxf9q0Ijgu1@WZwYh_6at$=l%EnWUu&laMtKv|ADr{ zqfY(V+81bQ9yUs*C|Y}Mt8eR6f+$-F9*VL@^7U}%wk7eid#npzTx5%f(xo@t`yaC@ zi!cHXPAq{URS*CGNKF9%9{`u>W&-~CspT=$v-2?U}l@mB2Mtnb#2 z3!J*zCrXAfR;`eTK71y%fBcR3P;8+d&48pH4fhlW#4!Csn(pcD>HhfJ>%!GuNDw-{ z_vu{!XZu_u-qfEt-u%;f96f!o&VRc&`}j4mm(R}Bc5l3h1W)#qT%2jz$9wI6&R&pD z=Xdd9UrIFBaTLVSME^Ah zEgdy8?=ZPiqB$E4oO7pvbM7{9&SnGW+-uaF7bFUN*PpK@y_x^?_xu0i&G6bKug;?@ zxvofODZQphXWAG&k(qG=v_xjc4bTyp88<*fWMvEFUG1}H zyQ|O%<<=0Hxk|4mGV^VWw#c1#19V32yc?i7a_8Lu{gFHG256Doc{f0pWacfYMj1JC zXC}8I*-TM-{jr&*pxT%O$*1I)G`G%>Y0}&ZL#9b{YYUks&8;eAnl!hbkYm!)D2byc zvirV!JD~qYB={W6;|1}5qU7c9yp;{iP)$kPbO<1N^FYGr-gmr+&fb|*tqNRsA5cXx zBeUz+nb03hz zF*$rC(>R&U7k^KLw^=KMnv@HuAO(~+WfR_p#S#!Qu9?54*(HiS9Cfk=m zyFu?`EtJfETOs|E+DcyNAG=hf!)efPyL&;(MdCkx;Lf!5dq;v`jnU#K zbI{3A%qbnk_sAS{a#r3QojzI|xptH0Jt%Gir`JceeCsiA-qYbRcY1ww-Sc<8#~Y^5 z+Z{B2w-XKs*o^6*Ih=4vz$S~?kuqRW841`tF*~XmZ=0l7!AQTMnvuq!0EhVv)r>I) z1vtjvk<#cYWo_8-;0^G1q;#lN2LfImI#}M3O5Cg4vkaVGRVgD7x8X1;8v|r%H`1%HC9iScF2&#$cdIs96jMxVTax zs)U!th=BfCN<WwG3urg6oGuOmd5&F_?f_MjJ!a4M)mOma)Q!A$xxxJs&Kl3OtjW@3T< zfEt-p7=Hz6@uq!JBUZ`;u7hK-AQ6sK&rTaHMxR^4?^uzG22D5rpwwt9M=6ef_q<*m zAcdYO!&*^++a2l!!XN?qm7A+cc>0V$MD(@^?pc%}B4(*GP75eQM9fa_!Kp3E5D~M| zd$4~@86sjfdJlH9D?>!gLhr)`(dr~pn)L;=r~x&L4xgoNw(SM?!h!Dv*fZE{3yj@s zhrvSz9a~q_l3lR_KH7;F&n9p&$E1g<6)TyV6x`h~xP63j)yRkj)~LN=>z!R56T z<053a>K1%*Nii-$_N#8e2R9VsB4owta>T8w&A2MBMvmTYOK}210z_cCjgIGvmW>gZ zfTQCTnwO0cn36*oshK2PV(lDVo$~a@G6J_*I$q`a+QO%$)X~u;t!!U^Qb6_CYC04T zR?=j7PCjPuP==8xpYyjASKnTfQqZHts5skf4_|H*R0ak~1FY}bEFJ;kAm5cGgSWGC zC_;`a(}4Rys02mGYek_*5i_b9ijd2SLXl6qQ~*WDUqzuv8i6hsijcF)G~`HBD9swn z>&**lnT`~yx4M`b=YcEsB`jbSoQ9 z?IqFPjgeI5c}cd`>33)a-?7HS%7Cl&)Xus^aD`YlU%^m%N=FMe*pA?mp(a{g>56~#t^6Y&7C!mqrK*=#y7b8fOz~BT z&+Z5u*WYn~R%*U~di&te{*Krcb5G1_Wx0Uq0m-UdqTCjbU)3yVUKqTF3|7S=H>JqJB0 z6bC9Ch8pRqlBj$*9k@T%peKd<3Y89HBcn{S+{5WG?0027tAn{R&2o204(ZQkVn_718=w(+@!dEg$LxT%ZO95n+RBag>sRk9 z66#B5qIE^C$|EA)j)_7*_8gYG|JxGa2qr1D_1}uk8BI|tmh@iq!cYqG+IPIu>%nm& zjs9o;CXlp$^K?y;H=!rJgVv9%gjz7#vr5>#Ox z1tEplflm@NX?e`!ki0f2I-W(>NIAN5ma|4?HcLD!rEYZO2pyKYRPqGfVLzvZ<|40U z#bgJW87@5igt0*Cgx)P^u9ph+$x-2VOO1UNjDt&mxfmU^4(Ro*tVadg3@IAsVDn+b z+YD8rkw*bygxm~O0+L4oVyJ96QtGh*F#>OL9Y~U9{eawQL=QLUCQRu84RnK<9K9Zb+mo z4A3)w-5p3_t(EIZI3P~jMeAf0TY{$H(*p04&naKwcf)vw0hdZsP^H`-&R$9>!UenN(IK|BiWb&2R zEEvdHjdjDIi!MtE8Q4u5aCoqQoPhbZ2Lx8h26nRw93BiHXf+5CfY3i#Q97z@kqx$g znqd?#A80;ER3NPNucde&^~rRv;p+s zEYUt%+wkVlgHuTR19c;hY*@LGCKwcdqa*t%f`W5yt+o{5eOW-kxwn=w&65j3i6#D1 za{_xwufu!JK9L41JPXYiSo;GebTEzHHYcOY#45xZeY9YU9Ap?v4fYXnjHTv~Jd(Dh z==L9GBaltfwv?znD@cbgr=)Eu8oOe%Db6fuTZ+bP_`txf#x{08Hl#&)>wVOJxzkMg zXa$Ys1jW$v*jZeXkpdkZl+^$4DK3+UK7ER2?6BYzXEISPipCO|T$l+>l*!4M&+nKN z1mY=|lQEogxG?k;c2R6hE^t_$ayc2BIfo1Deo-_Zj=^P@^~AVaR6WkXrc%7>_7zQT z;o`!0iu$K#(Qzb0Q7)%v(Q)K|L{ToMXVvkgMo~0UgdFOKZXQ!5&r+sUdKs7)MOzgv z8c=4dM#FCK{Bbi4>wgf6Eq$h@qyPlqUv6u5G6Mec*%(D$Mk(lwA8Qirt{>GJ6JpcFBrbA~QnO z_6%$X4;~V*PLP2X>a0H5>wt1|#!198wo9~ygHfJ;0j--59t;)@MFaVJGzv=pBq$V(-RGg;SThuj*fVIb9uq~g zFJT(2l0VpOeh_G|?u}D1L3xY)7+99*f<%Gu`t#MKH}jvw%aXE z003frlaaz8e>ONbE_iKh?Okni+DH=qo?oFNRabj=wvhk?W0> zWEhMpAbBN`Sp52%(F+Kv=N0eOZk;z9f}vaUOiy>uGn)43^yjD5()f^JOsoW~8sQp|_1I z|1k*Te@1?VVPbq)eQg-yt0A#&tJi5as9LFwQ4o2#8INsh!ajW=e|xRM0A;}M!x<)E z+m_QWAT-m~Wzbwc8DDP8XgUHkq?H_v#YNLHTlH^8wB@sw2Fy(brY(TkwsM&5wg9Hd zg4vdViSQhUBs_3|bTEzAF7ckpT~dPEt-}rDe~9`$aqiOp9ReDFTk4$U&_S?F+B5pn zHTm7^)W5yan#^sh?NpJk=*g7CMsH114V8h9oyjXV<< zK)(xOcPU})otyyfPEY`JCny6^#;_$p8IV%uEJ?CqUIeR0nkMiknvWJkkHr6Fuv`W| zaQNP*u_d8(8In&))Dr3REu=DfdiUGfe#x!}AAFDIz?HPZ zWE%MM#@Uo$_LeyISop?|A;~%8*qhIN97QR%|1gnNq;piaO$M%txGbijO9cFfivZ8( z-qgc>oWiEtaTGm;ffY@s&$NKf7zD| zGg8Oic@M*>bGeV0OhaCrh~x&-DPH2xmAPitD}L6=MXzZLU3)7pR#5uz_^70`Yh?V0 zr{0{`*`4fpu=Zz-vtvt2kRNdsVOhs10pCTOg}c(yqKE@j)UoA(L6Nm3Wo6>6rlgMS zE_D4Y3=n=Gub;eGyr4LbJ6fu;e}fDv%fjDzx7b^Evbnc1oV6my??**g1Gj{;0@5O9 z1yt0riJi43E90y+C3R%V&MHuq9prF9_4Q=U?8#LPq1G zyQD19l$PZi0Z@?bcrkBQJI;#KeR-Ll?`!aT4#*ZgZ${E8l6_A=k_sb(e`L910x8Ji zg2`zM4%w=-Ap2CsWic_yDGQbsIR&(20fOYTpqU(gnt=Q?Wwjh~npDXtPfW~B69sOX z$aB*~hnprk+%!?(rim;!tqSr3PLG==O57BZ76qI>H%%0{X#6GL+C6*i)iqW9 z#g(3sk?xf;&!ec@{q_`TGwI!X8#U_GhD1%_ZRm@fHv9+b^V(WAXb5Rg-LFP}=Q?w<7Qt>TcX-Wv8 z;}M1tWC4bJibapU^@B?gIK;^woP-BW1w{l}VF{BxQrdH)WlN7t)r z!kCYBFlm0D1#yU&cK0!2BFj?)6!-p70A1OX34o0u+8b?R7Mww2C$-}P+(1!zh$}sH z3xnXvf}#M8%}1*z<}v->hSR2%q4f`w|MXE@_Ma-ay`{F^JEu&-eaqxb;+mj9$BjQ; zHG8sQpDHi{D#9av8fXR#?uzQ7E6f~J$yOs|GqBEj{6s+-%zue{r{pnwE z1`?f5z;$->jL|`O*x*d|Crny@8NjN`Aathcbj#f>!2B5@o0xDa;bTpz>ubQI!Q>X8 z$%0zIsElzzt|t(&%7$QS#fYM!hF}56YzUA#n1Mz%V5UhhUG^Ytg063n&->tTOsHrC zic!c%T5x3FgTNw?WpUtS@ov$$vsEcTzzH=3Q>Ug`wU;JDs3vvSKYbybGGlsBmpph* zH`be0N`H6+bgHj6UW8AkEqGr!j)|hq2$NQh4p<^~HI)xenGTC;Qp#~FM8tj~VwG;W zZ#UQu4wCCO-8L3d)qqT=IT*VDR0@i-Zn@(+02W_P zC>rkuDVyU6HoS;TmeB&9ug(L)I)On`<>@kkjO+nlfXdP42k8_*vJq}2p*Syre4oG| zMqvYC)XgAUu%ToP#JWr&u9AZX>eU~zGXUsBkO^NXx-mB@kg(8aAg*oiKT%%@pNz-O3 zKPg9{M2=eDsz137eTgx5u;nrdIE^-~ib%1Ad~kQCJW>)8KmWH=#(_*oqQTnpANyx` zanMKK6&*s_T#s9oL%f|M=OIy|#Zs$E=!Cu>Q~Wb~{jB3hR3wT=VeMrr$yO1>1s?vz zcyxGo_SLrQOsd3lpk;PCNFKk)E!-7O#U6`MR(1-|TGu#hGtLC``1@e;dRf^epnQ=D z$z-#b?RDjM@KXZo90DNEBA$X@pBOkF>nQ`IcXxM?N;=zo3EIdro}(pp&@19EANXkD zl6<;%yv14--a1uKrGLzr#oNEfsTuCe7H6`|34tr?tOyu{j*X5E^V1+s^4cUvUfJ5g zEkM_B1}AFRS|LXb%H*lYkZzu1HPNEvw5srUei@h@truyh7zVCULKyW9GGP4KQ3H~y zDR5yXaaYtQP^f!HTClXXAL5elld=j3nfK!qP=m>FV;$3zAn?ApMo?WBUexd!jSpVM zkiBwuzXu%d4l}*ssZq(@nI21jJxGt4rjm8xpz?}3WRJ=k0|c|kgNLZ}N?^KS)rKd63qjFbX)osiaCUclt6+|?itpTei0eZZ)YTK+8LwV)d_#INPGLnI>f;AdU{ zEa-Z@e>HDNx&P z);J3@b^}l4@Q03mX4*Jva;cpIL2gvq9%5~{CXIfRNraE63QRgb4s$u8J3Mr~P{E9D zlM3dZzrbC#r&`V;_2bU6jp7^RlP}^4)i_q&lKd*=AoF>Hj?ZoWp>m?VT|c3#=Do;| ztLyPcY1{LkB<Na#5sQfv1t#kd<~o<$|3hz+P2{&L+Bo-cBKOxMy#7_xzB=&xq& zRE%l<5!yzs{;R_q`irSrIYhL~?pu(C4e@@}l3Z&;HcoZIZL&D4NL2m4=;`H*{D|*; zfm%sxjRG}wQcA(h$GBQpGt~2LWuhY_YmWpg1>e4JMo|7_s4IikJ>z7APHZ%c zX4WG!`CX^y?=GXt1irSUN{D}z3d@xM!gtDcS`9UzlADg$MAPF@|xyakb0R?)a(T*{vefJafWA1evLh% zPHVK#i0Y9mbpm^7*G*G)daS^d;RcY`@mwdFzc}e(L@d08ql%l5+kDj%D=b?fNMa$g z+Dcr#Iqy1>bj(=Mw&LBkQu_Mq%Z!pExGK(IpOb*i&%|LD{h6EPW=~F4vKHQT8r|IpBqw;1ZE_L-hTmeM-mVAcX zweC`614p^h-|(jOjkvHE1Pod(Y!dX`?W}^OT2-r!r-v`>dhW=)Ezzu#R_vS>eG8-t z;_6qXPUuMWWGt<{Cl(f%3DbZyTX#DlM91Rn+;GBQcqY-S^xH5Bg0@Yolm3JwLYiwJ z7yIw}3n)$VNgSSs_#h9z=31;IMUi2{WJRB(p`?fel2wD-_*Y)?wx{KtKGQ-XKfa&iH-26z$8syCqlz35dUz+lALW7S9skypD9UUnDAxm-jgv9|n+0|uFZ){v> z6{Wf0bT2qjPk*fKEgOm=NUJyP(aWT&=S?l`^h~mX*(XJa2nHf;0+y*bUF_5MLdpim z9>-{YC-D1hv54pvWG@YeFH>#tuhIzQ(u9@SaSe|KHdM(O$y+L?3HF9tg7@^hc@2-+ z2yN@|PjX+mrovMpFEaqdm3JElih_`vlV#@N0{rfs4bH}kwP9eQ^xMd;=NJu zP958uqeT%a7+AL*SUwKRXyXiyFq=)=0f(2HWZ-?Q?X-fUz&4WJR$LI8FWfOJv=Nj- z3&N{uCU4=s>#^qlVcM#k18FFZ`fm+HR2V$@IMw^G=hv^yRXN74~i}EbHQfl z1$j2#SAAGCbc~;lvhGirv8Dp-Go3b4fAtUF8Q^xc04@Ivyex^qw+f4~3EI9+;<8nT zuia|Qvt&KLDP{Uz{gx?(^P}-xWtve(_>F^Ea-Z)JgH}r*s>HeVvSaJ$N8I?+2JJ#p zf4Ky;^J`bpS)mI&o7oOl4M%74k<0@=0ZtOM ziW{{*^IbPr75^pK&TA@Nds(rfZ=w`* z!tNBV7)_EVrdpztZ*=aV5wyx@RSNpV`z%pub&aZ$e723TB@nna$4&vx$DU}`!M{o& zO4zB;@w1>M`5eR09`i7s6EL3jaD1=>f%1Yoz|z{LAKyUF1qQd+7rQT-cKZy1R<#if z0gD;L!7#$x0G0SvZ6t%5%6L4%q&c@2>RD7K{{^1r?StuG+ZG`LtItX!RsMwdkEB~Y ze`OJIirJ7^k%d$wSaKuQh&Xyh6q=)$%W*(DV0baYJr7O>J zlXW$&F0tI7sbdLB`d0>O(isQS4|G*?sX*yDercAMxLpZ?d8s333jW@98FQ4L?-V`6 zD&vL(BjkNJA_hQ6%5ANWn1x+G{d0i$rit;i=j=@D#A^5p@$c} z+?psPgwaxC$wpp1M0=cyKPDAhY3IeDFSp5XT42lwTB4GMJm0GpsyMp!Fx3_n0X`k* zPn$ONs)O0FB+QK*wXPq9g$|EgePXE-LY+IU-uPh;(K7U=G6bt|9)+h6HJ_z zta{>)Hd3cC!&Wu#pUdh=&fMpR<+yL7Kn!y=AXAZ*k&dbUOeUI<{~5RJ1Cl__{2;VKJlfALU`yvL;J`TRhv`K2`EMI-R@E&bw4kb$*-7 zTNH;0OJIkMa9=BTmky|6S_G%jv1!14`rz|<_Ic~y|LGUI2SC7MprWvODGbZG-}?U_ z{E2i*jw2QRiFAC9BNpC?bY_mD>!%3$A4<;A@*7`Qipg{hO5 zHEU5!=o8Fs#vNb?p2A+i4HKSSj*fFks%V_J-+hgJTJ^che1zr+8(+8O?uQJ?*N z-qJ5ee94mbh;uHALSminQ$R=rRY3$Jgbgh_@@(v11`tCf4s#(9YwJmBNu=goyY4#A zktRD-I_e3|A8ei;mJA%0NVZ;vdHq3$k5AN8`(3uu@&LRz48OcJ?7jKwZ~JyK1D%@- z&6`fAYnP4K7Z0mlZ}059!gH~@NXrLy*3H2*G0v{QWv1{y6DHtiK)hIY7ENgzG!p z+Xmo+i31_@0~IuW_5E^SYfVYJe=$(j=^c~s?6Fx6zH5fjkieQsG0CO(u7v*t(`<`8 zzb3-z!yyN&)lrq5@p7aAWvrQ~UB=+&5O)z5lGB40HJ)w2xoMd}Md|!G^9smSPbJ`j z^L6kQ?p`3|BG|pNI=_V;Ifz5yIJ>R7dL%!ZR3LSRfeLQv8XlrS*&kGqKxV@D2}S+E zLI|8Wpge1XjG{r~qv)U#G4*Is$S+fqm{r|^;5of>#eR;ZAZBIkt*?;7is0}e7vjiR zKcLUND#2JC=jkepT0r9pxLbV{Bn9&-_*LDBpEg*#S}8N(wJ=TJTL}w%((1tVnH_*^ zgp_PI=M_=0jQk+UK)I|{21_)JD-LDVtp;R#s9%m{SrR5Z2WUv!7c;REU3R2zOc3b_ zQeCr38B-?~7)!5;5Sg|sfm#CTU0RbgRc^KL_QUoN`W&Bdh^A`)6J~ru+W$d6dk7Tf zt$fUXmI&>E5a}tZV6%XKVW2;ZUUrs-Nq`)*cu2`K#CjWq{vYkGJm`2E=+Eg0!l9$W zS-R_kFj^~})@@(=wA1ej(--0|%Q7|zc>1*YoI#ch>>@npU3VV-7cM@S2EAx8Y?kgl ztRG0C<)PHapKE`n00yH0cW9i|Sc@*J>hPa1e^=(!g$QB*-QU^!&*UPe)GzT_PcyI+ zzrM+orFu*MePY6{6GZ$f< zU`1X+Ov{;Zei*Xz>*0F)=rEz{BfJMM$Z{AwFSyoXY-X9mvX(QL#!W25(|oBY%PTUKWktB{8!;5h|8LPshf0b_M(Nt`e*^QTT>!t?3~&ItVM7N0t9g`TT+dE>Ts<7HMn z`-+L+<)jx{Z({1z{(N#$E~Z(0JKm9MlX6BVN(zrDikcoz@Ta9hYDP_9qD6_`@ib$! z3Z$sS^BOJ6HL;3<=gAbMge>@s8>WR>4Ov?75u@}bpzL$FAi*Niej*(9Z|&;(CifQ> zfY`&zGt}8D-12>PG$^6h+}%NI&X5A6t549W_yBn@!+? zBO7%GoPpqBnmZ0f4b9c?b*%f^CfSg;bbi z({}PwfO!l{=3pgMiYQ>+wOoF<%fEQlo2YESa#lz4-3%dwu}o&rk>666^4Vs}Mi6$C zAYzd6$)#$h_B%!I)jDpBrS$pS{f_v}6czkCWAuQ0l1URH)+TH|Y$mUHeqyq7-*Vbo&3+RWK<0Z3k^{YYGJ{0){-j_3+~hyfTUU0P zBXpP6^5B(z$q@7M-{`6f?)_FIK%l>FI4?kS-DgMNsWAA2ALEDzhkXPjy7|hav&$T=FlblXBgkePq{^`YYYxMq|BdT5Ulj5 z?%{J(iYVMXV$b^@q51h{UEN(AG7FrCo(Du*OV49`nS6tshmWUxG97nKA{h>s8#sMt z=GUPzPU)VZ4^H@3c(a&&$21q&PG2x%zP&9H^H?j~k2p>-gb6xLy*qGQHxvH-Xa!zs zogj&F;G>7Kf3#Zq%p8t2(buivIfn_@?wNr`rMc{Uy;EjdYSODj3$qCqyB{@`JuWtr*pzc`8rxF=zV6z4vA!pie^JTL( z9qGOanMoQuPm?02pMwp2%z+Szf^Rd33kWY&syKvD*7|twrZA>)Wn)2N15E#_Rt1GZ zzXSdJx3}c)(9jB{NQBul15`whD8yrx%0+D*>C0#wU&V%%MiX=+wYY!Cjsn#btSZV| zGe@UiXUMm=7wZqFbH5T@bHY#faBP}}V0-O&x||?OVoyksmmtzAjc&gs;$K5k{lX%X zxl~5WIA*~`u1_Lwei8jh^7~P53}usT#KM7lbym?u;_&gU`IVT6wG1O3_G=X#?umMD z7!b)+=OJ#N0 zwAJBE*%uwcGh~r&Q_*|b_Goqg)Y|%ZIOz10;*#Pk&-(k;JKZpwbe1dib#ztnfIHMF zc}Xe9Nnzh0IJGMOm5^}#sIi=J=L!GEj$5c&_s*dP>Aix{%81J^S}q{ht;zXd2(JhO zThYs*b;Kq#WqF0SlS?eoya|&imyej{_>T0iy6#btLw_SNO7VDy1MYiCU|ACKGMFJG z(TR=t^@yAM99kX zIhFXR*I1cK3&K#&fE%!l%K*tF1|hwTnWAsu{7QP?-czzyYN`OWiXsIfDRXcG4F#v{ zst;&4$FS0;2a=c6g4!4u4&H(pR&5k-0@%I4)$F3xi$4`k%Mr9U)Rn!N_wX}HQ8U-x zuUtp%A@cG_-BiqK&`Amg+HHig( zaATAg*<|Zo6=wyMStnSF3R3iH3ic6RDnr5@Ov^T_g1$|^jJ30TkCeLk?cILBqkr$G z$h+MG1RJ_LJqmA1sW+Z5(Bnfv^)ICJzpTG1W%&3B1+ZXo=U+%{!CJzuOD3`hSUNei zJG<)o>>lAQb+Vov9sDICMm9I%L$EKX%Aa&CW8)7W8`cHTFbag%C_ge(ylPZ@H#TCJ zS8sxmsM}V+76V=QG4<9jMoox6pvY*xes0dXp0e~&vIIMNYEz14`&pmVQPmSyVnm*p znW@c-p~<^YJcXgRgsHovUOE-%IAOmC=jqcrz+#Xm_F?*&Od_RAF#V@+zwvyDsQuRZ zkN8ApA!`Cq5SDy9q4{(1j+bipsy$9KLkRK*e{0L{W!j2o6lo)rW3v}a*vuZ6+KTtl zs#4YT`65j|#uUfB1!U%=)(AkxClff12zq)SS0d5FPVi8JS>k4)?`5!sYxVs?=B@@K zn^{WVd#AW!t#bHVc&h#8f;Z8c#_lz7yicv>z$?N+(Oj|q=FZcfQ^&3@SMM< z<= zb%g8_igW1UH;i$I^0L|(0rrURE9!WUMb~!$S0?H~?xWVIgB>Ms;3<3jv`brieeqba zzV!s8WFVx**0bx@w0868^!6Ov8=eOaHGd~zy|%&T^2|h+&SHLzc=}rm?r0&7U`zF< z{`yXMl;L&QWYwJ2KM4H?cA2p6QeJ{Fk58%vn9%p4*||;%`8hs^H=bx{lZ%_mI4bnnVjgixhc^xk(K!%5N&@0rx zm7HXsJFMw>cTze&A1U7v>5SMRL=*cO9s3?`wohg%wLwfS6`wlzc3LX_o7X^9H~XdM z1&~-`Fu3pUf|!2Kei`Un7ui=_>X%^{el6A+?YoMf?tJOWqS_AT)(m#4$LrKwVPa9> zvRZx57w$xD$95}Z5$Cs9z-)uq{&p;6XJ@_()VI{S|0|OEvy}*sh+=DXbAe>NfiX3r74|i4Bht>Df;Xzg?i3RE|&x%;1A~Z=< z{6g$ajC!QxaESnTXj{H$9VX?W!*0sEqZ1lq?Cg=8fv<`Ab27R^zzJR+?=R3F!~pa8 zzkw~CDOZqkm^vwfM|^spMSOe5m|Fx(n*VMMy5}Db2k0^|ar41WA2wSh zq1~mYH|d#9!Ky8uqF|fF#*`=Fq6DkF-b`{m6TKKoZdHba0BPZLaFQ+aYOwxm=s4DX zkBj+D#hYX%xxb$A)48 z59Ko$-74prXI7HN!WnfPT4t)slceMIZ04HP{&%g;ow{sC-u?3}(UDYzIo^)m@HXE6 z%z(<<)0TL{?*(G%mFC#>@$6`e^3farvwQQebX5`}Vg*?r$Z-amsrfu`V?BPoBWw$M zxUV*qYZ>NtKuL`oZX0IrYvob6knNR7-_^flqK_u&*{TKx)P%GI1veRYqh9v+jYt}n zGSYGzBaclNrs5}t)enH>QW5(eaB$Q z;&gaC&=3dQ^3qwyJO9mv_`tMXK z1SL!0Jk5#RRqIjp=SJXZ59v?!~*3X5+Ur3Uj?7tOf*53K%lzV|5l7)OBMmOtB9R zmlG;e+_&~-*i@SELwS)7F$84YqiAG;K+xj|H;vxn$tkMg+OnCC?`eg@e0bV3bx6qq zkhMiR?(bTnV{=h+>VtYNQKP&7M(lci3MlQ-|Ue zMfM5wq8}OxrKv{YuGw}C8ifS50>gcLZ&lO@q1VOc_K5H?+|RZ&w1>>r!^&j|wRp2w zVH$@SZ6cVJxO%&ZPI_E`CE`s{#Ck_FC!Rwr`tm~+IR0T#jU=u>z5NVA$c%?`aoV8* zu~?kXs+#|RW5d*lVt7U8Pd$f&$FH4_eviW338XQrU>c$fg$s*=x(c4%zEkesSq^(nx($ z4vveAA->6Ln-8EMZ4}uO((wVG4D#poxJp7tLFM#9ufGZ#1B)>!lFqyZ^wfF zdRgC|%r;DX>1l!i_3h?cZr@60} z(T+t5LPe7Y>EEfk7#Q3eXJ`E9Vd9?Il`9Kgu_cvA^ytEYL@uK8RWo+0I5_$nwd&9` z4QX32g0&QK{Ol>jx>P42MV5G&{1=)Y8ahQs_UDs4r^B2FyzFnwUf~1$x_$3mh}W@% zxqJG7or2lUXCX)5QjLP~{L3l2ocDy~7*dWQ13-{|s(Q6G zYWf%6dVDpR-7ctP1zH*y3p;!X<-fQ@8-}fck$$A;QIF|Ux~a1A#PdcBy%l2bSYg*S z%1)=vL&vWeBjgZa;<^x zx5w%cn}~p~FK|eg{nl72q!1s~zG4-E+-=T}wiRXuD%hI_TZ7bcJMxk(Ckg|(9@D(Y zzvyRju@pxYf`*PNRXM^!U+&~uB~VdSGGBGN;uAI^rP(RCJ(hTF1t2m#`iv9gEc0ed z)L>Bq=!oW{VW(XW09d-KBH8$iQZ<41mv+$W7$u_QnfJHKNhjohSJ-FDbR}JRp36#d z8QH<;VoCx5ZS_Ciy5BF7`kEK94juh5RJ8ITuH?(f2}W;*;18wchQC$j#VUAUL__xB z($XfeFR9g<%SLyJ(SI#DcJn8F3zQyI44;EnoPrlcX`W!o1;}{eU%$)hDu-5Pkueaw z$ZKQ;Ib_rn%R6L*OE+d!3?1!-RSwsM91-^1rXzj+SZA$NbL4May-XeR{dB3$OZxJx zH;nw>Xj>9;bK480W8YNFk?|>uYH>yJCtxhO1SVlP`CUV--QgXIk{n|Qh_b(>8-j_S z`N3dXmoF+w0g2>#Q1WoQ02|dwkssj|BcDgQX7I zK6Qp)_2nCz{Kg>Mre!;7#CeBK*B3-|T;36bEOZ9xwc936fxG>#z-RXXtg6M|4E?? zm}28mLcsvyD>Z?o40Qc&R=}Ry{nO$1Yp*xvj~{&bSu+YWZ$^_WQ!%7%CLM*XMpp*r z8jC?Rj#Vlq((lZO-)~n((BHbDf$MlaY5Ls*cLsTPS|^7svy;Ikys;~7^VIXo1P+I| zg2j>c4O5_HRQI+{j&*txYlWZKm_-Q!9jvwbP-Gm zEgUb}hrUDTC0%m?e)IL*6BtGxPLXn8B>Hy-4(8BKdrb)7N>d*~ljLRg zxzIDz+g&^1zXb~Cp{AL-DyUq6V6~#P+f}Y>-~jy(bg)hmztC^tXY=aiTbmh_8&ZGA zh%x#0OqDlY8aAIhb+t$50DWQxAtm-7bZm;#2S#UeLF(f{w% z;V{{6Z@Ib&AARKn?Q(-x1-lyP)*u$4G}?S6Js9f<<%9J3)@SdakEmZQa=aOX=4k`c z&qz-plO7WQj5{mp6K~yz&wMe~m-3E&-hAPpi37%0a(798Sm4-xy@5imO^;;H*J@`c*6QKOdjSm* zBvxMhYDwq@gNF0waIn<7l9&j;C3eg9c%M_jO5K>Wlvf1OmFd!MWdtpF>WZcXi58+! zw>5gX$v4*bK7>mtKY9O+czBeEww3ypWtDnHI5F})g zzJ25PmPLo4Ye9=|o{SBct()4dPgRyDeJj^@{Uy{8`eiSfO$(%FUJe$~VsC0zF*Sl` z7bIuMVPOVfSB)rND-Wcxa(a-EppZG?ZiC=5}> zm50O5#c56#7B{3Ln`5YmtUacf3lbK`uKpY^OT@c4cn%8{`Uy9&F{)5ti>i1rTK$mD z9s0>V6i`Hq;^LdvN5EJ>malFZk+a8p1$f7(1Np)>XeER-s=Jl|u`C>^oMaACCN-3Y9K`xBS~mjhRsq4-u0 zH54D$zKLE_I9Y|z7TAhBJa~*^q!l&;oWTV(2$o&Sj zD~QAh(08zMs@t5Dkj&c0FL?eT+Ida_hhNIPNd_X0>h}_Png|y8I^f$xBD>&1%)H(#v>r+-_aodH>QH zwBFG4ds}UO#X@p5u+qs=w8Z`Z{vgA%?&D>dmAPDG^*%bo zc}rdCn`&WNlgX`pru3t5xq`-u`#4$pdBZ?Y*M!^pq`wA=)nV9!&tUrbX7HUtd5SA# zZ1jXB@3uXQa9Iyod1ojQP_kIe#YT5XxBX^yX?$q+P4lwlR;uW`_@=YBwDJ3MV)+IZ zpg^172D@s%i0>4(o>no$JciV>o20r)&0qJaP*-2^Z5j7e9!C3>r=sT z9gb4l^07=&?_`k}tMI+eNO%WG%kn~3?IS$1O_z%a4y7%xPB4#{BgfD-+i=4bBggO7 zh+#S@h8>xsAD&)M@3>;o!fh7!c;v_%_*@D@yRGlfJtBMeZX$+r^MyB*T9OQ_wJ`m5Amo9sJa`n#lYkI zUS(SF36|}momY-NZ9MDMS?QDi_o4R`ZD_wzpiYXIzricSK{-Tug`5rM6oq*O$f=n7 zmNJ_|Jrf(6U!DX1kkRJ(%}l{)9FXAJzVo#6W;XKbf@Wkcvc4o!%h zIVt_yPS!S0$2{-8LH(S|{g3L5t!!UC%H}tn^&dEnGZk=Yu6$)_D+X-y0P7eut7rX^ z%Xf_6ukj==l_2xl<&r3ZXh!)daau3!Qn|1@QA0}>rtZRePIcuql(F-7wk}&f}NXH+Lj$7%? zQ7U5@3Sqg;)h0H3{Br*L8?s1MJ@2FybCNOJa5*(F{TDq-O+wd!zt=bes_$3fG#YgO z=ztU`ljJSia|QW#SVr=pP6lM&@8qMp`{3)EU@KjUjJj7-Ki=!X$xaT@yc7-}|@sqWRK z;^gf8wx*ne$48xiiDl*Fr14Cp;P8L_xyd|i3quJwRl*3+9#iirM*J!h05%&d6)4=w zhB?{*`M15S`-~Zz_o@;M?{Q05whHl52M_Kif>#V&J*c7{>zqbbQq&({{dc(fB`WP% zIR~Ent(Z>#@5Qq`s3+DPrzh1Q)hMUxw#%#hzbt(MCR3teDp%5$eb_?J;~p;K$;Ppk4`l#r z7dehz9>$$z)TjmFeCr{)w(-wjb7Qkz&gH|g2@{cTU(o`bxI#D8;(cASt&E!>;jk}w z&R`z${+@xpH>1#5TDfjzPPgBn*RT$>15sEP6?dA5X@539tjMsGHQm#{(DU~XeWFfLgCXm(P;P^d zyK2f>IWgoMJv`}^@zGGes4V&Sd3HoYR+|gb!(S4kJD$wIw9wEp&#E!bvDw^}%C|Nb z!fzXlNACyEsR$+c7Yu9DYQDyXsbCUCB?SDQu`jKQy3L*0bxS*h(@QE@Tr10}Uz$)3 zpUp0?e0~}w<2%9uR5t$iypK6T5~R?IfD<%2a)H0#AP7*nUf?2vffdXA_n`-PxOxAZ z=5285v@(SAvC-L+JM;EKf`il72~+E5VwtQ3q1gR=sW=Lf3ASLf*=*s<;wB&W0A%D~ zOzir_ycV|G_R^uphSdbppO42nJpyC87zrFh*MIaUcwA{!HhAN#{HNv%cl;vvMj0_3 z{qTl&M)(6y8CU96xwsh~_5cRePNniC6LBf`wAUTz% zp7_qk?y4O!nLWHp%dZQ$NZ5cN-km;f`C{(P^{`1|Q{*90bPB&t`_{EoN~(x4ARuI) z2N}Hm$u*ugnRh2K!3r?aw(HdlTT%KzOXFs&9>rbd*Z%AoH?{d?0Qh{quUjR|F*@V- zg}q2fU909@JF1Qldg)^`yy-hKC1ereS@e&57Rpi+JzH{&-en5P4tAB$J}qL-Jrm(0 z!6n|=mP3-p=GJ7}^oxL!-oXSRCf5?FATE-JWJTkgF&YdPCJOs@Dw8aN21_VQ*fb8T zo9o{Gg(*jskrmDw0G6Y7a=*v6d}fT*Dj-y3&k>nT{DbBNF>SC+Fal9Tl(tcIYv5^i z7_7JILwQIhaEHmKW8XcLcDW=gbrYwG_PF&_Nod5l=+&L%@u)ri_`)AAHh%qAg_U+v zEqnKfzfZw4RWkMCk4Z_F7&6lR6dD zBNdOX#{+M`uXF02>GOCD==59!G|M6}wqols<K$o6gl@@W8=w{qSQq@U~*rLQw%vU!UNUuG*IQHBDY$!XDgMFqNfMTHhfcropTs@)b=orN_1H@_)KjFow~^HgCt z=C$?j>~IdJLHF-OIr`A34OBToQB#=~4uSUuMZr_=Ko+HIMcOa2I)ejOA8zT`5O{O$ zNWrT53fxui;f@NM@0+;#*G|UTYqhUtPB$_7ae%9jY^Nq&8ityo#bm4(pBkbjnPz?# zgiYCFT#rn>-jbBT_x~Cv%SvDbRi{fKwB`TX49jZ=A*c?9e3;ws=9UiR01^5eww9Bq?IiywO z-+YTkioK*!N48eqWrvrI|rk=d&zlQE+AJk16OVjpoNof*Ey%Ij~r*M&w@$$v9fTm2eaTr`@_R z2|~m)#6&P&i@>uwvc^r*T)m3@--)9RhIbC>u$l@9{8Gsg@Hm>J zlsmkA&vTK+W>>*(njPd&8H4lkqz!>LIV^urqqcro!yo#JC1kTug?U2S$sgWbmcX+7 zP52r3)ku|S*R-6+P$Vkat5SgzcHp#j z|N0011ZC5{+R$@)I70kB%KT;0WD7&y%FhMOBzKvqq0qozPm)0>AjlVazSqAKh8Y`9 zos7`@o`R{g+8i?sKOd6Q-s@acBpy&ONQA{CAg4A!pXG%bKPBArf|s9`eVgqTG-5D1 zlm}+=zph4aNuSFuhS2lJ_H-?lrUGDm;Viq}mj$q5uRrZtl^U&)7N;xz6$|e+_BcxL z?{_aoM4L?WtQwy~7?vVE`X=40vFq-G(RRoaq7ICGylkSDqEjez~~4S8{LGYHtf;$$+8 zBoq1}I4VFF^AmMG^yi0@r^$9}mEh0d{fM|qE0W1;k_j^sN)5`RHvqv$U^ab{&4-=x zp_~%OEAXZmcl4G2+h1P#tC(}UrHxXv7w-}6Z&+O=y}ukfdtiJn*LR(yexlHEd& zfYk?&8TQrN)Wb*e(2{&T!$&kyWxF1f_%MU-1?!?c(Qomsk$Gs+yO+QblMUrFNGMPt z?c!r-)j-Wf4a5;$E=Wp`|rOlZxA$UK`pj<15;;@ss zz>FD#u#alr=cGfw(d9NUV4qUKZ{VS8)#zTdK0fzu{-;{|RtQPWuM;-&GO2OAkeW!9 zkO;LT)_ZBE5V*!81b#J&{A&*Lvc6ubd=Y4!kTPyj@uLlsvc~-7tb8k=lUHiK6*_O~ zoXw2V&zyCZrt|eV%OMmx79T=vSAcHV(2}m0E@61P3MPgQ-39}fdT0TuYm4?U1J{}H ze3iLmC61&Xv-Shm#xxhLjPVtB5l>;u7-vzJg&zcT4mWa!&BFU zN?$%-{0TAotk0Amx_GE_1Cq0V4<4neZL?SDjVIyBJXz>pFKb;5QPRaI6vIpSqmnIM z=GQ_XcTW1nLKT%ijlDOqA_1zL-SbR!LSus&{{Ec%Q*d`a>^a zW?HSME^zrCby`hZf@1olA77dEuMfN!uzc30a92T9T9<$cw7ud_2v7F01|R)KAMpHk0&jA&SC>t+P3D%$RjDwtOC zWQA|O9K049ur77OQ$~989to59c_0x7Q;DD!qn4Fj&ujzK>W_8ia`3B&WB{1;M59d< z8gj!t^F_J#QsogVx-t7AmX3??Q(m(w9A{M*p0eu<(0`EeJfJ@Qc@r7N+<802I0e<{ zKfG%sbQoMeut1et*I*wIIbU~!08lM_!KT~pMBBl7qT^rhePTC zN!9X@`m@D$hizrLIe^|#pnMxK9c3yU?R-Gs3fiPTigl5hx#H?J?F@KxM6AxK%!^D` z$;tiO+j%G0%A^j8kI@=43%YBa3gZKgl9)PxlPc%~4%5ma1~vuX`mO_J00Gzg*1*>Y z0Rke!^qsjuluGXl4g*B>!rzfN?Cb zXfusEWqY}|CWheTG7Kr6m$}auIeLDc<^FuZiWThfWPAcMJc0NO!hQq$)&XfH=F4_K z(!z=LP*9eZe;E!Lj=D9I?yw#h_;ZBigw{7_n+av z5gwO12#$eA5d*1DPu+FZ{?S3Ky%n(DJ-j@{+P)ZLc8NVL1)Jvetc>h6zN;3$TwFtf z^}VHgYZUjVlxVOqMR5Q%+lhPp`Sb3yMRId0rddg=ogwfz;mc7J{gVUknz+t56`HB- zu=RXZ&{q&E6UYi)Dg-D-C3+*q)rCL_4i$>j(%tDo&K6~~8_M4}u*1NYdJp@eYY-~` z_W)WWeCu*n_PpYafLp5sU8ngZl3 z3!|}lqNEyv6JO;LN9Na04pPD&4^XN}%BLKZNjol?0zm~M{t7QP?Qga>24HP{qz?=! z7Wc@7+n@;Jk>?I64vLoI6czt5gl%bKGJLF&yCI7Zyw3`4dLq2!Hm%-j9D)C_rypZi zjj{!4tvj1_T*4|ShGjQi7nh8M`j8q6^nuEOy?7gIHSY-|1igPgCGp>aGLO5flYKh5 z*8Q6#095L7`=dO+_7H#I&r+#pjLEZmvl{e)JsB;OM)g~1>X3^vZ;z4j9nGV%h;DI1 zcAnEU=z2<-pD*@<73ZWufB|hPLOvZcIBPv39;i@=ph3_?(1e($$0FS6EohNiElh{9 zBqLv*>}2&9&dQ~{u%+;^x7c-7?6RkK#AnXKGJfU5a~rJ|&A)OBLxaZPhpg2w`R1RE zKb|DIyS542tq|2RLX~VGk7G8N4W6Mkp%-QxjSPx)BQ@1805T;&W3Lzx24$+??(r)mOn8;*xf)OXs^d zAB?nuv;yD1Ay94mhlkXGfMcieh|Z|on5N3D_sF?T|4g^-!Q@XzUB*0Zw{c>B1pI)g za7gKjJ4fpSwTvTaGd+=WNE6?i#VrdoZ-5@%+jYIW11oq9EHrh0SE3R->Boq&2h zPo`#d%$iTQ`i2p7=~9+Zp%_8YhxwpA|gA}UTRFS5e`$RneAAH zaSkF;vjP{-fakk!{g=X+eI#E6Lt!WedVTu&|DTrz05)j4frEe?5&Y-s24rXF_#e<* z`n7$A(2vpGr&?k*t(Kv3zxTREHtSO~^i^ET4%5j6VgYp(t_w%!jb2|j>SQ?5l(^>r zN|ZtVr>&86p+Pq#_#n-0*#xezspQFuLQ{`5aw3O@uRM49wMh$VUC2Ng<^9Ruy=dYZ}1yb{BbQG5v|JU>2PO%Q{Vy#U(+C_V68N^X5EJU z8(Y*(NeHYer+mwPOWa@U@PSU92hhWvF8H&KVCnDFhNP_ymn0#ve4uQiJS40JHbYh~ zFXlb03?{a@b+S}V`9>axvAeoKA=fKH2kUBs>b{_B&*IyNyipTl*^bwRHG3wN33j|a zp!1<$5Ro*zjgbJ|{P^{+3vmoX9aJy8vLsbI>|a~~`tn#@ZH$R7eysd-8c91gNPz-ca6;%m>X_C2s>yF*3U;6GqcLt1aMC!88;c zHW@}4IuB1Kiq+$+t*otL1GMwCt)kZpNUf3)o2@$WoBtVinpa~kWo%?@6y~W{Wo(#< zFIB)=1^-^EIB!898Pf*SsmE{Gem14M(z5MjZ((nd^tUZN zOSA=e9e#I-&?!H}E`PS5yWrl8xXjqh*eu*rugTa9bQ@m+-7FxSqoaHxwAnv^*%T{} zBW`Vs)HP#j$88o`Iw_d!11!BmYDlN5V82=rHmoER7e7*mdb;8za7Raeu>69xK5Syo zY)u()#dDsdfSsoy>3u5r0sK<5z~O>vA&@4DQyB-c==-hw(B&`{d5lY6`$cNn>~j`+ zNKY1s8V3+NUJ^FPtFIs0*4|}c+SDFK(;ha~=7qNO*{)_cnWnA)%tu%PkmfS7#y3@X zDQqq;l4)7X2ZU9eN`zKgPYPOGBiB8{R+I^~acav3dSr&1CZJz3SoIovu&|bCF&1fU zEiVb0_rEqiq5pU4XgzaxP}uhpB}x5h2}b(u>ie&!FI~@mgBc^_`i-tYErX*xkc)`i zImwD3J7|alVwuu5qXY%Xc4;U-X0iFp*EPUW0wG8uzD=rFf?7b}_~D$7i=%t8lv#<; zf5vCF+FnHoA zVI>V|$~uT6^d29l*ZY5i7=&m$5x}(B#Xo-Bc3Lgfx4P{E2Vrw*c*9#59Pg|6Z*<3~ z$UoE1DZdPL5>9e=$MDxc;)@H7&&P66Q~7|iIUv78C#j+23xnL_VpJ|i>EJikx7)f2 z|Ahb8Zb4YrtvbLwn+d4yH$kiCF4V9?$SvSL=OpM3LUNSTQ@7kx;p|L47X-Gy{DT~z zanD7+K&)4^_Y1NDhF$wTt7*kitBItrXdZ8_aC@cf?e*xclu|E`QQcy8ho*t`+uc;m zn55Qa(hHw%$k9W}jY1ImJbOjI3{BzaYhuY6zEFjP3P%0y*PAQwh3Oo~X{=l8H9H8` ziM5LpdT((m$?Ek=pL2DT@B-ooim3bES)$=8QtSaR0%Uo!4J7-&+ zoM}tc6kkGMYazBFwn>69RuJf_p|@q@w{2VPMNqiSMnqmfZ9#33fojwe=yp>&Tw*&A zRO7ZiS`CYD;4t*{#uXf8W>ZZpllHnrxOz{>dQa~96(eJcmmtmXQ?ua>1@8J2=K9U%49qC@M=N%Nd_X`O z3LS4gqjitBy=I)l~ z{wJdUy<$_?H0s6CKtNFAQsZC22!Sk|9Nhn1w0dv$n{6qd-N4`#a15_{NBXnsqG|EW zCSJ%4%e_N^lE6rzdK{e}TDMZSTrB*?Gf8{z_WnrT#(CVW zhKlFChaU{Z4zz+hS0Q2GD-@Iy&FmnlpMK2YygytlXP(O^><_QgiF-H!i{JMdZZ`Xm zE%u8KtNYjOVF+kaJc}$!{t(iP&20g@arA7He_=-bBd7SgY?AzWErrUzeD>ThRMbpe zwH&>OjO^Y3#)dsVaF@UI@nKh=&BB>UL71htcWM=2&Hfq**bD77sJ*&{yNkUoxDK?q z?G*V6$=E>>2%e-?fYw3;ns~>W6i8)x zudNy&`*PNS&mXkhvGu7EjxibDx38t4Zl%Mc2yI3MJU3kOFjj#;zrTi66UDrg@xw~t zJ@Hp9N^O>95B9ak^SC(`pXx6e7C=ZpE?kllO{krt$pp}jJL8>mC;Ye5Q7-L6_T(9+ z`9JJPQU;ZD_3wO~y~{=7CrfAy6)iH&Wr1#MdCG@Y#@Ece*8e7HDFzJQ8t33)Y9b#7 z=Z8H-KfU-~)9mbkL?^q4+`e5tRbBE$hOxW_9}U`D%JkyvGN4cgE^#>tzw~Dp78?eX zwFmT?mk)G-tbbmi<9egYq%UbPHQF1kOJb_-x(CwDG7Rh8e_9*^sVB|r5 z4U);DgZ#6VB&L#|FDgt{6fa@in3954kF^=eXOCCo`OSd3W;zdTYbN(w%)+I_ zWp9Aeqk-bp4LSeIk?Di18)ckXjMS2m?0HYK18KIy7H)Xq0m~Tj(KTEaOVv7)T{C0xu`KQxqcZkc z4_#P2$iIJR>+PxfEijYc-TAtZ74iKivS%YGUH!w+x9pQ^SI0mbCtmN*GpOSaum(ua z#bHn!#}rCWh{I6<(Do>%3=1JPHlB{SUWCX9iWDhpvU$^kVA96gx3R=0U=Y5};T*0R zt@AQa6;h{te}0<>!94v5b-W^sya5&6vJ8`jBwP;q59r^fhD0UTQ#VpVq4Z)sX4xW{ z_Zmd#xEH++j}x+ZRT*;a1T$SNCh-IpikUML6rc2DDnLA;MU5t`GL(rY5`%(Au`Sf!`nj*lj11(?QB3q zjuo~awQK}X^k{rRK?8q=9%^KXJ1yvfbl4#3Pb3OKBkdrfxH_8CrwPKGt|v^Bf@aVd zE0y!(wBU-v5e=J9e?l9VcZwwc1cAkNMcEGi1&^(cYv8FDo9+D zqg}t~impcz>vJonh2=u4`DLbJSzH}w$`0R*6O1(2U#sCp?^6~>|0p6joNg0y?qF(y zS7S)g5i{@^XRhxl^4+WK(s5apY)R2w_(`FLCE346|CZi(F1rc8So!1Y^xz?Mt`q*oxl^S?(k$wF7YXgvTXvcA z%mjkj*$AAFh=HSf*%nW#rB8m1$uSI-KF_m*k|iL<-Gh5}4n_>fALVeWxG(jBBj`S9 zp^d;nyDz7Z{*!G1oCil#)shRyOn+Mdb>1@e*9;OcQeti%E6enf&7VNjFhp5c!de6)MOA4K2Hef9C^Vr%r{E+QF;gCbR8%H4qTYo}; zPi3tao_XUk3n$v=K6O!JsLGm2A-Q#8<*Brm67+FD8+kX%b>mk;l#DXaU4Mj6^y*h? zW#~ZvUc8HAW-I-0mrQC$yr|O!0-^}rCinbs{qkX4OUkKhR&&ybb0?CgP%$a4(~&my zz_$mM^oI{KdBjQ1&!?e?IT>+>G8N9)xu^lMIC9X%!@5CWE$RL5`vW1;bjQuPYVQELoAjBy-@AqNU6h;ve&I9}JBK3b`3DDdG8!d2snglxelRbBY^k z-LNH8CbE}CAhy@Pqigy*ABSH=nO%Gx7MP06n4S(P^mgE1cK1Ii4Jab86$~(cQ4l$wAit+__X zNW%prcMhFq#f3Fmt6VQdmR=LSi`~lT-%oz{1dJ1fR6+R&CUU*30U? zb%@n;Ix2D*Y!18tH(+O0a~$lBxE?k{DlldY<^NTE@Lu*s7dlsVzM};X{JtL0@*8%z zEwIIRt<*ko)GfA2KBHXie4bGx;b6gNLMOJP+UuFGsgG4g>4JaPf~oByYxqpmfFs>i zFE=Q5>9(hB2CRCeyVe>Fh!mW6Ld!XWFo;>>4=UR3;AVXQ?=)(Jn$PTMr&nVQN{?x4|`TDe`%s{iB-Nl``w zXyBF7@T!R>t0H#zgN6o0amb?bg}nMG`gkOYRrC{Dqpr#dWO_dcEQQ~a zWST{RrkC6Sp%A69f_so<9hPJtNLQ~AW3YWS`JpsE$Y6-u)r=Ch=>u8w zxni;4_XTtq7xA0~JUCn=yD(+$N=`YLF11jiHauJt7Z;oD(+fXCRlm5 zvjC-co?KcM4bl+|kARu`L*9P?CD~XhrF@M|D|K67%xKEpp`DewRtk$;hNTn=BQ+|! zlkWREr1`hzSXzdC=+hjnD{LLL7rSn2+?LHsRX9A(dTR1bRWwDXVfFIrA=HEu-Q76a^fyYY@OyDjou*O<;FEOPCtr| zz$%1h6f*oSkj6a^KCGbch8CG^~X>cazEO@uUJ83bR=A5Pn4hdU+W^< z%OoD52Tq|$3bCHznH%g9E=pa(op=wn_)@weoV>pYuZ9&|=4N&p3rBwPf^U0F?R1|- zfO}rID<8JZ9atcYO&ZrIKytZ8Gu+}%VsoGgwPur*nZ;IA6) z_46X+-jTL&yxbxfEtsed+X={O1&?nWteSbR%EhViQ?-pwy=^_1TTR<$pVk4P8xX1I zRli)OU8ZDgjQVhCVO(iRDC;OChoDc)<|xT*m-xpr#NT<1xMtUSjoG7AN~_c1D|il< zO}Hm?GQBG>Q7coauuOgp^?I4yoTGWs6kR#!ZVcLq=ZdBb4kdim-vsCiOOLt1lUk>q zIEu=9mFp04Jf(_Xxti7NT1g1~xKrs_w%$)rIhf%Ksj3=O_;lEGu0~K;QOy1mv%`_W z4n3xXXlj^YM?x1;+PYyO&p*b(9lQ3gg`7q}h}MChQ!zi=TPR6S>=3OPllEf9t*cgIZsW2|wrF{$6CaDNLFe27 zjM02-UC)10$gQl{+{1#e$nLMmz>Jv}Eo7p?ANB;3AM*UJfWv{G5x20Hx}65)d9F3B z){xkaOn+n&Rr)BP%vjNetWR2 zh-C5i=BsEbT+RX!mrYTwphfc*^%3&&ZUM0~NNTpn5tKKKWx7^_C@I&TQIJjp==Jro*nayO3rNaAk}L$C92d?HPeZ<~ zaH&fcBKOwWH;UY`>E%R8oIkv}R})G8vvFo6j26s71|FZ1GA}77jC_*w=ai_b6P6&> z<{3Q``sU59WggAKXL-uNP_M%S#7#)jxEm#_rYT=+D?@h z^0YI64CJ7?pnsp`dPXn(95NC7C5~py%R-V%Z`OB4;y7hqX(F+*gwT~4c0 zBqM~OQKCl)cqC-Bv)nD<@{}IYQNAnt|9Z?+)yz`o6 zqBVscctnC9bIiUFinboaROq_zqe6few{p*{Q{vseN5lFa1t>x@{e5{sCSoWPPthL( zD$CM1X}u2^Q0fGM?=Z;S@a@Y<#(zNm14mORyn#mj5pYu*q&;E-+bVpPqrBeCmbSVe zyZlGHl;nCfiQi03qPnm_tGDWng0?rV8M{H9#F{26yo7V*a&}d2?O4dcVJ=|TWbDI5 zUl9i<3MoF{mH35%rAsUXc$}BLTUbyBjCl!EN-kp2;QJvijHRo?6O^rPD$4h|;y-qQ z5@y8-(*seE8h+rmrW*OIrcmme#|2m*A1?h(msy%&NHXoXwv878x5{zHXy87vXXXN< z-@NIhAFwKW^NQ5Tv}q%IuhWYMS1tiC7@8gc212{5{ftjj5%%C z)x11Ak^0&D5EHaW!qHpA+%@IUJHCN!LlLKS&Kf~&bqX)9geVT0eJT~=A^g>>+TK=EJ?qyc0RdYm?zQFZtVS6g0ru9wiC7H z5^rAniTuCaQLWU0V1pQNydI3x_TP!pY;gbeN~K=2iYMTmpwy)V-5JXjR2J#m6h!1se- zuM8KMnZd3i{rCxnuo5H55366j7cmjEMhqb@u=|8XM&AA zqvTI-=I5@zIbdjImoE|-s-h-o++5=$wK$c(M%vR!1khfTAoRn09hlx_G#kJaqhgi? z@H~J8bji*(6irKGEEV?@_t}$qwOoG|=Z>2c48MrEs=`~#Ja)9H^vG&mtQUzY{9Bp8 zx44KL5YHj@OgPN@OWL!L-PQNCoW^C|H?NHKLb$k1+_<5hEx6p55a4%uZ@u;HgOW(K z{ab0OPtGzoD4MF7MpD3Jcs$px2!kv)-x`7FSk%9sm=lNpI*Dv#dXM{i>l8_~nh_*2 zZ0Am^;52ZpxLLoDPq>6{M|6@tl~250k{5QTDij4miVmERlD!U z-fPcieJ!4w&|*_mes~1s6s9&SX8L-SSZD5LS-5d#>o>YXzyGi3Mr%_B7!w|B4Ec3W z(f6tOBQ@?7j5rmc1?;;Qs;zw{Gs<@aQdQGe9@j>WSS9Z)bz((cx3k}kuO-}NH{OQXdqIQYE%>yB+xKj?MFY2 zK4L)iqKaAjTFLT}5_W=_bWIuuE%`1l1)0ise>d1A(RAjN(7GmS8;E zj3`78?rg(fmrV=&>e$i2Srnl=EtC;%Md*o5o5X4BEf25X93pO12~>*2@A_b;7I}LH z$p)^tJZifK?loid4Hku@q@Buvox!?>~#Iy;BMbNo+Y$%FG zS(op8`r8DYKA2~eA`tSL%F)ur#PGR~)mB0|WjGK2+fvuko5jwf%}>MJT!>U7*(zK; zpGAi$!F2yG6oFecSA5HHlLu)8Fxsy!J8Id-WmI3{B3^2hThdtmYWMk^5@bbd`nv8~ zMGzrfztv_z&Os{yajpLxLZ&p){!0amv-s7Rjq{DVTK6Hxcb#s1Q@46Ici{nEP4rT0 zwlOfKG>!k46$@^(>yF%D9Tgm){;gTu~aw zRv}(Z(9BV}C!{pAMAkR?ylT)_43_hE(Fwc#Z?#Qt_kyb1;~X-LQUak-M`BT?s7#QN z5D)u|4G!Y`N}b^=%!y^e`Ge{@j9WF4x3$epCa=rG!unO6aPN#-nn=7wJRl;k-0)Du&fKz}mZ93tf-N;e zVLttF3|#+kPgS>27+w#{yaW`3hF}gPpj-BsHz#la6=3%5T|} zTr`&H!=Ck8r0pI4WHdP}ylFSify|9!V-qlR=m`|ccQ?E;dT@Ev_h z72E;C0&0(vaVk6mt0HOu3N zzhkXIy80vU;d(#JjuxBy46~8{hxkwAs*Uw%?l1cu`c3?213GTK9*;L_EOJHN+#aTz zb!TW^XHocWd*V%Hg-JIn_%>gHTd#4~bp(C_Px>0(w&(3@Hxki!7(o7L4c%l9D%|e+ zFW;BzL&eMx{j-_2CV-X={T6=df~z#N+sCxaj;im>`J)|f+Wr{!W!BL%3qSSE_~+DT zelw;J^pLLAN&TeFQ>LQ>9bTzjas*myEl&PBUnyH9Xl~n5phzSp*AgZ8c?abh+l&h2 z{7x>Lu-)?C)mOz{TnXPMa{f)RA^lM&05kj3%qPStS;2gMBOJ`rO|;9RQlnONHBy4) z8gb>27ua!uoVOB#*=+)KPQc3gItu=4q;5Ux)A8d<=eHsOE>Mb~*5$V|SKWD;WnBqt z*4hRSY^ob!yZsj(u`fo;Zq*>A(*xEKCp;UDoF#+xprI+@w$4?PGuZliC=eQJ$ku>Nxp6ML1{NQ&lO44XO@KpGTl1;Vpe z=CM}qG(&m<_9}Ry37~F>X28BX8ztiO`zDpSP^wij)-7MWnenQnr~sHBYMnogZNDM^ zr)HXmw0mO_Fi&MJLEHBwd5G;A*fnG~CkRiVjoe{k^$2b}nMTN}lEqU?6-Ojgfjxgg z@4ta`MI`sW%?oI>wCOcBQB#>w40ZMa&DSjo`fD?A(Zc4Y^pMt(QoZ!hs}^8x2C1@`0>8{>I(6|cc=likgIzjkOH zR^V#ZW8l_=>>{lYOaUx3tvMy;R=8tUrcVZOv0VNVt@l8&7gl1@H81lt6 z&N#mcUuIEE%kNGCl@5UHAOt{B3aTh%ks9Wbc^RJSH*?>#3{O0yW8Sa~&n2Yer%@Rm z`u}VJLbM?{LNjqhw=I6E!7#vcI{kP5|4}}gTQoVm!u1v?koYMP_>KMlHg(k|^#4jb zssCT;h{g<-rT;6fKT|QP#JTa!_y0fYf7AOZzYp;J0`(2?NBf5Om#xR(=H5Q_gMgZ` zAeJA{MwVH@IH|?kfyKNIHZUwrhn154YxIq`GR~Q3ddn#XQvHZ0mIhEXx6`ut?8IW^ zK9LO{e@Gp82&w>gV&!t4$P)i&6D;Q`w(nnl$dvckFtUsTU=(!@;P47I&)ZX-m+5*h zoCMe~#6;^Gj5(!5;1ykoI8^-P4JB?*l&NrgB$NZOSn&Lq;-=rg9~jKX82l58OHO$3Z1lCy#w-vpKf&+pmc&KzuWf}gpc}b;>fam zx9?*`&Wq5f*UKIZSQ~&e#Da&T(Po;05c)@8^zfO6x&eyMj3^CSP{X1KFBH%O5^wh! zv_j7g60Qm^R)K@AeQ*x~@&6J0Q@_9e|BLX?TCgIAA%1`WHBBJ)lS6}ulL!C-LxX@= z5{e@s&S04O4G~8z2~q+j&kcsS)W@d?;_m^r0JT^MRZbp2_*V2!M`Y#Ln)YU zj)%)OFHd1Ygk`{V#+IEGroug0V(z~He`7oA98o`9Czue2Hnu~Qu-8$(ND$Zt7_p91 zbnQktF!C94l=5G47SWBcalRa&EYp-i5$h0AKQlorP0@)TY`{ztK*1Vd zA)18Z6o@lurhsU0an$)BC6My4kcdrveB~hi(vbhL3bMolQYuG-xBxQ367oM*G0aKP z3w`7Jzpa|rYTN=NpJ4cpRoU#bOhSgf{{Lgu%!De!w^c;hJ{kDnMX4s=Mlo|okkV1YCeu zu6id$Y!lt6s>LAFd-W*>;Rs3AVn~)F#Gbj8M(*K#sa;iFUY@%QrC~2pDvB)d%Kc*T ziO&tY+rArJOf~oa!d!$=^|JoT+jVG&>UL^~+TOwv&1@A4Wgn}X6?}l29tBREw2D70 zrT;O4rZ#z+!{K1_ayt*J<}YaLUc{Phxg@3~=J%42EpmmLcJ^d`aliS~g<`=M4z=yw zH84q&qgVB@P7#@kCztAt=i#sApzVZ9Urj;xgU_vmJc}?tsM)Mtd%T}6W|p8&=ykyy z@sKws{$}V8bVwao()q6m2^%0cTmCa$|L%;>@y=ikSGyHzsOgdWiiGzU>QaVpSgna$6TT1A)Vh5n(?>+oo=OL`w3iK?$2RtiQcKpgE9&ksj+VBe>V?!=_<1v$@FV}?Hk@$ok$M-3e! zf}35$J&K9BE5S2a49+cVUF-nM?aM01D@xg!kTLk*g=c-!vOhE>;=7=gXp5*trj(UgZ=(2U+iM@Rhn)pR3d6sh6JU$eqs=cB_Qp=Xi~Q4VgE5{>C}oM zN(6Es#ge(Dmc3Y+ik7`;HLrZBx%cZB)ycaO`{#GhSeM&VRtu$S_Z@x@GB;ejcKU)7 zMG74GCs)#Mtj*LUz-v64_(Sptv3zfl0n$2&%>0>&a`6_oe2-w1bZ4IK4(WxK<}U%6 zuMCv|E#m9wG_cD=v$yk@#bQ)<*(@$)Y3x7uD6LjiHv!qt=-%vx81t_9^>xH{{ZUj!>8IrHA8Rvf0#yg_A_(; zX#*M}N?xdbS*$USJzk*JVJ81@5T{18u!MerRR`LGakk9xcMZLho37BUWk3-+W{w(i zU)5@!XA4RQ9vF@%OH29}vEs~n_k}KI-i1>OvEW(I($chB!ZJtSz!`-;=xQH6tmEk7 z3jXB{?*xt-tmKSFj-X=Nha0@wsE{dWpQIm5yIUL9I55IV>v50YQOs9Q#W4|=?}MGuxo;-#W?VUERn)xd?zzt?-UB<5V~@}r=!ktp_|hZl9f z{*2EjaS^T?a&FgIWqTisGcC^U@{2LG?%pz`GJYlLHoQE!din$9a*huTcFb6wgq>T- z?ZA9mRcF{Kq9P7=7v`gZlOpj`jCJVMGzt)ro8bbd*cE=cBI7JNz@yZWwAsU}G$p=+LGs?u16xw~ZCW~gI|rf5d!6>1S>877^*F>i_C7QT zR`4DMV$SQuT+5wH)imgh1x9Y2&cgyy;AO=#o!KXkER>R2YBEQ3MKO?<+HmJsaIs7A z3lrKF`+$y(@=GpzIbaG-U|CM_1Y52Y9!RA%RJ*2vmh(sT2i}SJIyIz-ZNYfcyO0P+ zX-!Ke3>|W#to7)D#tQAD-QMHr%P_J1aMl_MHE@q}+$m+{LoT z+NVMPu)FT#*=NEzdm_I+#KEc3EFF?3!e_kY$MPw(+aJiuKa`ga=N`{YFg-%(c<7W~ zrs|7cLg*PRGKQSZrRl!5)bjYV2!vVNWN?$c9Vso+DYEwla|Kx#y&C6GamU>_i1cI0 z7GSLV+A&8uY25tV-J$2S(*RTV9J`d(h>?2&bq>N;lCz+79&~La_}vpC7ldHcXo#eH z#)-+_xwYb^W1083;wyCG4N}vQqceni7e3qaU zU5r7HZTn?vchMZuiB8)P9yqMtfV|Phx{X)YUX(gTyKVAl0zn~tq!|0-{FiLcEfN<< zFLCVJ2jraxLC!O}P|5(}4l=cG9^Z72VL)LFKkn_t>?Kv_t^Vi&(%QwOK4jForyqmr z)*fD!(LCL$_CWqxyHgAHu+#0&y+mw(BD2VBQol%CL(UU7t9u5QK!#0h%Z3F-^$ymX zsCID7Gr%;#)xXjHZT$rQ$5y)c@)~Ba5cqPsF012Og%9Lb+AA z9sIPw|C1m7KM)kLZ@+%?VjNs_-o|i6g-oKTHT&9>BhN`~E;@`n30aj4s)*#_Vb&9$ zhl!Vak2d)Uq?io%9rLN>570<=x%I+OR_<$_=Pg0JnU(UOU|`4`vrwV~C}Ge3x9dr7 zt(T(cyTUNgdD59TEUm+f^8)(10munif+C$<`_Qz%C_Gv)h)c|*fnw&d3f}`$el~r4 z_tDgymHB{H2LyG*>K7L87(<)LF<%$es(Y`L`^dOC!NKhHpg@jYOMnk=#Vn~kQ4jh@ zAkjD<9I7XaxA)#7llWiX(|N@UePLh+H=~zQjOO^K3xhGr8dV8DHTyj<^09R6rRGqM z);Npu=MeQWN~3U$lRNvE&f6;u59WR}w5tlb=6ooGt8ut5wfdME&2lo&-^klaV->Py zo{Zv<-?qu- zwrv)w4C}a+ymRfD4Rty{qslRdvs=2QYQ<8!CUGC|Gw?O4tbU}HVw}r?tBybh8nEOp2G(0_h4msXkWL;GzIROHf`*ukFPZXE(ekbp)5dQO zSx77dn5P-Ox-QdBH006cD7sxh+y}3d{;r87MJhz^?C~e)#Np5JA=|7aYG_+7xVE=| zkdND-XYBuaq*|3ez#a(UE}Svy+`sE5i!lEu>|~1%4hOWg-{e5~+%X_2(-a)8m+G!< zforns0I@V*>xXjw0Vh#FK+D!Ap*FeLq-e)FfVN$b0A9tHd@xv)5PHpsq!BJYqz zur^DpqD~bwEB;>+yGUP3Q>S1Ni84YV!{$ZZIdH?xoK;l1R_!CVWSr$nnR}qE$N;qbC)~TYyst)^5))_oFwW#D zfsAO@DemgjdZVr3sj-jfdX`QcY_5|rZS0l2x#M_&$)@he9zsV=+#}#N_nTgIv;!7n zYce2LpW>pqk13@`yK!}^!uS_e z#e(Cc&#D?p&J#PeGmJ2gv(km9)D!nRNvfPzrr(Tbc zcLS`p#FKK=Ac8m*Lve&fcnQ{N7yw|7bc`qKYZc;@JR`s1BYY(@{HJ!4j}O+#glMyS zGUH1ewN=ne$Y)y-BmhZUc8AmU$gI9wR?i~=oXGIeob^9bS3=x$fyx)D4S~DVF9Wtf zd*&@T<#{5OT`{XQ#(-GdOZq{3)@m_;u+dzk>#CgZu9`BfKoV;7a{n1tzJ z=;*keG3V)h-G*~+!A5f?elcZ)+!O89Qq93a+#m$LyX9VF)2DZet^ttfTBi$ zz#aH6S~r^9Lmnv8?1Y@LDJYnroB_)uc!Xk(1>d$V?!`Dws~HYlA`)y;FLFrNBU8rC zu0y>ok?-Z_F~@&08}`cUyQMr)xldP`;C7RRpRm%zbf_G&DRga(P@BC~t5`SCS9>Z6 z&?zjFy)prCQep@g2MJ;XMo1_M&C>lKW#?SpMahK;r9b#Q67WKIg+T;S+kjjbwz~4N zj`Ugkz+lcIP;;)pYk!&@`#<>wF*!>Ev2sc+H;+QlUviS~l>~g%dQZTwPonc(k07_- ze<>CI`3nV?)WR%LAd0`ZzNeC#3)0OrYmLN8Xf^4NSTZoT-w692#Z$BNSjZ5q9ks+i}`?8)}t=+&Oo=;(-y=9DLawEhSP3D9Dn3AIK{u^)gx6n3o@!MWo={O#!u!khd<*U!L+XmaziHFc zpGpuwQEJ*6?zhn3fI%=ni;>v~vEkCX1QOpsK}OoCl$r6i*P~Z(C2U!62n-Mq5SZ@= z2}sLgUB5p!2uMSIDl7^3cM%>wXTp)!7aSq~g=j3Cgcvc(|I^l62gK2H4d1}x?(Po7 zTf8_FcXx^wcb7#96p9sFiY`*zwYXE<-QA^l@ppUieDD3-*Z0o;G5bqSl9Nm_laZVg zID5iRH`E|>Q)|)C+~7MVye~dLI+UZGQ|58D@Y06WPp!*R%}A?aE=!nnoTD=c!-Zqq zw@?jWK>cK<5MQt^eLh*eZ}_&w4o+tza0#KNxKXUWCWKcwAi^ zoTtqh16%z(9tSAU(S@Hcw;(QcU0i;jlx!J4Z%vGa1Djl54i>3A(er^Xhe7Dxd+SpK zu}1Bg=nv2Pd&b73t&amMz{-G@Xz!Uq{l1=(U+FPMBr4&LHzor6C38az4ASjnIq!}?3$F3cFLczIlPgGWZ z`N%;k^VBe%Kq>7)qD}QJA1|CWqrw8~S}>_j{rE^-Bc!ydSZ8Dlbt8JAYFq zBI28`(qg0LCd@^R!i9pgCZyv8PatvSLrq0hP5htg5nmJ=JND;&*>5b_LAU*W(?a z+4S38LYyX=YY2#FsVds*O+89vkb$HIeYj5t@@^Z@vPl^9NmO7F9f4Z?6I36H;4z1L zdmn~SUDVSnZQoclYG#Z`{?BE^`(-IZs}17ldq+YrZaz(cDMT&`6Ia;M1m6%B5@1!1 zJ!DE3iEzzz#}AY{<$1yI^6Ln22?)y}P?rvEJuq>{rakLawAjW`q~mp?Ou)ByDegb8 z@&F1+Z6TX%H47+M>{_i!#o=msl0{n-vGzSpTPUZ!og3-!;fM6 z$81~k?B)!{ums=xi(d~IEubjHnQHm+6p!{0PHI&e0Z6VpK5KB$=3$CgrDM&Ut7WHR zy6K1?!l;eF_EDL;w0vkTS{xEnbj{Lz?=+r8N@#i3j!_>`c zA{5W1P5Z;z1uhFJ^}p==0aaiC1^qZl+#bMN69;mzhEk)bnL72zi}rCeH#V3>u&V5e z*+&z?+HSXjBS6GA?XbND+l0hWyv!sO zu{#f@bJD+pi8S#_D9@QvXUM*#Z}O;5te zkKUr9-f=nP+bnQXcvq5+Et}65e7Usd%XnAPC+JC8@w1*eJ!+r^aP;=pXgyEz&WLwK z|C_UbxCnmVc6*I5>lw-ptmP+IcktE1hu|&^b%ou&+~?dPq(~tiMa5sSKBw%P;AqY)t3L_3(dP}BoE6>(z@7Aylcozq zNud>slcZFI3ziz~yCjfT_On=l6{L4tb#`d-7W`a)Cbhin0dY@}*tPKRNXDn-oh|R6 zkEg!u%>ispxQa53;XL?R$gz*qTAJQD$%_{-;YE&T$0}~CLQeesMq-OH{95GF-X;mO zaI{bZhbx7?O|zTX*@F;MEdmD`hg+!cc4wkVk%>6b03L{O(riY?tn4nOghYL$PQo(i-lj7- z0O*yZ=j8jNW8fN#uAWaSLl-$_h_&(e6j9k~p>3|2j4Nt)hCdzWIZ#uWKIoG)U70Hu z!ZkzX!0YUw#zEIlDPFqRy}Bp;S)EefN-nSvL#aA_1umCH(?FOy+4FScJF^vs-**G` zXdsgq##Hx!scLXzJeZfSSbR7wMhb7Y&%CG8^mq-!qL7-u30I3Vp~FyedZ+VVa|8U2 z_u__S1q1PWXdLH&omBrrmqyzqB2nVdhveIy9iKfcE=JF2(%bkTK}vCW3y8%e$JlQU z9}or3T(`H87)x-fR`gcM%|4Mw>|`GzLIZJ}GO3~5$4g_Pb`eHX&;2(^UkQvH)fwYsRqKU6VvU9n3G@BIqG}N1@K{4Oe5RN6WJG%PX%qY|W-x%N~ zT`4s`OfMp*#OdSO|L{&NM(r*OERVHas zlR!6BmZQ z)UxG-qbk+cgT*Rb^tWZ?bL5Plc}(Bx=(W;D;!^4m<-*ar(U}Y~ym9PFLn?ebFq(>V z-#b!>%P)f>)rR0qqh?oGc>iW_~45x-G;2T=m!SW9cnzG4?F|2Af6wbxbUO8+9c zq~yYnIBflc@xXXi)lAxE6#;r6I7up*ZM512z66vwFUv8THO&z$+ANESXg0b1Jhk2bd43M_9pFL|Pnv|Z%-DFW#iFm1`$sqE&l zjV#I%6;>FOZU$?XI%8Y2XD~VS2Q?8E_wPFHIE9B-Vv1hK+cU`w?iU)sLs>1>uS6Qy zFjdgC(9UKqd;EWHd#2RAy^=rL?m(MyYzgF>V4Vn|-nnmiq?x{Fd^!m^M&Ru`_`}Ey z5MMu;UqPp#Ca`~D`EUluRlJM6H)l-R{9A)N2zuyHqmNSTNkV9OaLnoh!%=ezYp{)q z04d#R=Y4~LViju??BPNQPpnGdutq+4pwWjr5A%0Ql+VqQ{8pPjEQorV4n9Wx4(SkOrP;LB;V=@xVvx1w z69pmkbwP^-Mm_Bx(*J@sx#YKO-vnjc&NM~CY)8sH) zeT~Phorg35jBs=C1T2&(y67(ExT}db3?Bb}>eTD?#7C5+MQ(yU{fBO>m@&!_ z^$sGD_*-d+N9PI}my;-L3;?vFiT5IcWDX)_FbpzE-%FIc9*D*L! zI{Kq6EJ(ciID}ja>=0JsJ7VuJX(EA>1iAV-OsJm8uFFR@0V5Bs%8<7V9BKu}vYX%Q zwd)WkQ80*P5$vO{q8-kNYWRy;l(0BhDO400?{^4D(CJ$b$u#4v( z-*rWv<7rVViL2Fp`gVHwQ`cD`Yo=#V>#2t)WrDYI%UQwWy~TG&FVAi?63O^t;?YCr zT;+W24q{1`U|^C?4u`)vGNJ&c7Jv5&U{uPb=w*$z5uUDHj}UGaJKn_QuO`3UMm zEU^&mwL`6wA1*dpD7@88?z4Dr?(YO!KYd&m{u)YKbOhWfvhxnS#;lFS@~ez@GaN5Y z?F8eA3h|ZT5Cr;H>V*a2*#~v#E$N5n<3Cs{EG{i-w^Gz~OlLJP5nwiP8M2{HRZPS0 z)XaQck~ksvmzf!$AHHW{@HZeKzQR7ZNd90)2&4BsQc4m;8FzSKzC!n~2`uT$g7~Dq z)Ll;)qyxIE7|Pc)@X_NrJfxg>;D{c6u@#S1zy!D+I4o6$=Zv;6Q%%}dlAdA%GCSbN zxbjkP35y3FY-BVQRG7#0dBq-1jzvX>+4Ov)4>;_;aDh1aU3(3r`By!LKgx$|zz}F6 zml!blK3VumlKDM}?wFYmX-FMA-!fZO@+8~LlmM~lY8Re=Aj^luZ!jt{aXnPrn)SBT z6xvqMzxD3?w8I#$Zbd;ES!o|@hyVUNTxk=ML-}GXs$5y_IyoV;n|R(D{fyB53|E?C zqHZ{f7#_ncmGJlC$zChziO4Cs5@vkwgsIFuQY}Rj-paRfKA*9^Y2g|E540RJX&iG1(dc@z>CEC4_JH$FLg`oZB9Nc1hMx=L;iD(S-HlH`j zP;O$`Lx}hoLQg+yG?uwWHQDV{aT})zv*}_Nar=TnPJ@JGwxdTF%waSG-Z&&7L^)zDr zuT$K0HA6qwxK`2QxEQn1i=`G>?V23Q%IO42>MuAVy5kalk>-Z_=xt1s8lvait0)4E zlqR*8S{&eyE+pYJ;!M>85~JiY8fE}`K}f`%(|H-wZv=)4YU7oKimhEs>sFeF<}^ZL z-!YDqwO#q8l4xNYP;}|r5~HcZ=DFk44qj?7LkA|8i=*kOQ8S4GB>+fuUW zx0Yat{W23e66+`Lna1UNQXiD{>7}6(lM(oSG&z6$okf3{+A!jF{>Bt<3p{lhL-Pr| z-0%Fg*GFldtol$;m-cz87oT+2tgwCI199S$aOjd>vNgr-BempmWvcv6 z!uBM0{#DD<&n6;=@j{BE3nMCfAiH=Om5305`lq1AitVXT=X=ExG4E6EvWArw?_ag# zbQ2X)mBg)90t1IA{Z01=k#OZ{8}N0jVDmes4w%a96lQ z&8i3?$d5JrG(;I@Zs&4Q0a8>ze+qHgw$hq1x_Q=PaYIzf!OMx-E5(vo%?>rReK?uoj7(oKq&UK%VR6ngJuURzTHxVcSXX z8KsR>5X9=GVO#XEBRU0_ob-ENBram!SDR2*-Mld@D_rC8Xg?-Se97=$q9$G^BxeMu9Jzk7P2t*X{7MX(&$I=7v$UF{SM(;$0PyzG@k}ye_23qtb=Y9 zXEsemD-hkUUgYZdUZ$sEePatPQ~CjnXE)k0-HA9I4ZMXi6PNF;MUP9l`Xs-m*>G#> zr;f4-sW;MAfDGf%uw1AF5oNS@x%}M%VNzf0tvA33iH0=nlRN>JTOx)Vq`cFN45{DaDdKTBNYbrK@3q z^E}%(!h}oewsa+5(?giw`(pfnF3L=%9khv3m)VvWTeV(+?c?&T!p?_!*Q&oL9d#<+ zBJB{gobt}qMz(Y%bl)2MeS+Afq`(esIj(FJI1n*1+iPf;O89<0wp<`y^X-0;G!;$8 zjISeAMkmG~P$0bjEJCy9OP7-WmG#opACr=unB@jglmGZ+ukDeARuDYAMH)0oJ+lY+ znz(+Ip(5;lGk@+w6?vk5MJ_t7S$rS1S{p*~A<5xy_pdl^$5`Tw+@>nj?+7JX*orbt z%eEz8&*U?U*}M(b+KwkR-66NIGGV2kKWu&caD@+R3v^Flv&-Y@NjPwQh!J-rAlC(C z+!`;?got^s#0jm2B%?b%aN5wT=Sn8s*m)ZfS`p+Afgewq-k*vsB1jT9L7A%5eM{gT zWK9}wc5>-8vB)aad6&+%FzK%2tu4Ej@sVzrz4|xw8*Q^4L%LAUu%vlW#DI>$Bpsr} zcf!BqB!GL@ttJ-PMkSZ(x*=1LDfflCHfjT)C2HVL=GKoNRbA+%i^<5Ac2b(yS@e)w z&jL7c4`(5fnvyM}6;zL%?<@CKwYg~Ugh|*uKe@Nt&&0X7X*&RicG#*N#W4tucw8C) zZ-hOHYkMw@QKwtcQlZ7fUAC0?=gSp9wI0fMOrVhB-36MIDKr9I{1~mi1oC45E|rA~ zmidpLnB{3r)GBuupPpWND~9wF={eQ^VuY9cJBq&X1QY zBTYg!8XHfgl~Ybz7$hon3tm*^CxX#jWq2}h?qA0)MEWteH&bncZ25~*_k?B1H)oA; zpFVl6=RgN@r&6 z&kU;p{=QpP9y#h;SF1|UuV&C(oIR&#g7ldqsiD4<%vyY^f7@GPWAw@H>@v~54iVV) z7RKH`oy_iRt6#(0b>&j%+m0A3wtGHbU&{xJU$uhOEiPdsv_sD3)h&&!!4u0* zA4JM*f&eDEmha2zt7J9CU<`Ipc@g=DQ@PeM3j=a>au=NIaK}SG8wrIbiVv#zJ)3i1 z1Zj}oeX<`DOeq~ilFRv)s?nn>njr#=-QA%Zj4{jU_o4e@m4{GN#;g~uZKLW_-00&54VO5#3uCaxm%(bMp-fu~;^h8(-H2 zGfGk*`r}^3cR$9p6wVTwn%7nn+bCR43y{sEauSoY8X4{{HE ziqpGu#ElXVzw(J@{YjE2l;t!>JqRV}jBp5|%fXZ_CBbvVKwEYgS9byumcGNiGog=# zeA4>6m(=wlMfbCx_8;dRRQmarfJ3u>BtI^E;UXJFtkUDEfYO|*-Yevg$4TUI3*EX|(j^P@n>uS+xFIG8n}>Z37yZR9a~V=^qziwQ-6r)UFA9EC z+4Y|pW_4t5ti|(W>PPkfy4hmscGMgCr540!2t=iuHRP&1Tmwp$7X#|tp@ zLW_15T_0Zu-SC^&nbtdcI-c--T&dOgRQY@!Hy-6Y)GMxT%t9i2h#3FV+xd}OG!M!KOTn}hYi#xcAhpz-f%rkM$81(v zuD$lm?_^Ybw)zMfTO<&Vu&vkv*!-Dk@Dm0jO@k1%a|xgNTiG&Nm^zS#lX=N_>8Ygh z@x?4vSzvD{;n%@J|_A3El{**?L@W zy%O%rBv!y~&qRmBrb?cH0z6$zw5HtS)p>V?HR7D6qvIXRHcWSXSD4vC* zP3QJCGLAu3N4>Z@o!Z4sht5CSco(*H(VM6$yU1#54ZRWafEjH0GdC&;2EY1?U+A52 z#YVjG)dmuLh(k2dfFYAH(yN?t@c8x!Mq(1jp`Q1F`&lfyay<1jFz3fIXvN1k;xN~6 zf+>qlNOpqY_s*(|#W|P#B+&O)tprN+KlbBosN6T>7v;W3LaAm47eAehq^!g|4L6-T zj*o1MS-&7z0MUqIA4C_#l|ALqaqy^uzsXJEYaOjHBHl=;?D^lCrHBqb! zxx?wEGmxo?^<)3p;s5XDgk`mylhMHQK2&DK32Dt zNB;i68Lff>lqC$n2PX6vv*e_X6swzZ{s@tXX__{tyU()%6jxBwlp?lOR`V!7Avhj zziPw)-iOp{>Sc=41o6jsHTj}W^|lQv2t%^JGg&6-FyW@;nShc7-O#2Nn_@c(2w-L_ z6*suq2QZ9Wt1#`L`9lo;;FQK7E4q9gubb*wxE`?b5Jsp_eV?ChkdAt~G$a1OC-uIV z@}M{i@(gbUuC9}(ThsH~86m>XmXJM&h4(AJn1-@`^me~)H0Um6$h=WBh!sf!i!`6u zAjdmhX{3{3ePK{2WVrcBaDDjvKYmPExUvFi{65d zz9>^4d-{eZNk?1I+hj(Jlnr9B0IBSr)14N-S1UlEfKp@U=>rkUKO7z3gEQ-SE26pq}aiF;ynvJvY8lRgr05xcFC#|5R38C71)grOS@ zLT9!LuoO0(KTN!1Y!J?l_)PL=%IIBC8U<>TN z7YI_u^x^A@Z>}PK785D-6wPj5g8HYY7Cow!jnjS{AA)%qqbtVKDAJn%<0HWO zA(=W-tb5HKfxRxl^P=8qoP_(?>@t<***E1OV_>&OIhWpA1T^c|_Ha^3MRJubE8oQv zj{&-UShEiB5E*NaO?DRTc}kgVn9kgOrpaFMxjlpa39t_r+e`FoXkP3RhShB}foWzorpTs)|cA9{FK;fYf>E-Sb6CL=X{ zF33RhT3q5c6ZfrWs-VzjEd!Q;^bj({?!4pYDZQs<7t zMVBNi>af}Nu~jZ$`!+=viybUHXB52!$Na{jHmM!f1$k-54vT-4N2@go?vl6A#eWa9koVKP z(-)`7*H$0ZAx`{g{Nrr7&20(oRO5SkTkul!kA)+A5jW>*2)%wrsf#%EQ$;3v8n zhDylZe$~yR1$*p<+fz*UU!;?kwX!s7Du$t~AnNgaya2QK1gXm}eGM3pESieaF6py! zho`QpbBtGW?7PCTlMyEa>rfGm{!AGNY^JTqkh76@EjjPJ8j4kcel=d3wV^ z1v#M0usPJdxtSN(S+qkF=g|&yed>SGb5ap#>(~P{+{ZYTc&oqzL#r{C4+RIyb|I5N zBu@&ya?g-0;>3AV4*V%+W?n$bd$9$dH@;6)vq$u%t>YL& zgTL+$uzlm+p}e6WRx^KV|GqefDWgkNJE6=vE{=^uR(oq5GWGv4Rv7jEo%!nTX@NF? z9G~$$2VcYwb5&~rDN?Oqn1qIm@8BMiQt5zOov(L!w+SdhsqYhRjwV%TUMqIR6P>8J0@zNl2E^ktT2hB(bDQ-C1Y3ly@aaM+Qs zH=TRJY_&h<5i+?egEn&F8COHv!yuPf=8$O+vIn#UTa@i0(VG75ai$LXVlXX#@x9=d z9AfSkUfynZU0mgbU02SpXrz(^nujr3=`&iyN5R68z*%?EIcgJBYv1?t9^-UEp`YmH znCP$b>3KztkjjeKkNfS*GdihjvGs{-jlQN@28r7cIB+o9D=8ZC`Z`+*g-Rf54Truh ze*Xoi-`Up6Sto^Y1-Cvy6xgNG44v;^LS^XY219AG05yQ&8g9X2{8$ptnte`0EGmjimZN%Yt^Xvi~ zj?~^I&G%$}Cs1UBlbF}nc*u4^##QP9v&37AIX&e;G;6_<;!Q8ceR#DxZb0}^<({00 z_n6tEyDXbOhwdrJ#JXy6rs}jylsUTINP&z4{>QE=+@+sM%FJ{U6p!GAKUPK@rqm75 zbVyX(u$Yb9Gv_ED{C18gE1N6sXljqw0uku@!UUe-{l@9ZBN+#DtrB9zJ8D zPcAFCi6Efhl&g%vLaDRm+oAjpZ6A)|Ya02+O2^yB^e&7lEG4*s&#Vo1Ml-wyDCX^{ z&=y*K*r(gwNA&?TJM8%;(WDHNgPc<7bM|rJO&I&J#vv7klZxJox;#Zwzz*ojIW}Eo zC3g~R8DM|1KhPU-T_4b7Vdj<16Z!Q>k==J&a|c!HM&hIluk}VgbmgYAYsSR3pAnp`+`Uukf?@hQIfqFrx3m04r=7vn@%Kp zGudmG_g1#_;AC1(8F+g6S;vL+K2BW^B&Ib$jp-guY=P+6=V%`zYRWywd#@waH64+m&0WCg;NCdz znc#VxV@=*5PE(Q|(Tg@Gn z-9NuTX5R#wX(y&v;2+QZzz;mOD1#s9ZUF(J3(X&G134LkFxoy&5mD{Tth6YqGY2*pOzms$A}8Pb@&82Gz!oAA zPkO7fBYQ*8M4YOk2JJS{Vbi$)hHX1+gxGiwn~_M{xXB^;X->jw0z`fz%&tF$vtQ}1 zfTyrjQH9L$j#0BB(0W|wDbV_x{3f-f{I0;6Pq7-!&3=U~e4WhJ`s@ytbdvCZqu(q{ zKIg%oxA8Us(31|5A47hy?$g3v(CUgS&`DTAPo!oQ4~B{cxt=Z_7o~5ULMsl0i$UJm zp-0Qsh0NH`hr6Xl(*f7jRL>qQ#5!@=d^G%Vt!7}E!Qe{A_$8ZxaquI5U7W&`XlfQV znrd`FOmY{Fq=pd4&BCqc(6p+&S(D>vp0Jbzc*s!xVwpCM#+v@EFR$k<_qJ5vp4Sn! zH8gnk>%^q(=TVrg-r^_2_iB(%MMu$OKAAG?Ih=B)OEi2J3}o6~`lT+%W@)79SLO0_ zK#cE1PT~F3kMA7{^6uB-h?aFCNpYZ%Ry>iPZoCk)lh)-hmDQM@mC_uwI4W zUcbsv2@tMk9Hu#gnyfdx46;`OP@~4+7p-Vgwz|NhP;7wGlmH}}VTDcK?X}5Uf99c- zlK<2jj%Yf>o>NpAl>Jfk2bwp(BwQ@Q-rCF4wMnBZOAc%CYnAx?uN(fq)e6rF`7qiLIM4T zEey)W&6g2H??(QMftGE0XS}Zz&!y|$!B`W~uJm7AUYKQ4zP1R#m=`=N5b`wCzSao3q(I*>7XD= zeGo=nh8E%PaX`%=kq2t6YNJ<}FNbmJ^^&<_8(rk0u);z~s@m;Xjz{RUR%{TA&T#pC zfZ=+3tuWY-!0M=eijx>@q+Tj9IUQT2-3LYd6P0p3N+{zBotYFim9 zuMsd|EBp*aPdmeBffM_-_-hu6`si@VeBF@&e>a;)hPQ(F>R|8~Zz^K;+$WoP4|se6 zS&%-R6gt0x#jqJi^5kJKoVtX+f8&wmIN*&kDM&ySKmwfdV@OtON|LJ!s_{$8%*lX! z;mXZSD<;Z&IFD!$usW^5t!Hh_@YgLrfR>Rnf$x% zEn(ZZE)h^lmC(o0TRWb$ot?-tG+qp{s;Zff@xb9{?n&PmH;?uge;!ckZ*oQzl?uaa z<(&8J(6A~Rf{QlhC8jlH?^}EWeT-6=_H7uhu$%6EAulEBj8#b)JCmU+Oh-tw|bR*zuXQIosw7Xsqr&jT59G9 z=tK|HRhZ!I3dVRtytNKpeJY~v<8hBQ5uoUef2=o>CgbQcA5jkC%sN_z=5RqJFmiRy z$!yW%H;QwquGi8TG{$Vs!>0PUjX7d%8?Leg>xmJJg|1MXm3ytOgx_gWr4!HLt#x1? zO{oV|;iYeF6E~F5n?qNbBZEcsl`f~dO6_te^so1 zOi_4b`n~%QM-k{L-$9a4YYfd^pLqWW)uIo*n)3LJ?8UW~^p{{(Q;vZ}QYBC+6*f2n zWpnA!EVZ4%lkN$#lFnt(uD2!+Kc>aZfF|_7wqFCz7&D^R6CN5e?pcFjCb}!)-~{2O zF5$ZrL66Ee3@Q`}&4)pQ;Nup$#E8hXI}IjNZ$1f|Q}KmLG}z~yE~az#;t%`5*VYKzkNWO}&H$@tOn9^Iwe;a&M-qyMgQ2%BYm5q|ESX1)u4 zlLnjF8u^v`)*|<>_1P!>W!3UpRN&wkN&om5#_~N>bsE$H*uW2(h=(@NA8G+D&`xEw zHPFs?A{2wNSu+l8u!p$$kQ{;U?|5i z88KxIIZL=sC;Kqmi9#kAv^Aec9O#jju=ysz8vfAQ64u`^))(o1_R;P!a5!<-PCh}E z8wT4dC|xF?gaT>iEiU6xfUUQV-ZIC3*Cc>m3s zkf<9jjUF1p&4jCV(g5T%d;+I>0L0oT~jxh9ZNs)lYcqvz>06P=LQ%4sfW_nW9b5=XqAs$98Gs5AgZZg@5D$bs3>(q1GY9BwdyPnVi(yFF$o2KA#T^oR4*{+n^)? zqa&Md7l2bVc+9tLf_@%<4k1gix(l)>TKSfXFWIt>AAJ$#0-WE>*V_yl$`&X;p8+34 z+R3vXZ>^-+A)hn&zige82<=@swPZeTtX^$x&s2m@t(_X3!@Y&G!FahGB4`)kQ_D6y z?GJSn^1a%;KD2!~!&oZ!YruTD|Gm)6!1wa#k_?O#5m^H%$FBJSb2{b;or)@ASLYu> z?9PTRJbnFb+JVmtHN07ij<@ap_9D;qkH;Gq=V=cwjgOnx7Zr}DFV&Bm8y6Igr|mic zcTRUBX=BGJz{QQ1`uD)6v}o^_v!S!(TcCcx`N+itB$?}7uksL(<*eNx;Jo|dz~!I- zNJHUgUUBItjOqKbareXy%4*epzTS8m17Wo31=O{ifs6y{9)C$>XpfzqIocVt`>FL| z+}u@o2phLsKV-I|U;lbKJN7xHU~R9fsXl6d@w;oxeCd8*7-9$N2pcV4BeZ5(7zEse z7>=>u__vC*vr~{Rc|){4_awRXY#s&v8aruA+G?vjnmar4f9M;%e7I;N6UkVs@W{H_ zQ})PQ6Ke2Yoj-e7Y*CiRI5{g~`S$d(-N?EhQd^rf#6ERU$D({@)0nJ1bz5LIDD-@E zvDtcmdHH~GVsNFmI^QVd?QnZquyeaZ?r(N`9GbDE-t6gqzK@!Xp-#St>l| zdkQknv*1@2Wc4KyzM{`8YkhvU=3gIL6Vbz0@YmzG66L(wedZk+1L_3aI`OZVk$5&) zi4fyo-)_0EQyjj}%HJ_2UtAQfT{9-}cyY)Ao-Yt}3A659yer<)5{LyKh z?OCHk*j@U&Hqj`HRM_zOV(3VHZD*>RfSt{Y={eS^9D$d18>5}vUT#_D8B5luRutVD zi(JH~-s@4}f?8;&;4}7SZe3LM*NZ=PzaKEl2~*a8FKppn2JaBD!^j%sJ<8w_GyF$C3O0Fp})G!zsI zWdC=A{Do|jIIp7G_^+Y~9|$l}|34D-vp5DH4P8JtC-_oF}GrRx&ODAJ|PI&6jGJJj{t6%K%&2(4U{{|1twOT>{})k^3`vS)#!H|1CI5`kEiB8Gr}on(S4vP&0^PLdM~u zb`XW9A^Ma2qy7Jpr*{Bpz!}E-`8C$4d~Gvz(|Tq!?sfjDYX?I3X15zN)8SL ziCO@pU@SrsOoGWk?v?;dP^|^zfNF<<#w`F$q*tBePw)_10qiLMPKx>kgl7qmf|dn= zEdh8SCrbc3Ok*@C+Y-P+s>BjRt%(T*C8G!pMe$z++QxtmECKQ`PnjSdD}W4)IT#dZ z1yF#2%?6EH0gPa}vq5a10CF&i1t6cl`|U!Istu%?>a(@Gm6Q zzrxsG&}n=HavK0AbQ1{L20#X~hx~_;Y5N;N25PkdaKNZ^yaK8%1o*mNljzw(#QyZX zLeXE4pL>Nrwg3XslUSO1b^uoD&()O^UlGdcb9n(m!Fq%0rG`p`Z&D5!kSe~V=xgTx#GBp@;cR$mo%>-lnwwcm_@y*kbs#OVgnlEDL#Ak^*^$|fNR{5>EELL6U1djCdy zxx4~+9uiIB35m9Le+@D7ghV@fy+ZY0m=1jfXfFtiCjTv#1f=W*Y2cmjuaNl{?$cl4 zkbng0rle?h0{6@VBph@gBg$oLfVfz-sg^flPa2O<+z@d{;l z5ScL_h^pY~*ARSPNOWD@D=d>hqV0Vl(W5_KLu&sQ56zz+fnJ+Gkl7nX-#A=?i? z_}3phF^uEPYY4X4D}-@57X{uLtyEd)V^(|dteKyQSB2eAf2bi4cT zH-rS_77XcH=<2VqHUWbG8VH7r{Qnra{&&6w2CuRZv)2Tq|H}mNzlxVOeieh*Bt`&P zgg{DkbOe110dSH2$9U1dvu^W!O;dRfN%PM&L-z^he_yUV0$v4VK0}nYihG6R&k#la zV|(V`nVM$2wjsnC4I=31GXRt9KUN@Mpa}o#coOEofY7M`MEEN5aFA;n6qFC-M@kPl LbuB^8Ur_%C2s5rB delta 116075 zcmZ5{Q*>a_wrreqY}9hN_+60Y#|E*X{sG7cnBap zs+GTq)6RgcJy1KO=d8mV=%pl0tK9OJT}W>(j@F`1v>7#f<(e%2+ZZF4|6<3)qJnDW zUaQUYo&SFGUHVh%W%fXp-U3=Z|;ptlmy(^vpU5@gF}!d@My9i#UD9%i8@ww|tKpn*Xd z@oJeuJ8O3P1Q%m8#zLtK3rju>Z!3{G=c9J=_9GY)yk(G?g$6Su=#F21K|?0o?t03A=f zZLk}P6EnzJ-!-~@C0ByAjXXPn80t`YmLL|M&5O=e7T@I-wXR8Qh)=1u&xoq<$DEGJ z$7FXW*plJ4Av<-N2>Qd+c}WL9iH=QX^VyshM(Z-_Cw2D9Gyj3u35h4_p}qzdW@6KX zp1i(LzMwRI)R4Zk#mf{0&&qpKl>q2}%1fTw0>h1Of+eb3K!pSSri-PnJ^#f5#`tPj z%4COaFa)3@mfyPXO9}3uu#R3nZfKl#HR%;G9Qn>D4+EHu0@E~dZk>U3QDkZ35ludV^B(`==X~+jgwOd`j7D6!ptsa!7c_l z5;|;m7Rt@%x?vFR$TBKNyPEpLA<&qDclqMKXw7{8JSY1ls<*s72vA~)%sJF+$UBJz zl11=;J*9xk4KC3p@w=j06owo$ATN|axT)m~H5Y!Bo3^|wPP~9f#2As#H0dyV@ZFNP z@J6J3?Ae|8N{~G2@sB<^>bg=cpX!3TQO>JWdJr<+AIOW+YM&6uk2;YFjj9ck|4;C^ ziVS4?|AherB)$iaEdDPxB2Z%&_@6`1>}};=5=Y6wpwup?RN~RV)ae0R9X|ZNe|}ml zgOb>)8u6HM@!7R~a$A(K1P#TyK@;Cs3n7e$T5V-Ik6zc3G*2$QHOsM}a3huBLIUx^fVaASN zZVUg5g6Ux7*P+`9e4()6#QNaFYA3s|{J$uSo^XbK`5ko>RZC*?+&ej;sG1%Ag@Xj7 zW@v>-z-PJQ?LrynGFF`*4hI;l`tw@E|CIm50ydyc{>%5pUcG;F@LvZm)Rynq{1FXL z!qps!`5AgXY)tsz_PGE7kNfNw!FnLtPJvFGidQezVG&a`v4*$ z?z#dePy&GswOU43Re>utA-cE;ttNd(>PObB%Rzc7VMY$C?9uH3hp4$Sq45ya9DL!A z${>L2=7|mbB%nr(-pht#TK3y|IQk!6$TKUWKbCT1I`=(Aue#SNO_^ib0vcz1=`;S91yF}VYo}#zwOmZT1Q(OHznc-DsCIjVN(7cbx zi#iVRWJ8gmi9)|)k&jMSnaf*9c>Sik(*A7VDr_nuLKtLw_&YHM>nC|1SbuFKATNG5yy8W%j-tZ~%`mo`vukk~hUI(K?=q zh#JsU=p#lCzI>#^z0l6SH;zL<3%1skfU5dv>U0y^rgPjxVveogg_jd7d1 zbu75nLLJgsAB31eP#EN^C2CI2$o$HZSK0|=mY!ei#y{`Q+e=k2t2LbE@o;Gb#iG5E za$(IJF^f_sVTU(n(#ZZjMQUht-N(Zq!Uwcc*af|z%XD*-VEz1oEDhnW-B*u8pk!aN zXR++v(#ocY`U3%1_Uf-0`e$t`Y#WsP26h;<3rNwsRC8Ix-l7Is!?I1S+>9fO;DCMj zpTmnXOVbrSDIxDTa@}xIzXDg@%8CHbV59=fV{qnU;!)brscN6MoExpRjl{>0!ys#U z6{jR+W3Mt?LJb(mpm}nx?Mxl-SXBTiNwD2 z*5prw)Fzs_fP{L3XAC+k1G zBS>{U#IWGN=NM+#+fNV>VPg;w%r85#HFYsGF?2CxaxJh=<2#} z{(M^J*J7+Xb-;~ExBBQ9`144vrjCo6 z8qT(}vW}4CZ&DT=;19qK5Y?p@DC`WEmVaA$f&c^jpITz&rXOMzfF0VJb2w#npGp#X zUR<2_ue5aHSTd!Lo^NMfQOHSI=kiiT#aCCe-0N4>P1hlIv7>dborE;cEk4r5r#n;+ z!oce;6Xu$nEnEePpjC`vJIv%j>2Z7L*to2PTZ*^s-y4un(?$-VG4NVfQ7R~a| zysD}yvx^_;PDKMPnu$4pksY7jvv|Lceedk+YbM0@<%+QUaFF&=Q*P zAP6*VQRl-uYiVq25BG5em6oF#1|x4BJw3e@&3G*-H%v@k9V2K=-f${~%zV|Rci_p; z{S&pZ8MIUB=J{Wi&MVG9(uR4FWCr1larkL{Qnd=dU79m!)Ghz+wo^oB?Z~emL>ukb zDr2fu9J?}3n|iRY-<~OJbwXdIA8;tzNK@ZlF0)(#--61hW+s`~?S+5;fO=ed0cQh( z{^tyxzwHrO2?_N#1{M1mK}{MjAHZ(bCAddKS2ROX#Hh4P)>E$bfrfrGf;6lX;e9^K z)k;S~Ru=F+gH%d?PTEU%qN%U%pfTmE^B}`!E}0Kcl>V70?OC6)%imeYgVQiopnZbo zska9qzGO)f5)up-NaLP9G=!YaecQpS()ZvnRl^~ChJVmmN~?7>^1c2v7Cyc7m zfn#z9`?Lg`cyRr#d49&i!$b5oBlwG&rnLMAiOGOH&%wvQKEI&A*_O(bCC<&Q-PO_2 z+;Mj<_ii2QS$kK^0v-VYlDv1{)btu-_cu5X&jqL4DutqX20s_yo}<>ZO(a@w|DFIr zvbu*m!QqCNfWF$Kw!iu0CxD!|A7Qe+N6!B7G5ZJx3W}n%E=c2!bsv-%uI`dtErw^! zuvU)6v~zuR1rzb`@qv?OzUDDlEBHzNPWKiYiz3E?5&gSeoRzY0KT?(HM0>BvZe446 zY1pYamDoy+LAp2$t#&BO2HyG&Q%F=^{sIqOw7RZ|O2>EMqSXk-8W^N_gg`9|ec3v_ zt8)A9OY?hZsO#pIH#U1yE`%zv(D&6YO!~y~H9zK*pyy!X+lAGq#lp$G_92QJR#uwY#A~5K z@)qX7<;gvjTqC1#lnJ6sXXc|0qIR#x%JKKtsV+rf6<&yDs~>HRCO1j(mxDqYJx z^Ok%4i?e3*X!;GxzBZp&Qs;by@MSQ!mb2XxlRS9seh=ZcW+0;VWqC*~VUI^O|n_PluZ@4MM-bde_9nX zWZHq29XU^=hyne!q<`OE=2%8vE;p$fB|7%WDJXWsIrusU=n*ukVPR)CA`fVB`}L$Q z$YV&oTAQwe{zhRTUG1!j_Q4S*C$c0yAE)4`3xV+P@Gw4FH>$lD!oekde0&7#t4am& z5%j>-jd2WZy4sY25l7h<6)P$!xwZ^aQc`xJ)tZ-WqycTU%vx;H#f1VVfq}0s&hiMi z82cxxLCSIOvf9$Ck-OrQmwyB|^cLxTQkMesE5{a=;w!*a@?yf1)J+Gm5TmQK-hD58 z%{UJX^Y>_oBo{N*b^G!Hb?<$Bh78@WeTaz0WuQo4VXodt+yc<(%ggzYx{PQ&WiMOQ zSZYUq^8j4ahGd2^FUDZt1S(zh@JTTnEzXA-&F0V5qL)1;fBU~h1YSLFR=N z|KdbRFu?*fPJbVfuue4o2sVb`ZqOKHC_J9Jdo*gCu} zfwI`$Z4kH_*k#?j+uI*ab%DZZMXM3&Q;6ug+Z~R(T9>}pQZ%*Ew8wrKqRS@?Cm79j zX?8H6Yi32QZXy(Fm#9$bAmhqXMR5wxL+q(Mk-dCThbn_ za5gdZHeBrokZZWCZ*3VIlCd@*QxYr!@dR*V6IGuB-k*P%5V4UXDhTN9x?&X^X~~Ew znRZ2nlPXf&ja*$9Z0fb(%XFTKZ~>+7fk9Y(J3=#Tx|Jy|fm`fG%@^&a`iztM`F08k z-`X#@icV@)gz9Qrj)-yro|ad+~hfk{KYo)x&$Xwf4qGUm!2;8QAsJ9fI`F{ z>bKzcS2Tn6DDt zY6=#gR{mARF&#gDWALnosOlBfs!a#AFeDrF-%Qie zVr?r^Q&rtlu<|#UW~^CEBZ46$?TNHk7Jbb|rjm@(v@}APt1tD-2gOnOdM<%aH#C$!eie4+MD|n3FzUV1L~uz#3a~P`StEw_$6-Bb_?+`*_9}U~Sd&bI ziP;)`bpDEWa%U5+pef|m$Mo5?wCjJ0tmpOBG$>3konrc;6$u(Id@#=hd zGhuG7uC`6Lr(GQ#!N5pufmhs$zFXdb#T+sCjnlPqO9MpxmIG@~8=|5*#tkMTSbv_o zR+g84!FVc6o9^!xU`!|9EI(+&X=%nB5v$f|G}+Po3zYT9(cd40zmbua9yJ|*obO#; zX1?Z+3LP1tTb5RBLOy1QR`vG;`+f0BeIVU=?9i93B;&0P0&DIucfQ&*hrdIjuR4Zq z|Ly0)vnrq-Mkvcl@Jd}cDk*J5oGkQ@zHX18WAv z;#k)UmK(}68_61#O>m%_5t6_Hq5CVlJC2W!&2$0FZ7T`}Eg8y3A;IL1K#xzDE>*Ta zczAdfbxjX;fudI1mCs`{k_eDTNxbP$PjIjZ?;`Q%`Ld?N5`Z2O5&Ul(>b@+^4dO}5 zDpUBymp=u5QI@eGK4uGI;k}1U(u$3-!34J|&UmU_K|08dB`Cqq>#wLwi*ZlEg7#XD zVWvR8v)7XCbov1%H*+7I=f@j~-|wRMO{u+H)1oJcg5`4uzx+xf`0xn|fG%f9#m@=W_q-WXB$Ws@mdaTtGQ1XHP;0b8|0qjiC;)={ixp1&UXuLP6 z{TuCP3DbY@4BgtpMT!pMsJ-^Lx&AI01HmM8-sXxBF*wTuMhcscr5U&adq2?dgeI;mI%ZX>b;5a0cOx69n35(TjwmLtjgJ z?0R?8f>QJkbHO~hHCXR+&b5ThcZCG04Klqa&WbN9MOtqVmQwxbt#0MDt4zO>9IAJa zi*ACV%$%{+hY@mdm`@&ps=`kuuZ91%OyIu2!!u6}h4c_pg( zY=~1|Wx^Ki@b|~hv$J!Cr`rv7xBPI@@Z$sb?J}HAh%1fx&g$FQv6`AcMf3J@$6y8u zO4D#ZttK^vz_OI%Gs6Ot!|>Iq>#z5UW#50&$Jz8hF#vTtrKrq-vA z1ZCM>^gamRTTS{SkMxshiw>xR-UFcrrXJr|k=3zC_elnHzHw;YXk_wi8Fal#8XWq9 zwKL%jK80=O9`-g^llv)wVU__r?rC{v7t8GFNS=aVcE`#85^t~}8*{9tgd2O91oaC- zbA|WqIq5R?XAw%dSIEFv=n+8c8#@Ksf4esr5=^aC7_2Z`SdEe|(l&+?e&2|~N4^Ri zTCsd%gBRW+Etpj+SSB4MoY26a+Whyc08o}j4H;zJ3>yIZ*7q;l4B-zTZL9l$B{OVk zAx}d?<6jY=78kCbynt7{y1wpH@A5nF2Woqi!azitvyZVt(oY$+>+BJOw`iWdyx;5n4%o&xZJy2wDHCx+r#NpMVTmF9^bXdRq{2d*xW%v)v*foqP%l}9_ z4wiRq)Sr>v-rVrq?wiH~rz${9YxS}}8&Nw>Y^tL(9WZ^MUc1l=;SHZ1?$F-a>giT5 zzC$W@weH4vIJF{|CYj{&oIx&P79_lu7tOu;%x&1rKVI9l%ikr&7-HOOVgJ{BIvk6& zwY9ZM`Yw14-m1O7^GJ%b8&P-Md4WxrMhD+1BYTSyNJUP`EUT^W>O#P z?VKW`FacS}P>*{yLWH|mdCGm0`YN%;?MlgdT19MdBe3OvMBH=s7S%AqVMTn$wRYx; zuNiRcg05*nT-E?24efWfHc*rmdlW92q1yz-7wRui5mO(OX@vIVt<~dPYfQl_N-@=k z4B71v<8&YS7?f%6iz5u@eY-We`x!f0KW`9jfQif%E)Y9o3Qsjxo4wXI$Hqqr=59kX zfvF>@-(#$-h^DT^rtjl8@$u~9Y462NueEu8=d|D!kU0Phz}rc(Qo*va5-n@o?F!`@ zY;oMm1uTTQvU3EIR#{-nar{nZ)VMVF57=JYM*&kpgfnFSU;vpW`aGT}LCW^hGPaKk zP)%lI+XcyUYI-vDez;SXn<(Gck z_`6s!*2n}fndjuss*qPL#FM7&479}31xh%lQgea^p{2v1FZZMl(m1`ip~dhIi^D3Q zvNk;(zoT4~Xqvfy6A(^hyD37gdRIkzj=3!^GRwi?_71zqa{B7XC#115H_wS|d^+O5k!sapVw}w2sq(fq?-!jW0yE*b8V+g1{u$B%ZhYADm6= zUuC_?+<;?&E*D5?kToR@dJCz*Y?>>Rk#qntItoc z3$_P(=^d06B~oxnoY#U89g^2+n{LMHnpiOWOiWA(bOq4me@6qMLo>|aJ%dI;8O2@b zNmqaZg%mnExh>7v^+L{{Bqqf`^QH61zvJZ-Ngmto+`(Y1? zEJ_|BcU{OIKg^b#32-dn`@^z%N^OBP#WVoqUHNsxkLpQNV%2hffV1JN=sF#92{SJh;Iff=vwNgubL}U=;0HU zQZc7fFz?bXE*aJ64|(2{w!Lnm1+VC+5NNY&XxeXuS;I5l6JlZ%RkXEPYCZMSdNl#w z@CujluzD5SFpCK7(lw|^VNH&N$T;W$OEA^GRtQ3T4_P?{HW|r?+Vl8Nq`Mcw^-mll zPv*=Rqbt&Gd1>vUd;TuCxb)ar`t4MS=x!b+jyHGQNG~SkyEUr@T6e9QB0cMG;R9N) zPqaogDo=h>^eHI}{fp5>7_h+sz&sEO7f+|sC!iIr&P2*1zCRanNIEGKu-m7rE%KK95S^Z7{Xbd8LCk+CpBaD_))TDd+C8VM3WWOkUGIvN#6 zXII6m=QU#PXaG~e#Tuj_OU9Ueo>?qZc z-*0CpH?^H;*jDFgH_diFu32wAzG|7Ib~}=oaB`b zAT%Mcu?cu04NErjz2#4$CdnkhPZ<|Hs7{Y1FP#@``*ONr!lPDXQF=bG&9mxDhzX1G z)a}KS&Yd)>eh;*2TIQkX&H9c8f&us9I&{AGHzEU!(rZOEbTsCss1qnmjOIM?Im6M% z|9EMb8XZ*`n>i^3zW;DZa+NN}>-O%9ih#emjY;R}Tl zt;A+~?aH|#mUVvCoDGa}Ry6;~E-v=QrpVolih6BgQr0msPnK#&vI-TG3_)}ts(yax z@M`LA(L7!~P5Jxx4S`-8sK(r4^WhQ^BJo$PKr&Ax%ggUKH8RTO@mf3@S{=KDu+_YQ zgYDhyya$B)){Pncccl31wvQaL-p-Z}1q85%OP7@TX^Mv-5vGS=Nivp`xJ+DV2b^8k9F^#~-Tj;2z0@L2hh>+-dO|xw)OjdQ_vJ2|4Ha? zN@C>0!z@T~x_}R^52pC-xMhqkgB^S$`ucFsSY}7zdDcr$I3YCjVa8vt>!}L7m=eS> zvcsO8>_TLE^)cB)I!*QA7!c;e5P6zqjQ0XG=PIX1Hdff5v$i@-1=UBFL4%zCN)wPL>fTL$nGO zPQquku%w?zGT^Mn0s$ecc#MZbd_hu1-reqxSfy0wpzSGZT9rD2dDv7(tN)5LTljY> zQ_Nj%EbKGeOcCzt9%3Jz7Ez1+&Gj%&#$`;_+CWk0(S4jN_kv=7hjI$ zA#ezEnIV#8Pnb%^?feRREY-s=WJu^G59)`{Pm)SBVfzE7SuPq!p)E2|As?;Zy_SB} z7Xw{ScGrHpfOF>}WG4S4GxGh+ltK0b#B4OB8M1_x^&HTN^@?9BrtPJqqq8=W8^XFq zh_e>_^5Q9c6>6DD%7U|LPKwg_2Tiw;k+h)WBG3ck>oWGzBdhJ02uB2Lj)wklT%T+npinFi+)sxXQreWb~uvd zVp==FrTbs;Drszlj!4ltzIcU&ZH^HfR$1{?Zz{VZ8KdvczvjjvRwj_=E|YVRTZDY8 zF@fQHkdu{Veyab;ZCBM6(dFb_Qrf%8r1VMZ(WZe zL+oTMJ$?4(CdkdrjX7Q;F)`NwP<5dAT$9UF)DvCU<)z=I)4h(x7b!7@Zad`#lm%T9 zc(vM940h{q43FM(slekX6NHB^*(uTtDy8jp>$+&kmKHveU$~u^868qGAfppuv)+0? zdFY?>N~C5dtfL;&&iy71ml^%jTW+K^pXa{1g!p(UXvX1_M`AQrYDrr+sbT%{h|}-vA#*&(8b> z=Ldp(U|}AIK90FnYa(y&WM^k*t>rzv=Bx;Jf_r7D_L2`e%LN4m#aLMxYH0}(!(?E^ zU8$Ghxki|NkIIO~d=Lo=9FWUtAb?6-p`?%HWgZX-o{^!stJ6X{Sqdi_y+kVD>-aDMD2BL@p1AbBJss)u zGdmz?Kk+8aZ~XcxvcSDesO~Ua{XD~P^|+vVFy&P>t%@sibZ{QN=uU>IVQH9*eFB!& zsB^&n^X#bmH&`rpRFG3p0?%8{)@&6y^%2z|438i_v*pW_rXK|qvl(tlcy>YQO4x8) zk0ivgZ`SGLcpXj!fZ1q-fx_+H+@$%(1d<+#p=1dPXE>^?qlTNQJHh>3bAV@2JTxX5 zqtoZLNrpa6RzPPv0)oa{Z`wtMy{woTTvU)EEntt$8x@{X?KtqPYU)u@0qz##X^+Hy zT)N7i6Y-#++)*~~-$s^dHK>ri$7ZKbn;jczn6!ZbxexCIa6*$P>SLXiG0Q>(5?qv> z-`|rhO-Anh27MC2torW>dW4bWb(1I(?}sjBz_P|*W-KlPLL$i}81wJDEgA6|e{Uwg z1D(07yZ*!9C8cXkU4iC!`g(|gtJ?;iPVn%)hmg?FZD$eCl>v6*k%|zw#gExB#M02T z5}51*9QxJ*zzg51)G~NXP{5=Nyuqk7#WI~D`C5esk1rTH5vW-sQ#6L_;GvguT#uxo z_hdSjZ<%dOr4>ZK)=BH6ddKVQnv7N^`NH^UzIf3yAu2o$c;8qv7gRTnsxef3aiBsw z4?rabDFvwtC8l*lKC|4pdAKyD;7<$N)z;ba3+@IPV1r6P9EHG^Q`XNyVP_4&$GH8W z-ZIUi*j9{XzsZOR)5|WubS)v^y%RDFe)$#bBtM^_vQkn8avQ6biH^cP>|s3ZhuR?o z<_5=kl|IF^snDKqzf}2&G3)m<@4Yke-=A*rgiL)y)K(OwObG#L~~FLem}YdM;lqs*X`$)Ph}IzgB|9 zdMnYn>_RqYa0X~A z8nsR{@pwmbW}NGaQ^%fXQ`9#%W@x<7Bm>O)0~2h>H2PKykUy7~!8JL@sXXvmTic@- zQ$miPVT53yoPuDGrDS6Hbu*gx9le_Y+waOW{U3=D?P>6wnQW+jkLdBxn&p0KA9fr9 zEEPyg+Ai>cq)SB8@)*fWB)hifKU4=e*<@Z@_z~36olLFF#3{uJHv90xb#Ls?BsF>f zb?c6)6u*)*@1TJjPU*tY$JMNmb@D$;EUsN;$vb>HTk)}yb_bJt%#eOad&XxqB=A*3BB8G&}>fo zi(GhS8QyJ2{@B8+e%vK%oyi({f?0IN`NVUK_am50Fw|Nisu4rN7$>#d=9S=TB?mk! z>fSR#{Y)vhf*N)`?#G)n0`Lh4KzIjpmFY^P2Bm3M3k(N0uM~5jO0DIO~ zGD^K=GrblqU;w~ANO}nHWoS#nu_2LXSn_9W}#B<|$SRH3N%CBk9YWmxb(da7TWBzfy^h zOgJx{2LoIMX=P1r9ecV0_so=Tdo9fHb8);Odk!JftrjW%of==J#ThWsUe`;qXf9^A z-fMF|O;tv^-!evOG$a74D%(O`R%L_~3yi=(NQDuJ6C;p((vZ4TWXpw!pRG0H1B5gOt$BQ$8!06}mEkKmz_Z%4!QEp@N*JKd7KSpO|@h?GTv*ijV*4n>+MRD!iIqllc^&^q9e0+TA zByn-=M1gqrA0@TU_NMKXZ2OFINx}$Zf30vVkI^peSB`+RvamLL&EO9h#9DZ*k9;fH z_fo2t)Jf;5_X^R&eU!RNcBgFBP0^I@eCU!e;8FtaacuH(?MI?zo8>Po_s7=3!EO^? z%p~V{jP!MPop?^5fL6|}K+t2Il>i<6&R&>;GjafSzKKe_Sn2mYx}`o^HLhQ|@3Bw2 zAnYrlq6$C;iq(UEx)YFULW1}F&KN<0l<`4~5m@4&_kmcQSe&_R-#-~Q1)j3}elWXU zHpFQR|7F#v?3_p@Ks|gj zK;v&FPi%IbM_{}TONDwFxS%4b0v-cM%Vp@;ngC924g*FNpi&D%Lqk5oGZ7Ma9t#0E zeX*qAP&XY|bOuX_h4`ZwnDYra-Qp#eK1VRkD(1a#*{f}7pGX`?431w-_DF|;f~d7hv3icafEAJ#q*X=TZgN3=@)HPN0kK&JG-xihEW}# zW}u+YoPYk&i)c@*Z!?M2gw4ZpQc`5&Z@GFC7cF=58=-c;<E7Oph-wgQRSpi`knfgWE?c;GObLwRrivXgr&2hbdfQw;QcO&YiUu&ObG*Sn z#O>-%=-o8e?IlTB3d|rtojVg^l!6^#kU&dxJk(8@uXs^7V&{keA7rFO1vv&w09xyi ztz$!Ha}l=ciay(z4)BEG92+Uu;SCXTm)ifpk+B0;UOw_8En6^aS>BiE6XjRIUouZg z4b7DHrP@s-4rrG!hFiYxvvHoT7fK6!M6Ma38Z*dZx)I|O1jrt`rc=JI*?(=~oghnTpvO_Brd0#@esKnIU|{O=U*8o3>;bp#dF)g zXT?d9c@4swnX2zK!I3@GF=wKG5Vdk!sQisL*6R(|9MHgp*Ha3|N6k0HKw#qSfBlZG zs!nW@#Zo&PDt$~g0rBeo_ww(b@r)xwc260k8rocEXQx^A_UyW}jrb2xdY~YlmqJA~ zh>}r1B^Y51^qpSt?QeAE&}lbh&&|wCtjhP&$LxkV<}3K_o`J6J0atM())E5~%jSTg z{7`t;p4=9M&LSGBD!-42wFQv|8$ZggS!Z@?)jMRg(r-_5dwZjngP)iQj1gO!>gt&G zGC2+vK~l?O@M?F3DSYHzYtFcr-Y|XH&plfM?3qR@@zJ`n2O{;`dln=9Ks?AM&r1V~Swr3~45+-@D{}Jmt|_LDiSn z%H;ftZF&}}r)|0g0;^lxrT7v;)_oJoi47-x;2!&T;lY8{5;JQvDo{_C%M8CX%`C)e zhM9yG92~3^d4jj{R^Klt=_>@077BK0?y2%K z)nyqP8uukDj9iYccmn!dF}7{kx%&Ix5fu?gg1m+;^w_I0FS@!^g-_bqRpC16rhaJx z#=jE2m9PD4N+#lKmw)9U-NA|MghLe7`f&nX6;sb16&R^69q`Z<8W|D!Ys-h0A?#aj z&sGvj^~muFYq}viLaLO5pvq%8)bkf4PP<{&f4Moxaq zF%@|Bd7lEMihfT^#qpI%bZ!0qYDnn&6M<(r-vAcsMk z7ZQzyTb-n(*V!<2gp2t1Cm>5^_&xD z4$(I24r1UkiIaGqS6=PpG+0Lv%DCD$`77xiP$8++dUrhK)mNRsK<4u5tG_S%v>YwM zs~g=4JqGvwwNWVncZM*%xqJ)%bI?saDl$5ad7!kek7e$G7OVNRlBCdOgq zJFCzRE*|>k0!gx%^5OSR5f4Fj;yS1?w{;nsGa4sS4k9(Nz1UKaYRu#^8}{dq`BzTK zJHC6Y^UqYZv9zKB(opTBc61h#Du}nyWSX9WLTn7M7TF>$*H{d&fhez6`il3JSEanS zJeQN}JN;(kyMRFfqc^puJ>ju%+<5n9edsXy$`Aq^Iu7!a-zv3qQDRm{hd7&Y5IZj{ z^&QLB#Nbf-Bc4Bujdj0bvNof&fA9OL)y|w1n-^9&#QrR6>WUyW?yxR?_@(`i`#5Ca zNQ8h*L&|%fHiOCrc0T#GfH+=VMpI$}E)}j`%-kFrtx9Z`U=?T6^AXRv#J%jiP&UgI z45yCKYdJPi96eTWF?5NPPm^G>A|#RIY`NekssPQd%#!DP)6wPSrsjiyI4FBd6F1S_ zi5j>~#>ORS!(_r%>8LdE{v0+KSU^>HAO+Bv=4^Gp*_GFXpuxo%5Yx22SsR8{|K6w` z7MDwt-cZuffwBW1=PSBF%tlOX&`9-)FYv8HFpdb$=NDaBSp$uG9*H-P+5s>%KHsC) z6n?2+aL9HmO#FK?Z;BF1kC@BfbNK8VBh^n+eJ2}r26&C>y94ZmyC#L`h=XfFRhK{+#EpWieD2)sH=~PU*uat2*w3e33)a1=G1>Op z(QLWM?E{_1(^afXXK|?CL6Uulw?7fC)(LFh?!!@`JjZ5lXsO9#+`txpKuAlU2hGeA zUEpQIf^N^>vCAKC5pwGpm9ZRv@xB5jbh!G}c6PnBIq(XzoFqKp4RzuF?2FYEimh8( zS`r(WTP9fZa642U;&=1<2!^%Cr*jrN9=(fN%Dz*#BXV-kYIJ4E9M90Pll^0CgolEF z!XRwv@)hH|$fG^9`U79GE$YKux~`$FUU_%4RGg^w@#4*N@&i%=hT4w)3R@k(u{JS5 zpTn!jc<(rPnig*wzaXDg_X9P#yF1`G%SnsaE@$E_BuSnEYOiXY+M$@y32~U82gQ70nF?s_BgYU_NZLQQ5olY!JyIQ}<=HYBI zmg58Srsxuz`U&SQ$A404Yo!5jzvVpLDL_V#YAx`WLT&u|+68OBRlUe|h?UX8F5yW| zPKLhNSq<_R+Qk3|wO9NH#VfPn)I$)lb0d2f>+p|J+2`U z9c@88ROfjUiF{A7?s*N=%tb^*$)7$_3Z{-+_wbBHHr*tDUEOQlYW1kdNRY0gPSP98 z(3;SRMZ3!ac4AN7bIsePhg3GFV_=p-8zX0Y{GmbdkEmJO`*ZZ}4`$wHm4&x#`xily zAb$+G=A$AR9+-6r#CI=lMKdrc1Vm_yG5rwA@ikB8{#;qXNy&qp89L?!OnVZk_h zImm8FJ?Hx zp?#*HtNr*LcoJUmrQM;iT7)99vAcC5Q3ijOu|%hK=qKGS&8lRxa8aOj|~;M zJ%%CTAVw@e@cG`y7R|3*AZA3yxpsmc}1AF9J2U59Ob7(KIqZ60P}6fQ}ibGR9m^Kr(dzknst0J-tYmV67HAv1iQ_T zQC(+dme=50`x>SnvmC3>n&(S4AJM^G`o{NwOHxzk`+L=9VlRp+W`Aj7l1*4z<7}ap z>iQ83BJ8LndrDP6qDZc9%^IZ;E|s{j&*a+nY$<{dS|$`l)l=@ZA-fpJsS83~t#m<0DZBDD@7@@;vx@@nLnZv@x2n{hAIe zsx?natKZJe9WjfZjX3EtX6GI{q)2-%j;1jI{2cr`V#Y!nmV-qT`&NdKr+5vWxC}g= zs`u^>Z&)*-W)%rIMR94iZa`TId?->WZiIP_N?5?`=TPqwOghQS{0x93}`fqDxwPoA0F$1(OiNZBM)=DI)GRws+u^0Ch& z*uM`qJEf-VTID9j$-#Xp%PaP+f9HKmN{P>B(nx8Ma6aaT9EP$nZt*}tGSJ#`vQSCb zdb-Wd;av{@5T`}f?0It9~ivB4W%)v;3@?R<@qeISDUwq^Mo5fP=+;zj>3 z-{OB1zwvq>9UV2!>N&7Vj8eI!0uiB*5WHmQLGEnN2vNUh}bYnWp*RoR@LrpHnN%^of+Cf z)%0!VX;FdYBlNBLY0pg#Rz#XE{vWQ+DL#xY+TyWo+jfJ-wr$&JJh9oRVPo5N<1|TQ z+qRRN@7}ljFu%QKKg{c#v(JC6Bk;CJs(JZpAr5}iC3ACgq-6jN1M%46qIH%mO5iBD z%A1#1fK25HT?k;tKPC0L)B!H?6KMZ zQ8@{VU_%!4SCOssTBPb8_0gOaOpti42MqaVPEH(>!PE0|o(Tyf>&MW)E1vXTcEntG z>7i6NKcVbJH(X>a-L6)*Z*Yu<_Bb2hlyx8^>99`nn?j$vMjC*orr~(Wce;&FCtoKx zmSR(Xb{g(htTZ(@h96WA2OkicF~5J~N&RbC-or0lj!W*~z%dK_eNl-6MF|<`oE{Qy z2l5#3cb!xeDMOw~o%N%Ad`uK&r1i(eTKYM&ktFm*Y8ZXKK4Vdlq8(#=SRk^T*pyU2 zBKSaOyA~TSXhs)6s!Zhs`9VD26Oxk*I!>GJ2_UFN&B}n5(+qv~Z$@|KU%Q>r|NSGI zW+Utgo+V>zJ4+6`WO#*xjgE#!_Sx{}$-A;eS0SF_k3+HxE64Nn=)CKiJJlz;lYFsy zfQ5CF_aapIT|*-^G%XEGWlyJ%1xJEY+F_7NE5CoUPg0>Vv%Wka(RYrhONx(gn7vf=-iWmemwZ!Z#v7_ z&%G~#f|WjieK%hAVY~I@RaG_8(_zlOlh==KFw4RhgUw8@FRFcTO9fX=O|4q@&TKhF zt<^q5G=U?1550aWyhe2mF8&uxl<8G!LjvWjZeEA*C)^c|+mpJbrqYi7LELf-FC0%7 z@6HqgZ+1jPL_o34`7HegKcBeG-7UYMjVaZpxx!C?+5*iI#dTFEUVsE5E7j*4^Utwl zoa}bdw-Da!0#4ViDJx#10vi?|rZb4%_}A85`K=UE1iCS<#N>>|!EZCC0_)@?nn+KZ z!VO2Re&`94-xKi?sJf?d=H2v>nV8^Y($6=8y1=aGmZI>joux+Q&5 zkC7t)>~l5UwDsWI`{WyNwbCIw~rt$>pW-pTXCk4BLK4z^YAmRHC5&haCuX zmrG;M_aox~-kHz07tD`saBCK<`4C-_!lS?2MIQPBa|#9@hKTLrQQB&H1}}=I_W%j)uC_Y9 z+frT(+npdi>!MA61(j!!jiq0?vA?+=UNmFa6ngW~xH**ls}XHa*)i7;^tj5acnw%l zjZZRz#=J$ShL$aNmih&)x6`P%XD)kaOy?^>ov8oNc-kOI%XDxP4zUqr-oHYWfN>|_ zb=17!ciU{#N!%CZF1j%so~Jhz^iKjoP@?pDHHL+Nn91k&;sCW~b$K+}j7o)%LJ-lK zh&}}#(|QSjAN1tXKovLA(svUNK49p7rCpm9NI5#0HcwgrVnpseH89^7$V|)g?BF4$ zw~4ef@_#&;WVs4`pD#BDz#Adt6IDwx{(w7<){8JpSmHz`>b z4b&11ToO0OrRMZj?R9GD|kLbk^{?n^~V^Ja+a0%hf7h(#z-R%`dEE5ZJrNVL7W@Hw*(%{5Ddp z83wE6LQh^rMcWhXTxQs`&T#J~i5E9hmT!kXI;#pPphrVRG*KS1vbP2WKi?V>euJON zZ#~u`{If(iOR?dF*yI-J5B&ghp`yx+7@hp}>(`I|xU4V8zzhLlke04wwxhZAGOs%A z_M3}w)7P{^;8DG8GsI338KVGTD}1?9ZaNhB8Lq0Tikzsz@3(@jhLK9?_!qwapmVMA z#5})5N%HPf=3d#M$eZ0Eoc$#;9VIiN&puHSjpKN~< zL{77g-c*RO;oN?%RTok>o`{1Zn14JqQ}VnMu0-6e7IV(7ULlebl(q~YfRNbPyge34 zxWJvT%qhytRD#$I%nkg^9bWN@xfV^QxTEG<*SK9Uy8IwO)~Gxzo+NxxV8YMnW;O-tJx z`e==+swrCk9*$v)Y*_&IQ}?q!raQXHSLp6qy)D>=y6uO^S3VHnKyxuDDJhj%>*iBZ zYS!21TwGk>qoWzA9(TFWB9m`3ydH=QbJ)nrex8Npazo=h^plog<*vPJmH9x6(bl zY;9jeJF%dlfxW!a&fX8I+$Odyk&dVR@!5dEn_!@d4)hI<2RB_&0qGl!gcC#H-P?gF zI=X-T=r)z!hZ$hpGHFTeTgK_8^ttK^oTBl)mf7875fkXS`O}LNGD$1v()?hBUz%X5 zJ3@T_I9cQU*{tL4)cqLe1U>Z6t4*}nk%r~wJW|W;@WuzJ()!l z4=>|Rip=6{|Jx4I7=s7a?ZU#sl5UGrLO}ZIXm$7e2-3u5X~~(s`3RXnc`fneI@)8$A_8p%;qRvrbI4F{`f%8*UYFl`*O55tQ!emJ zWec0Z51m3d;;=Hvwl%rRZ5p}q*$ypLM!zuob0)s!nW7$I0vG!qx}g#XOD^8G)*479 znp}hlpL*Z|2e)qIJ9T$w=Z<3P-P9(s+EmsDmQaX)t9U>o#$cVs7gl^x#;%#hw}oaG z1BPEXP3Yw%G7Huo9CSE{xfz7nA;cy$cO52oy%#qLGj#<}ir!q;mu^ z&dxW8jg5^JVPf_O5ni99%n5XYXf`#|fefOYjCK>lkt89lNOqCUK7{-x@zfF9kSXYs zLAbwZ@*N3vB|4Y$9at@C@I)iqM zX@b6wiou~R2&U>&8*oG<-UGJ>aiDh>IY-$h{bbwO8Sco-2PFOAz~~FcxK77an{jZk zX(u5=TSc3cmzI8J;LR9v?mqk%i{CSL+Rnz=PqGdtXV07zGy_t`j^TwSVZ63Uff^zgHIDe{n_Are^`|H0A}>@BHV0!4hag zp`g$4KT0>Gh@c=aem^wuIgskb-d>Pw6GyI5VxC6Mw)>4$tEmf4R(wr>`n)VE*hrT ztc7o>PF%2d&j%;zXA~TycLbOg=oLJqxeFUTPEq!|-)pS)e%nS?Z8;sQ)Lpcl9Xjv< zF;E^*^1}O8fZ3?N5mM7fs%dhnY4ITzzrq0wwH?#6pmoP=7o0(h zuh7>DPBlJvafEfTU`9rHRU#E#jAJx8UHt-17yD|KtK`>FJ#?(VDwZ^#LT;P@AF2+s zK^Os6S@x;;EOig_G7~SvtPP#G$8Gp4{m(DdQuJui@BR-kY4Jk@6EW=eP}i;oVWKZ5 zw1%C9rE}LOUxYduUStRLi4q~WRCf4PAiu*^{9s*rtL`d2BX6!iruOg_~62p&{liGY#Mxh3DP(CjpwL}z{7R|{IDt+vZT zeY1~gEyUxFGqYa~)k=N4XNqp@ zjpbYMOD38veG-c~IZvIPMufH%J2qvulh83f{-NU97m`P^n;87X-YaN__||aeMS?wG zlDwdZbJiA_%#u=#Ger~h(cr{g>+kPj#8=o`l`^eB1z%&FAN3DGk z<=r2M`J)cb0f4Rb6VsCYWr4oOber>+F+(81;)ryiVeO^rXxMUjg{r@5daA3{^P0@t zjwV_72;xMuy1GVD6`^tLpC8j#h`^xi_%{EOTK_Vd>y#Hk)-#n`Ond@ zh%d7cjTEZv?w8>(zgclJh%%~j#V9jGe=^D)w%;dgZ5;UKy6xZ;N=JT(e=!rDt<^wJ z4&+oxvBXZ8^{FTb4+T#B| zLuP|DL?lj2G>{iN1#Sy)YhsgCC5mal43 zo?6&z2E4R9H_N#=w84vp)7qqbdtx^6Z! z!qw|ol(%^{J7U=woZ}O4{GA2F1o?JPw3Ui=b#-Zo9pYNQXG%LE6IMHgU4mKPO$Uj9 zp@dYZ5q)oUy)+ON6$KGOKze!B4iHO~=s-afJUbJGIn)?B)mvMqrKM3K$IkAA@VtK< zekJnmE@Iba^68=Q_guOP^c@rIUrenaHY|a3-rQ}&pUAnY-7Qd?YQF(SNbe=TCfA|J zI|G-xi>nSpA7`hRmzq{>#fh`<1;WtwjSbN~2VEN%;DP<&e~B>P1*@{WxRY&(hr^Q# z+(x>^mSt0=n(O8Y&5%S~6YLO8qt9N2Lo3S|l!IgRX_rO9{t3rQk;zJ$PNFGCMlxJp zF7N=Im&BK^Q>*UoZPh?qj@N$7-8RzsU0DMK|`kQ#&(^!TLGNw9W*p|fPvn0+TaIE z+O}rmY;|=tS&8{-H{pTRE{oL00(#CK67{YfV{k5syIn5>nHYefCmauAG(Vv6#>A;& z^b#YlI4e}XYb2GADQp#{8=mD?yeS3Bcr>8-<%#a2c-8}JcHE5XaLjpJI1exwTpyF! z#J5|)!)xh9Q_*iSia{T3;%z!xGKxLS0mnkVnR@rye;tEU zq1ctXr$V7N`UgDN+21_1?w+hepQQ0);k>-n z`5CSLcX;Z0Ci&!r3@82c4BqeHs9K@}jO#Gj5wV<2f`BP^R6x60xQJx_^GrvgRY&G+ zSCO2n>r|V0OeSGUPiOz%$4h~|KREi5<#1IHM17M3vspghNd=S*WWTUC*B>b=^rs0khY8?jyE)z(%gEv;ab+l5sA^XDWz??=;;i6cyd)%R}C zYp_QbkgbA$ZL_dKL@AqJPDS@?MA;5S+!uR&v7DKQ<%cU6%vCE5l@!9v-1I|y$?rb~(*hcg&)nSHSu5<*(lhKNk(A<@!=+07T`A^Y zD=}n|o6}wEGSmT09_L+g2yI8fo@*=rRf5cy05RhxXy&Z$Hx|OqO%ieI+2x+d(qpv( zFSQr^x@Id>0?~xELA@@0!+AWd76;&+-;~WnFU&p(SFsYCEqCf4xS~V>C-~34oZ+la z%Xr%ytyU~HwToW3#Zs2f>33@5g`w{q^5MDfX!O)}9th6IYpmX+1yfvibXV)s5R7d? zGSX$XlqD`K7W9{!6uyTQHsGcnB>Ts+NizrQ0BN5dH&M$dwMzVR^J@3>+GfuCmmh^vzL)9F%1n1s-tG-$Yet+ zE1JQjYHPvyzv+KfGX-Dv$p|RxeOl6bfaro79`zeX3Vf-}E`K_HQH(~Ouq zbdI-M(XjGBAX5v&az$KP@Cis7ch~2gP8J(i#-1gQB>s3Upb4c>AP9UuOuLrU$dxSY zFLr|X@mnlA2Imc9&tHvO#oinPEnj<~mI7jdno{IIY;w*|Zj3n(vWO7J*GWyd8ys85 zbLpm4ZkYMJn!jsEg{fd*G{qL%m(J%J+MiD66`K$x1|wt7LK4&T-~_O~BuwcF|IMbZ zrtxoO#f20Ed@&fvqkh5($c4?AAZ)XFJ@R{nPd$v7ZX<}P?Qz(JcNtjJ==GKe$i9M{ z(o>TV^p8=LS_%|?rMki_IE^;sMdLYH(3J@W)xqvmT2k&z{x#yDzHf43q8X3WiyYeJ z*EOv*zs0|x^R|F!j|!yxDCk;e;oIBw{{?tHCrwLm=R6N}@Q-_39wk&LZU0E}LlSGu z-P+>l#AZ_W#tTCb&MuGBCRF?&-}%5cpFD9qN>tfvQ5*K?-2FemA3SDIO^ZAG-#%pySnvL zTU)!z-p-0+r!{vxK0H+$L!0HCNL?;_@Pl>Xaje@r1bjJB8< z7B+Uc!4VLiUi~)wgE@d6Z*2~COAKe=ABupmSeux5Y+$c2+%hE6f!V@dK{35=vC6km z5Lp1HbL+0S!)Hr6go(>ZK}CcN?FPFL*zSQP-`(P|km@%rV1)f8mtDK6$h9yNgwQWl z61S?$ypqZzS}jVu(BS+$wsdP7{#Gpagi&c2GYhEvLivk6PQ3Ds6@2_eR~uHD2E#*m zzjQxTT1_kl?rHKevA1z(co?-_llNci^bqzp%ySIxAmfh=x{-F~cl+w3q#tDU#yKFx zzukVMfzNsGFu-VPIp4yY2_8%}q+|=Ap9lG8kaeSU2L}KESJ_Cdh6A#3pIF-K}eIU?aWk^(2nc~3@lP=cz9G#5uW0Gei zMCv#O@NmwPFLcUFJtE8#Nz9a;oqv%J9xUlsB-r@`_f3FM#|br@9vvB}+4>flnKkPv zDs&T|4~#L|TOs3O=YMaBhzO7Ee{)WaHme7mq=ISW5{HOgwdhjd-g1!hylq$^s=I3@ z{^Ab$T-5h{hA{2x`3S^CB!BR`LX( z&1mT89T;`I&Cmp_geJ%P<7vwJbrMHEvnI;U$~WLPbqN)uecTK=hnMeyEoiu7>@CgZuzEj8!my zL=qk@UYmz&=FU_lk?5yX_}sVascty4E=a2MoE)eFfeKl!6o(86B#DXH=V|d7(E>A(;IeAxEp3oT`Fw zUvr!#|JU94IZhan!L(7bCkZ+-lRpkm6vV8L=+Ao7ube0k%8|b`u*VUi^$EZmu}4#z zSo~k|rpJ=H+Ber!pz^ZxhlB2o^5yR#DkGMZRSg4e9*qYxKi5k#leR9pXG#qfIYmpK zJM-s;`03kPqHmure-`xuR}RceJY6YC&6s2KXXU%SX07F^%9m~q!4Vo243i1bkjpIG ze6xfEA3NY>IKBMX_1U9Ipfmt{U+y3RF;X1Uy$EwYXs;i^$uB0vn0eVCSS0xg30=N^ z$PB1{y&V zv3cPWBjCJbbYPij4Mi4LL@b9GSPCGOfyO)<>=+ld9DE=fF?6*c%u-c^a9%E0w#dfNL;Gl`L~6|o9L+4 z(2$ktXu@$2vEVF0sAO`>#b4TbosQYgSv=u^eJnrnbpojI$r~EZgWbD}>#e2m)dXwn zYjfpyM7rfU`-V3_L92vX-kOC=krGTaz`n<72*AgVVEWHm2oaRrDCmjf@2zW^Y!)QJ z#s$M1ZMO-srp^Nnon%WOVx_a|;>W+Mo#NTD2m92Ag%RkGwcSK($~!Au`0aZ>99PEf z@C1TM%1~M8dj|(Y%3O}y*ESs^@p$z6pw2@!=iFd<19X*Gs=JBc4Z@-heCP!x|1NmP zvINVvA}?$l9UmL#@R*y;{hO&{ALlNvzd`9HX=_wNVzdCn9adrCvIs=u)*Twn5O$6* zaY}zLh8mQEh}YLTQY4K=x3IW}3nJ&p&;DEBV&O1b?f?Wc^Yh7cECN4!YU^U%P8_(| z4mQXibqrtoCjZCOTEv8O1OeO9MA>6G_WMULJNSfw9vt#CW#6Fm)G-#V#It#AGiG9yR(GqX#e z7Um>7FG?f65&`3vMH96Dbz3t(1`GtG3kn1T_bcMr)!N?O&f3A2S=H1kDLxo7&F}yW zCaEm|5m3RPR0*vDv2Q1c${%q-YDKUoT_KsV|5w9ouHC%XDusOh2P=Fa{hQ-PLdEG} zz1CYm^Z2O^VTddmL+-z((TYi4&(_ZnF{f<(s`h@)_)HD1)iPHc2E4N0dr(9xox0Gv zhZ#R`et5$d>81X&2Nup%Tjty&Wo54fWVCm5WdN&EqAxRF2&*(1nwe(wAA!kwhW9|M zRN|Adz6RaaG^mBXqAH`hFN+|dmJtDl6$GzE1njsnoEk}iY6eUd35ECX-V&>oP6yXV zm!y{5Y-WnrpN`F&9z{V96=!R3Jr6hvL8JQX8$8EbXvOg*=csA5gIC-NsH}A&6E>k{ zV*qzOscBR(uN(v4*3I?p#YNG-)#mCOLnF4u3!~7fm;y&~dYX-ZoA)F3okTtGx*)PY zO~P_iIn)lOVs*DO0jP)|xsIdeWNP44Fx=8tZ)mX5@?O2#31VPwa!S6(|1u=b!u z66{39a`fT~?x(=2r7r@)lzigpnz;s6HgI^;N<>JfE#d*LaRIma_M6|L#QYl?hfQ1^kP1IH`{Z^hj#YKHZ*(lU=yx`5GOT>h!XQQhu@SafcZCu9G?$c zm^_8^7-+6O?;r6JZ3gmiI##<1$)D&>b2{;k3=ra8w`sMe)y_ zk0psuSZ{*~Tm2axXX?5@wX!oJ#ZvX0yRM`f58Uyf#LE443?mnKIj)2RKo zZv&t}WE^QOsJZa&RqiO>Ytn*0I3R7>zXEEj7@t|mj`%(!5tPXGAfoJ%BZUU*`&287 zJ(fiwqi~6!$lkaAPUJ#2L9A#{9Krl?QsI`@$KAiX4<_Zde}cm77yffqo<=&hjXm{m zuUepo&C;(BrY&{qJd2u!uH2!aJNnujg@ZLf#DqOI#8O1y-@v=&CqB5h80V1InV4~9 z&Z@7qr-=9l$eB5SG}<+)f_DB*cUYMIh@d&=XBXNdgt9ye0U-h8WbS)4giakpU6>fF zA~R{a>L~gxBNOsz8%a-fermXM~nK#ir(pf zdI!6Y%CIXYTQ1fH;hni}M-=`ohKcMfWF!*uO4aUe?)q{Ncs|BBd{&+uM`eC4RLZv&{N*K_`WkQp+0*RTU_V{LT;rf_TlMED{ZN8D!R?9}zFjz0!P!#-U;gg? zg|2d;SDpuC*T~)NElXI|6nO}br%PbN2>nHzU9+IcKB}KRay_`JK>dhn7Q=Yg&Lnk6 z#M@L!oWeU-$3)3J!1gER?|Nny$k@&PbE(CQJm~Q*AMaEi%1n34&=1?THE&tASjV$v zatiG#Gn-JB1vR`0ZFQjz1JK_`TR zjwj=rU%CslX=_?Jp3M+f0)=;|*Q&nEM>nQjHqF8h6ZpThqQX~#(hoe2X=zghp#n-A zfMP0+u7=_UNd(FgB2LF#XT3`fsRrkM_n2` zzVVd*%Ui=6dXqh>}MOg zW=f&;ZobpfEOs4G2$86z+-qcww5?S&FpZa0_^F`6^39QLgN!ZfzHU2$L@q@TSy1GL zFU(rl#}orW$33&}4~r%0x$jr`OUR2oS*M=_Ikp?#s7&wo1I&k+dmpi`AE$qoSK||3 zpC%1k`%2t*#2+vEJGf^XTfVITmOu92T|T@T+7So#W?xuiem=dKJb5^&y7ygXhPeK* zyXEwcLw9sPUH3uN4I5@6Sni;I1hPM#{xC-UW{#GfV*a>x$E{N&(tC}j@nx4?3z5$F z{QbauIqHXy7W}w5N#S>gBVqTrqyVhWP=` z)h?aeG1+_;7~-762e!`7*Za?%sw=vyoVS|5o%VdKqMM9-Eo;X+G3!74(`ZGQk3y2k z8f)N)$~w--ccT9_0i-`snDdCg7yR>^4MsFdI~7JWXseOIE{%zvkv~)-F{6*bn=}~m zk>_;kA_SCd|B$^1RsGjg*QhKNXhlkM$nDbY=yN?Awy_QSr<1aXT6F&~A)9=|A}u;`Aje{lZReTq; z^EHwA{2QH=Ic-R7cmDxCTi)yb4OJCG*3qj;n^{FU_XhOxbtoQ!DZ0z-CAg~VBnW5& zoKF~E9JW69%{A2x-44a+fyqX6w@LZEqR8^&q?V<^if5E+J;3kr?I_#OSG$2S`EyJ5 z?7Vcce=8hYeU0N&{N)nuM)CTNwkmUJG-ti+1nR>E{pnP2dGXCfxPw@;j~UnnSvW@T z2=fcq^xx`w+mZL_>}bD1I|>x&iD&_$@h1A^2QN5V?}_*y7;1?BTAWoVFt2Pp&x2?9 zzCJ_wUhSHp`^me8UT+P2<~-E=_Iq*i&(lr4IQwL>yj?9BU;WVnOfUnl@9#j=BSbQ! z;h1GyGCG^e2c)buLZp-z<~!%%XqjpvyH}3uhWr2t1@+}CN8O&@B>3m))+SKK6bF5| zPIGOtssGztur%qaDdn2gCH>{jzj!;U!@75!?U;IC8%FbK-08Ve9-LX#Irwqv%*Rl| zn!jKu*}+(XNG|Wg|5=sAgd#zxvWxo{yDsHb(qZ4^+2mguZXe?6^!dIEcZv|~$GIpU zjWgp8>V5%Q6wJ&uq`{{`AvNGEh!4d|LZ@3&uc+9mvh8$#nGl^)p+Lj=;_&^gFHx$# z!#ba!WODskPk`<>P5+mUHy?9W#kj8C)Xf4oTX>vU18 z*3;)6Q$as72Y~?^Et}=bIEcQk**MUQ-;14;>6Dj$Dy7zI zbhI##;N zsLizrJTF#*HAN{^qfnHN@Ln$r1_r}&A2esxvWdEeR1_E>qZ$ENWIasyRC=RHEEsqwlqq)^bF- zKl(hUIm>0uAl_rP%_2Hu^GO3+5@9`}&|_gcQO$DWVA@rNURl3ZR<4l%Mxc;8B-IW)Z&`vLuNTi^-{qbD1#%xE`86_TuS(joy_o) zs}$Fo0M042QFs!-*;NV{FOa8hVL4)!1VM%0Poea}#8SaHFD3`Gy z$#52SLFuQQu_{tHZ^z?-O!PiNt*@DvQxRON{7Ro3RC)e8s7&UzCS^Vge{3GLh6Bz! zukVgPBHl}4bRM=Y8ZaRSC0xc{oR--0bj#xYgx05lUn~d&L28a6SQ$96xEUQ|d7x0r zDaIYPGskp0cD6pjFutzizNVyp%ES$wI&M$UBz&-c;<^R=V)>UcM;nv&_oZa^GS#`vau|bg0u%e;EoWvAo(|_ywi0| z0AuOsu5gRGeO48Rru^|Y^6Ei@Zkv#Y%t#xFTx4IUfB>}?BOJ944(O}uh?fBQVHT#& zL;x<~dYfUXvV4VW0roA5WU#RQH%B;ZsW}X5nVlwp$Q~#w49i+}7KX@+EKBv8p*$H|JvLcB@^%=5S;UC;N!BdbS6x2l(pwP;i^xiG z7yzzW*~Iqj-0+bal1Rxc^WwJ+{^_GxPrQH?^9N^$hfk?Iu0GJkr$7;+pkK63J9bpq z*m24U!z$i$hTePy%hD1Ux#Ch~$&!eQjUBK_Tv0%=i51#0nHFw+B^aa9W{%_ZHH3|z zB-XdZp!&i^BK%)#nAzLfRb5Us+#CqUpLkf^2pVo4X#SQJdET=BhZufpJFmZCMm+_m zM-*>O2E4|<+PJ65<)}qZZ(4bp%r-naxu~2EZpHlEDY0JDT~he8l8{M7qvC?bs-S5= ze9U8>kdvVasZ~n5wjIx1#MyYL$v2D%# zNzRoLufoBgv~gPrBg3pW0hH!unHYr8Yx{zV3Sw(l$37@sz5SSp^n9WnFIM6;%VvEp1?}?XFnHS1>G7G@Bo%$!;~UX; z;^&%}1Vk&IV-S!p2Zc*Y3I_t(_8Cn^1%)Ca&HHs)(){faGrSEK0KB|=-J?6g7Xq8` zE{T_EvFK2@TcR!@@@u*xJuAe^@?mnerG5(bVcUnJnzUn{9{u|+y#g0_h4IH`$~hvm zK7)O%HNRR*MA-+J5w`#nf;krH_8pLByB35!@SVvgzQ)|F_wz{l_ec!R$E5pA|hST2{!^6o*tEB@}%t6)07j91AeielZaHL z#@M<@3&Ruto~;zXXMksA&bzJ}(4mJHHJII=3-Y6xqqaZ}nAC~o3G!whl|ahjIHcT1 zi}sQ#6VIKyOSR~BV10yfSf2J7J=G)6l%aiBcu{fA-cx#jU74GGcnAN0mBxX6aQenU zapm>`s~5ej3ZCa1B|Q{x5+8xqAvMgs<+YN8dSf?XfhmJ4k&XCgj~d;YX`IPMKDPES zzv&ewVoCiBU?oYh0mZpuWPlQejc@0NKaEJr8h~}bz5T_W6@!$*o)ta|3hogTht{X7 z#!DbMq(N31Efa3qvnm7OqkQb7v$G__+c%s&j{!#MEt5o=?=GVn5hsPZF{oh@p%v_? z;V&Rm4~E>a= z0s(PyCe`+#TL%e0DV4I^h1JzOhTwI{CvfC`2pu`}akwoWyUz5FQxSmeI;L8?stR9BP9sO`^Nxxt~|j^xUPtDuph6+;&=TQ51UixPcl@X|koYnCL_ zg^0ZX61DU7&44+?*+MiYnsH{$P`m!55*n9)XeN1h9`U8>)Y5YCFpdz1Eqi#z@(A#g z#7R_PbuTID`p8rsF;GxV%1j$Gg$?hl|W%H$dwhPG^Wd@<}Py`%+{Y<3tXwAajUjIG%5ST-*C^TdEay}JL zdE9(nVr_sk3@!EmM~aiE&boGdxej}>lV;ts6Wk&~kaCWM?IHqQik~FtPN^N|%7YR3 zj#_Qm%oH>}N=XD_$CM(zxLtnb;OP5>>IY)XCJJ%Y{Gg;;70fh5zq7Mx1J zWOKMsWv)HM)O6t%ugrX7?ACL+nRb9WQ334nn?5B%?Vu@#a=(r(*H0&*zFjMk{2NE) zAS*dMFTjd~DqG-0_`$Ii=>iuaON%$X7X(3MY(D$QO5O}_6VHf3B{L)rD|Uzqj82u1 zF(o_}!r#%&o0^u}=_2RQ;b&{KqmMgKlpF4NELKh%T3QQW;guGn=!cgqB<$VvGTos& z`cK^+Fm{HeNvUyt{4@V82t9Cz02}L;#(~DdGL?XG=iKI7zZ`lY(dv8_v4z?b3?m$6 zonN4C<^H6Dsg%>yZor+Imt+-A0cZ9xO_uKSnXM>_y6FfL<>Rf2%*xrSumM@ohK6j4)Tq3kd~ z`ta6xO6p~JhU;&ieris}#$!m9Vo4?kaodHSZ#+Op2G+I#J5$Pr3_Z19@{Nqpf;@fK z{DHm?%cI`S2+}M!JO2Dg|EJ7FzB|_`frPvXwvU@u8p+Aeb}Hw6`V?TAGqS=U-RvU5 z>H^K8FIbpET{BEMX;5AoMP6Dxp>&hkN-jPru+K*_!opD)r*nc)2aw{x>7?EjLr|QF zVf47I;bLnxvgGFe!8hd3RNZe?=V~x;^g0wB9Y0;anO$dS{ak~0z&eL*@S=5o zINV?5Gqe;qNHiV%`U1q%1;_E{LVtV5E%-yTIt6}hJW7f36)1G4BCX_KJ&kJ2@2%Lz;=n#=+s9 z;C55k?tB#}vcFTtc0gchR?Kq`;--nq8NTSq!=Y_e@%BYK=N^>q;~X%}wEC9-UDEwM z(wQ_vaL;91gN~Jo+Ek#&L?y}7Qcq#Xsd}q_M)P45XYy5V%kBHF3mca!B=*LwNaI%Q zfVt+*pqEZ5S1z!tTDIvvEN0si((1I4e|@a&1}3f)GyY$_|KI9vQlyL!i$)vHRG&FK z!Rb1UCtDT~$!?M4l=(Y55NP8%J8ec|6t-y(_b1H|);~eGXW+t1PGGpm7 z5`|om8E|m4wBL`YD3r8I!3Hy_Y-%D-e@SRb1mJOJ_6<7pwpBIuM80|c3DM5tRI%+5 zuj`-%STX|n&2p0_V&;4~!1;QE!y&THOmd5OSD7Dpjf8$VqdiZYPuGg-yectHEsK)P zu7=xKD_~;G7&D2nBcw=)wZEcFGCFxV4Yeu}tilZ>UR)LwPtCFtDFhR9gqKt-N;~+% z1MctS0v)04D~ZR~rb>%ED)Rp2Y^jabPCD$loFPNOeFefCi9M19-BZXq)K(A}U_MYY zG5q0Bmz<vfkW*j@ylG z^2Y||v<5+oAG4>==XW;VeD81mD=Xi60K_vSi)||Va<>0A;8epe+ja+jn}yi((uQk{ zM7|*SSlXVm>KT}IPp0;d!&eVs--L_Y)9Je>M65U(TFvvevsc+>Vm4FF!v-X=3|`Mt z&8ust;nHX9mj6=&Uy5PjOHKELPFQ(ZkF#mwsC}sg%L2A3F2mhJZs1zurwx3KrK{zR zE0=30)nvBx)bheL9{Ud}e#_wD)4{d$yR0grntK<^f3949od)CQQZ<_AF9gVlRe{=R zH?9QOja=sXW5`4@MmOlQJ}EcB;fTN92009i-UvE|$%$0se&9h5l9 ze;ol>On|qmss$-M@~O*tJ?~bxFIEza{(C&N>U&5CL^acxQ^M$90Mwt4-ZRO+$S3>AZQf zzhryr{{g>#?p3^STD@H)DrovnDA&62bGfkm*8D@qwm1rIPZWP-$62I4GbLR6-L=FS zg)9ENSrva;w;C(w)4sl)afseuEuvc=V%9PCE(!Ur*y}hD8R?Fx4!r-N zVOlNG@Zjl2727wR_7L7C#;-!LEMoqO1G5zaWg6^wl*6En z!P}ua32n`Q&;ds>lVSPom~9$l?WZ&Fkf0c3?>zn_IrTGhvFh`ozXNfd<@pz-=WXlf zSly{gk`bnYwT;a!x6TGb=juWa_*8ts!m7I4l#MX?yGCI;C9aGc0Tct~Zi|DMVleJ( zdzPK})H{twda$I!nT6m=*|#6oFGb?vvdOc6Bpakty1_dgOxgt)T87eZQ6q97jG<|_ zAs`Ul02S>+T=qqi@pww>_>|<$K6EHsx**VU$7(OV73{?wr2{^sp~VHRRaY2tx{3sf zY^aV>7(ptTPxhzDuadr-z%$_8kg!@Tzszd9}d-{o210HjW zs$kTvNN>@qhM8TiLp_>M>w=1{G<+RLy zG0ZM%ct`H_;Mm8VgewW{6a*7sNPzT%B$G4&Gb>w>MAK6>=xzJ|ILy2 z_mCT;Zq-7{L|W}AQ&Jb&iA6Qd-%W7QxB3Y%<$Jai3wEFMX@q(5v5c-3mT0s9;k1&- zI%vy_-4r?^c9II|q0A3rOXG@(xsRbeXlmr52yp0y zFWdgc4VwzG?r#wz_5#4}Z()XhWl|?htc4zwPPThcXVh)JfeXcJ;)aVe{NWAMcIFN`t@?pS^5qeL+$+8`p!u~Iil-QW($+winq?%C3t2%oKxj)kt&-M0 zW}OE3`70S=FmI#D8d{=Pz~RN zCucCIVG}Vxi?%GJ3I7IkOsfjiBBF>ukX7IW4_I^#iEyA~)_A%DB)knkBM3H~HjM27 zf!M|(IAOe>0|XXT-3$(e47H9S$odKb)x!{w_6Uxc*aK8Bk0BV)0|bnN$O;jT4%N5< zL~IQoupUswCO7~wwFwHfhM(t}hL6K|jYxQb0E~nq$PPt_+wlWu&Jv062_0Bz>!Mz> zksg@%0vU0r8Y_zJ7L^cSSQ@Zkl;LDEVZ1yIGSIdiH_R{B3WVei3x!T=hh8~P3p7!o znZOmbY>QDgVPd;#SfAhy%oN4ufJwLz8i=1omJkX&|DM(ghbS}|0F}uf#b$#;c+dij z#AE z{S^Z#9@m^pWnD(#9{?c|OYO9`$5J zcJ;Q3REOzhTV6%>ICEmglN(J`@%JE^+(NGkM|-KW#{gh|`))uXM-eC1RFiVrT(Mu6 z{Gw++d?r8=6l(jJ%JXK4Q~jUM;yikMI`bN{b!TUPStD`-7NZwx9het&q$NrqW7R zgO=e5gROV-a%zlRkFm&VlAiIbcM3TJS;rF5rfzNwB~J{#D-DjjZGl-p2^)JVmFdWu zJ71s3&1p3Dk{cv*c#ucQXZjIrW-?9>m&4Fhm<7O-7H@Xrsv^E2A-Q%Dpy3doFi9nV z8>A1w*HHxl<8ytMI+EKKbLz@aI3y5yxek5x$Wd@GKaV34Q&&~Mutznk|BJW{W+fLY z%5cVe@;7lf?i6+iO2<^j`QS2!q$2~|SCzQ?p%0h{-=g=kb{2nO zwJ8AQ>3-RMXnv+(fp0N-6K~Gc>6C^Ry=XI!^E6qzdTp9cmzH+9GCHS);bw6Vjczf` zWpXvGdN9AhW!0={n7j8uRu}J&0An-%6)o>ir6tFY^{AM1C7NcxH&8DlVVEz5SOFO! zQ|DCHo*$Z@*&S8#;yJM7DpLLfBf0JSS04ah{CUkjGMRe}T9rl}Xdzda+8C1gfY%y7Y?CUs>xITtIs%H9(bc>wE{H>qUMQcx8 zy+uaPc??0K!WLU%4f%3lCo=Lb7d9OEP4<0Pf*#fpXP)?C^k|C`>fZ4&R)lu8!S4X_ zL3-dlsy9QuI*P+|9`upWkJ*#=7C^t{478+YYZ8C2M0v4IEBe-BtG5SLvN{IekzC57 z?_|%a$){EK3MzN0-$;H`bgk(8TAFFzsp#SvPjU3VAH%pi2;lp~6R-4opRCOjYMy*J zr^>RG%I>NRiY~>&oBr*7IOlWJnuiP6u)zmg|5BZgr{dpk48mrjx&c8LP29#QU+`N} z9Fpg5#<51@ks_dad|1@n6gm6sbfq|60(72ME0615RVSoOJX9}yO;;!UMn8-5DRo8j zM8fkzs-$YIq$Ts~56X;8p#beExPw>2YHKwV@%-G55WuNt=xLmI&c?YzgxCdiV?o7{ znX$SNSe9gJM6;8of12IPUS*)oOfNF*@8Z8R!XErUf*)N!YrJ;@v|8IZOjeuh=Nb@C z*oA3qT>Z8gKAhbD-M+=2x_RpS7RJ!30T^+f%tZ{~se1CZ`S^TlX_DJpQ_yy}Hd1of zv>W#M4v(;&efrbB!@s(D>iq^dEoutX0VW=Db2po z)QrS~UBdCP-UeA6kHHzedCWoY!?hv2LY>=j=W1H?VAtx>3Cb+AOaa2TJ!6Ft?EEU{ zy4VJcG5vt$D7mR{{jq>j6X7=NdYmKm2JQ(d)tktFuVkBZyDkjuMa~8o?PIZD$;Bxm zD`?Vs7PSKxxk24L|6M1=1Glk|XT;Q;YoiJqSW3ODQEzYjXYU^75OA?zV}T6wL5hhswqEDh^kNa(7*1|x6|_P#b#02 z07^P$irTc_z&9HoNWp?ZT(ceJ*Yht-9K+8BCklQ%&v_+yx7vHVTJ6LwwVejnamRT# zS)3UxSbV66tfrwi@rSu=EBza%3yo3GpmdPw|TLSRzaB(V40cF!v=KWY7w zxEG2|UD4K`3VZ@+3nSYyjFN!&IF)h~X)cY#fr^E<-`oLd^`Q*&$OZEJp~)koMHQXM zYr4LmF|Mnd^EiBSkeYM~eK@U(#+cnP9a+(8vWJMk(2SZ(dUbdYL^9wix0O9$+)PBN!AR>?g@}OUH)1tZ zVki9U=#OuZKBEjvN;cgupmM3QMl;mi8j{wMyQDdFeldkr(9jfINUC1g&v=Tp+~=}J zt6lhHP?P}y1xq!&2Ek4Za|6a|?6?+&g_#XR2Bt;=0-6u}*Gf+nxB-Dm{b>M#2-rk^ zQqOEN(Q&`*1l6@jFS)7MC=mV8CWBG7MquIyrkF`f2;n??b_+61g@ zBZt`wxOBX2q}DfH6^bANzR-Gu+yAte&6s%u$WDm?)E{$2Y zN>jrDm9EwUD!tMNbvUj<|2nvQfjw{%r8dxa{cI;&=(2*M1Rfd5dO!w6zwvk{^n2j5 z?R9Zc%z@p%;AM@*P_s0*j zbPxW0zdd2CJ#+Mzhmrm0b6H+oq+kAvWM+Odti%uPaf6KW*9OAV)Mv7lt#X0-Xl)hp zCSkzuoryrRr>5d{1OPJYY^dc8bkC)$H!&8~6lFEWm|9mLlb)H*iAQEyXCy~cu@H$R z>H+)L;=VB6il{jxQP)tPxOGg?0?kmKjOn_t@rM4{c^5Raj>l0`(1_U%i^ z)YR$pchOUq(R6jA{SzKIVQ($Sbv^BBeHBV7%3YTB>^C%pW`JpU#Q9Y^8#LXOgd`>Vl#M9A0(yMruKBGLi-?*M`aA6+1`SL2Lx(HMrhkGQc#L8SMKg(jXbpe7(Oq zeb6GFV@IisWdK+@w_t*T%fEfMs<7#;%QHRECOOD1=pgIbkEa#2MCbps#pbu{Lx7Ag z?chiXstKg!N3t%Ol&O6`Na0Xw<;n1T5akM(3zns|r2LUcI5u_DvU&)Sm}M+$+W|!r zlu&FN#wE?FMbF5p6g$;mM3lE|C~E%nNq)VnBU5^U_*Y{)DKS!##ble^tMt ziCC!i@bae7h@uHyC``WDw`rMwI|xMmoQWvMYmF>5R) zRe+$hnvh>;2fJCBjaX>MxAr#QL#bPo*`R!P8vRF^m8lu}xv-d&+5D@}^mJB!&423u zqkS`%NOHvY!`6fNXoe8cqhVg6uGv9g3GG-hE<@BtuR4KqtL|59t*7p{o={vpfm0)| z@J{rAQRn-XFbDiI!vE^On(-|;t+-@pL=%tH*ivLyud-mw~}PeHTGG@4qC{?=Aq?pC3A7w4u7bfKo6GcwAsT@Gu5My+}Lo?Is-pQLSQx%6Ooi zt2FxobBi(UU+?39OCVAYWvQpkZcr3K?6}YQKZXBiS&J2veg(Bv8`Zcu*-Yspr2!MV zrI~MGBWsc>fFO=kV*}J2&*YsdhYc$ox#B9Nm+m+bX-uR>aM7(!fK^rRs9P#sG!b<| zfToOvh{P^`rUOy-5LN9Eun2Dk2b`&=mx2=tX$MGh_zByjU8J8o3N1#+kEn1OunG0;spgT+%y0F^+vae=Tc_3)mj}u$i=Y#n4Sw6rEr9dW`Y<0 zn4ZN=_f^2(rl+`7F1a1hc`>}|K1>sWJPu`9Vncj1W4epZG+Yq1{xCH5RttHsAYjUF z+679{4nc^(o}P^htl-TgM=StL3ygUC5xQE792nUGIb4;6ylG?|Oi~~dDBT=|aM%{4 zC`~SawE;Tbn;n>WoLrFnn@N%h1iTIgqD?4Cff$2o4h=4uqzJSa)DaSdt!$sMZ3T*Oh6Qu75x1CrfJIC* z_;;2v7PPz~0~zf-3L6y?O#&XB;VK-#$xDBk02!Onj%N*9n`8YmLpF758ML5GQOi>- zp37A?7fPMe6POI@KmMZAtcUr|rqb7)%5*eGc3ZezJS*3CcJo#80B~=#+~aPG7lQxj zQ~e1!2lXkJy$yDF-#*#)et&gFW4ah_8gGn$Y)MR)eSVO0>hbyO`1l~T2N-4@Sfb}L zRBUXG*4xk-sqqlsJ)yT`ihJyQ*DKYyjIQZnsd$@t{Gly~b!=y$d3v>7Ma=#deqcV1 z#ek1TL`}HuCoW@Z1Hi~QcXhZoy8W;sQtZTl?|5|##8Bbo(fQlxvSM7rsQ3HlkU7y{)as*j8%-^v2Dkt<@hB&=)y6G3R_Pz!aA zrN;v)vufkbWHNs#f{60A<|oNAQfBBYryczM%8+cM#m+^2nn`%(qZ%|;8jBlGoZs?T z&1K~Tprxr38{qD_JN;I*AJBW*Z2jDi9eecg>y=+~e1|jt_~j-_f@RR$*vBcq$3_|K z3s1*{OuDEI7Iz!63Ot9isuV5)l)V($f8xRe??Qj(lqeP~sUQR}xM4j(3BH~&(6HQw zO6dP6s2T9#Nf#)fot1g-1@N51Z_&vXD&56~+x$S<0XRG*(A|6gsoTA6-3Xqq+dhA+ z_7kt}{Gi7X;-TwY#fN`0ghgL1vBOn%^Mt69iQg8tsdTBXm}ySoUJbp_-98*sQY#0m z$vy95j>HuRXWv-e?5iEd`|E+9BHP7WCY|MgI%yHa_{327c*R}NN_voORWW>;vP|u< z#|+&(0eG=Dm%wj-Xdgprd?E=s&^v~>NNlPyL9#BaGD-I+J;#iV!+)X7x$PbiD3@eI z5by_q-=NOf&Dk2S)~0ZXq#RicjW+k>K_dI%Yd);@mJTWO8b^z*++Ui>RPj5(pDFC3 z@@AImlu3E^xbW&ugBDmuUYo4hW$tagh2!>^;m`(r%MWF^7Qvn+7Q`=Bb7C@OP+^4^sl^+ zY#h;BVOa{RYx{QHX@pb`gM)`d^n3i)wgq}RZqUTef>ql)7nTmYo!*wvce_@9BCn+H zBRnG@{`f=FAxvES<J8iex-r?2f&%<{CaF@%uIQXi(o zh<#}4BsKw>w4Xq4lNBKc;;2?hGEeIR<7gYmN{itfoX_`nAp|*pKp|xQs5QJJlhchP z2N5LO(|-baIE*`5XT*Z;&kpV0$bfJE1GM<0^QbC5aKRUXh({-nCzekrY@N?6BoFF+fP zFuZdsPQ1Av^g@YHD(E@8oB4Zscxt?D4eHtb19`dP(b8!W0I#xS z^#JpLA=PYVRIROmK?=7H)>f7xASm@+-@cuw;&j*NAdxlOZ%(D(3XtsI?z&)b7?9NR zR=owkz!q!ju2KLZfj%&~WVD=sc4fcEK4knYbLn@$30M%^Lz*(z4f^M+pj0G#9>)Yml+BwGA5C`^ZL7v zc+F6bJ`N0y`ZLjQF>6QzQB|hk?{ZPNoE>F3oZKKQx3D}Le}5GQ=S=)6>{FJ`cuc27 z3zf*{ zJ^ZTWU1}42R*_PQXw%+Go|zPxH$m z3g>gR%<}c{x09co4a%Te?|xSzm5y~gbj-6!dvQgIA2s2VOM$HUG-~i*H5i7DCHKj2 zKeFmAgd(`KSdxHlTA(o4$}#8Sn|8%*EX8Uu^XI$pap(hhy~$ir01@CKG}PvhcW&H( zQsf%c<=zXGvI+yk$)!%ptwEevKSe){qcSKHI0)ZT#>oH5RV-1E9bLm_3}0X*+&wuL zVbZ@-0{*~M{>n`GI0D7HJUx&4+~DoZnk^x`G_*x<-N{?%l+Z#B#ukaM3V)iu=JZTn zbrwXYKuHHw@?t~pd0^NE62VPka&3B?Dm+5=R=}vY^O1bNreHAmQGw0l#A6J%3e&kjrTrTJ z3DT^qL7zf+)VLQ&)Y3770bb_JiAX7}a&ky(>L(0v#N82@`6<+Jp&`6YGgx&=I6IS_ z;TbJVPeGs*Eiez>lr!tIBX|4y(9s_~1P$_3N-6YLB3Yll)_%r`b@bCp`W*{8fo6)> zkC{Xv4LqX7ly!mljFa}Q(k82xwaZ0E9(Lde_wW0s=p`0#AQTLsqCO1M7YdIRA7_j_ zjT9d+xC{Dz$RhNENWV{;n7Hn_DH4?6=T9@ltoOXDO+NBC;Qr^RD-$J=x^xAi$V1;1&})7s_0UXOg)!E_AJ~rOk(vtJw9%>7~gAm6oLKPo=YI+-jEE7dDcs zB5Bs`Iu^>Rl1C!7t+v{g|Kl~elXV_Q%SY9iVvALqX54F!qhZSb$9lX3bR?)a6&q#N zm|`?1a3!ru*UbNS-$zi5>o8(Osvzq_5f?dAb&n5@)O*=0{0^!2n`S*}a4$5wE+a{l zPom9)heON8FY&P0zSbR0W!&wsevz-FQtv9FhBcbQn789&ef*ZK?2Lle=yTtlxrCWB zlM}%Drb}$ube~H!;2>!qO5FrKgTFnWRu?K2C4QLVh-s*~`#3(8P@T||LL4-D9mr&y z2{7hhFyUYz`hxVa4CJy2s7N+QsXER`tyaRS1XU=S6*8-k&TjlbN7QOPmW^E? zjS;I<3_D8s(<(0-xnK-atby|W2$>Gm=@UiNd5AR}4QWae@S#HULy2mj8ri9I1)FZk z3u>QQh}W15Do9=7`toYE^zt8$=8f7xT z+oOv|07sGi>;Zi{#418l+ewZde?$nl5$hQuqW=K2La|!<#F7ZXF>D~|?aqkT6q9sA zc^t7K+LxlKxm~oPt#4AKQo2RRx#%d#IYG3X8I}--G?42#RP9RA_QF-TDymhdD8;xL zA!3zFu&sH|`5MQ8|SS9^+Vv#H!c%x~^VVAI>S`N`=? zI)I0!jj6jr|2qYYFOdI#nMd!gEZ#&00-`DVZ<*izUgiPUdOj}S!EIjxxj}_9uHLI_ z$YOj95%#u|J+JgFY)KE!rKkC1k_REgYVp#vey^Z{e3DLgN!ukD#SzqroqhCmoi9f9 zNr=Y5q^SLvi0`FV70#!J=2HJ@^5c7MD!~9k<4$`Un zv;$IB%R!w@{=+-JTN9RhuM+kvo3gDVn9aS<#p(gQ*c6*3gG-k4N(H;x%grfRubnu& zqHRk=pyyS?lq}Gyq#cCFdKSk{ruS>`7G!bTwvoqH7`J~cce5)Z^YmD=1!|6UKkASg z)lpF>n3C^`kAalUn#$BKO=)dJqbfw29I1`zF5K_z0my#EyA9~c?S3o@<}TDR3n6Wm zA&dYg;-;16RRQhIA5wjp6A7~G&k2_G_2Q!{lmPtx}pBg zQNNp(+Tkdm-Xhor=9e-OLWAXecu!c7iR|>L(UlS>B;or4-k3>2QN06^TxJK4h^++M z9f)m%28zPwF$nzlesqTc!9T1dvaO60|AEx6Lue*y z4Lez9Hoov1+e82A5i1ONRj?NDA0u-4xFZ!Ab*RNC{L6UptDcbNFrab+T)cNS;`A+? z`^Eur+@}FT{DpWxC2mOWt<1&?(+4*E5s#@yIgFNJZaQ&3JX-w%zMSABtGUbO&>JZV zE?U5}{sP^{h?n@lUPNsgJ*48wKnEL8t(j+x6a`V4!l}NTac{W93o+=!jy=5i)(4<8 zP^5{YW5DfMJHt#(KiGslXe*M`4VTpL8`gYe$8PK!bwn@T)5b?3F76Z_CndgFrMO1m ztmbKo4Jg9%$z8Rj0itIE(XTx1-v2^FU)0=5`mwTVHDrJ=iLbbSWj9$z*rOIXioql^|j%_b9igo&Gko1CLh@zSqg z=_*@nC~p`n59D0t=8gp3|Lq!!6Pa)pcKv`-nqNyTd?mHJOp-{pxm0EE_;3{yr-*Zv zE8!D0Kq?U^cTDCc5D0`p%P3t$fhB>TDzH@G!k2sagM1~hkd2CVjm8%A2w=96!~)Oe z1DzZziCKmSg?(`oy%BL_l0mfL!RSzwN70|H9oUQw471Ji^TnADEM#(aAL6^EaUn~q#J{=|WO7{P9 z%If+qE&RFfEZJKx!~W5prJrZ8>(lQm;?aH3E?Hi~BDZCj+ZX+$U=>~{P>nlJpi9V* zZZZVGY;8@aJkNHs0VPlo7+Eol?IoPFZ?TEC3X9g8eBK!RbWNVuF}NV^Q2o)#FAj=L zfBuwvi^2Y!-%XI1 z#V;IFx$>fB63)udxUc-f=zG8=Em|k*h;X+Djf4ORY$sel@fn($%z{(lxYR()36l?9yF= zMs=;O$WE;x$U?0l)Wj8VwxNn*lEwQ|iuc33B)~D^(2s#5MbQ29n=A{N@vkW$t1uoa z)_>5p;(2qv_@AXX`#ya;;AKs}=EQoxOuyvPC7KE$uuz|kvA63EM`JY#Nln-J z5vMd_$R(qa(-rms)!2NB0pL~IHIQ4{nF>0lHq zgB1(uP!uhLh5v3O$^ft^-@QWrkz!??A;umoB4x02AuvjlThqAt^sI>1zto4aBNZ`DpwvbxxW|34 zD)GN1NS1y=2>-Mk4mONc#K`y-j8VkEhC(Yy1`w)-izz)9L*;YV1q<>Hv1du0i{+15DJ^QMT5k5u!5J%h{boPf|bj_e>afjGAQ4j!2eO; z<=+_MSU}5V=;FUI@Xp{C(X$EugJD-z=wbo4=syf@fO25v)JQ_We;_3FtONf8LFo3) z_!k6>a_R};{{!(Y5xi6kA^9%|1m)C>Z$WtFRBXa;5CPv9?pkAiLVmE#2?^#Thh**E zfNH6dg&0vQup`KRyfsZFPeWC7ydV1KSo)Sp7rjMW%{2HDGL25?Mdv$m}PS@$8b=oU1i8N9*fcoln zfSu9StC_sr0R6;3=K)q5)kFbq$8JEnooa)%FrXc&+tx&Ddd^(2o5zUzobl@Ha3h#2 z%e3HY#TxT^c!NPrI@?C5u*_7}473nsgZjjj5PL*o56(cTDhPdvasz}PQfAmAn#f|VL<%lIeIto@T>mDaC- zNgCw6wQ8(LHU?D3eqrE$fl);!ufjN9y9=Pcu?~aO=-2nrw}T`EM}d=CN)b#0GE(8& zGR#0bAE{090?onAKz&(l^f~unU?H)8zeB-5dWO$;x%M3=A^bL7lxQ?R2Bq)y4WP(i z%3z}>a@d=z!tykmcuvJnxdOd;RcCrmNp0I(_YpM|9G0Jta4L9C5fYfZ?gjwX4)bt&%p#8Sh zz?ri~MGt6V&ND?YWs`w*KUZ^I1!@Rd0O5~crlt3+fUIg$Iyt9KcCQB9nKJNOsjjJD z8feS?*+G$bH@wp>^nCtJD$ejmD$cGJR?3KOkC!vx=?Qa~LjQ&;KE-?D0{|n@-|?v& zwd6Z(#KZuGR!QSm--tZ*Jc5r`tL6q2pEB`}gTg+0;~$ous@~oxc;S=Gx>iz`;MAt{ zkY?}|p3i_VJpLZB)`0{Rez@Zkzmm>M^6`p3{zjZ16cKd^e&pj5ZOZlhD_3(tB3ij1 zSF^p<<=E#$4a0!zxeylqX<+ZNxXyj$0^5r4wl&C)v2!|7KIwalv+aucxi&4_JkNcF z-jhyuliR4X<`9*MeJzs2YvD}(RS+Gz-SR`-r%rp$8V{}V3 zo-X2j!jO`a&*1bl$cmEqr>XnEHj(AYor$Yau2uES$Hh)vQ8B+9<8IRhud{pS7)tDN zmf$stQ)sc-RA1WztNz*F-poc7EP_PmgDv@*x-#5Si4OOb*bv8CMNT}*`mRRCz!jU~ z5x&*p@whf_{6Y>;?<#!nQ+Ms2{gAR|SAKEnic8yo*+n&c_2yUMsl^@HT{(%vjo*3R z`d!M0`QbABG__Rs6WTEmh@G;|d-yNvVxN zxly1sV;y6;VLj*I7Euw;C27QaI4d4fb!yr;N4N=cSqNa#1c{bdm~=pR1G!8YB^7Way91`sczplPOVKM%D+h8BV~i_ zfhhLLxjLff;VLY^JJi&hsc^rnmMof%@p?lW^A`t~0u`Jhb{kR&IYubdyXyca-A^lI zXcK{A#;t&OByrPj1ui)?OFL}^6_e7!tpnlRkkJ{y0+jni6?tizV0uLJ1s7VO&rWZ5 zDM7KZx7V^pw^|x_Su06ql~J+=I#1JN(3tZ^t!#LYk9v}k$yakhPrCavws}9Z2Flc5 zaVHps%sDEv5z*jM7Nr~H0a?^Z*`@WT^6n9NL@8{vpLHw9Z?LsG{T*^0$wY}QhDwW> zur;rM^mfGIn(tZ-@&k<0Yvs4-66mq(=N9EI9-?`A(a1EhRi+1IN1$3rfBP85+?}J1 zCkMxf!)Hl2=k60Q9zQuFLs!7e6zMG>=j~C#+|QhN|1O07QA>TCVtx#w`4RWQ2)OzY zZ}1Xl`2u^1C4LfZ_(Vgz_W@PNRMI<=D7E;VHpxBs29sm=>Ja7)RMPPRp8s}P5JRHz za|lP=zzDiEF|{Or?8WDK=cK^U21auUeBHF>-c(1o={nGc?&mJAWVP7`geDC(lZe*! ztbP{QkZ;L6BKZ2`idX2S?cA@cWh}V3@}bA{VfPYD>EtZ1}qGn$$`nmcXCq+g#Y|yY>dE2fM*(71CfXa zv3SXf>Lz4mE0Q$#`U+tpreSMimeKRG-dsFMDJgNyAweiC--L&p(c0|6-`STZ+3ii`++5|u|JQs^kJ+>_{H9S5bvk2+HW8u5S%UV7X`wnLDc8%FKn zJu0tILw0QBME#X0M)8sic;CxF^D`0 z>65D`;x!xBpFE|-J}OqCA_6qC%VjMC=--bjOVUd^rKmv;nhmj1f+D(5E0Au8?UKnz zWc*fn2Xws!*v-ZF@nnOtavdvkv{uHI^gXKCYT4Nb23Ybg7CVg8zr~}^VO)rv=gERo zYW^ZQY9%V(Wev~C03^rOeSdQFXNYMC7Xa13S|=Q1mHp=OCwY0MgGXnIHAU|Dv3(D! z(&cKD5qGL%-VG=PU>w5#qLPMipPAI}fVtj#j%#eql4+=|car(T)rfvIniT$H7Ds)W z+-|%(3iW#H(Hb0^&p|)IN3NkIM`KFcF}IE~yk7%*=$1-K0FbrYI(y|C5~(s;hocUp z=L{bGz-7Q>QxEbZ`bGgaVq%oDz|CV@HXka~YGX^2?{k=-bZDgwvu$-9dp;^S~V4kd*nUN%I z-##qnEN0?a0`MBaA|L+cMi@%CD;GAV#Im*ezD2jw_*3O({kcYS|H>P3~ z^=ww5(#rL4mmiGE`d(yNW#K;Fo2wM-6=5Xf*Dl(USgMuiH);sj)Msa-mI}$pt^Q4g z@L!|(MF0FZ4eI~x57zZOv-&{-0VOg6wGy%bV`IP=1UwBS!vFydi2eK105EZ|bJBa- z*~qT zNJ=@mcZSiyNYqPYSnPy}aF+`3)ufDIWE3Gq&C2>l%Lb32u*V$yO>dtu2i<+QdO2`? zr<*>rei>ktcZkj%MB`)G1=LHW-E~gwOGL-PVc=m6)d!P+Zj!#ZdOJ6Y>G2whQec%z zj8cAin3mQ2$rWmBjdN{)sKKyB6VKwvoOT~~x3ur&Q*`kZD!qi>Cj01HyI{^TrDY0Z z7xsZGT=vEq&Kv1vF%yBb?s{>8#(XbX0{oqemj>YVZ)i~fBCmJKtn_GUZ7gl{& zKDe9X&mooRFWV|XKGAVR8kGbAaqM?)xun_eF#TG*3-bF(GoLgtdb_$li2b|Gj`TQ` z8n-&>53_fX%As4@0>Fx@@fy5H%KSI~zQBBC->EXBE^L~iJ=?A@47g^IGt>Se?q|4J zrXg`o2!#Hnr%b_L;!O(d`L8OgjIc2rbc;u(&PWW_hz7(wjd2#!onLFE!S2spj=76S{YI+p)%m@P$QqSV* zaAaA*eco}$Y8^0oy((9p-Sw}>U0RdY{Va;m>Y^5ia%vmB7UvbdBH_pJ^ zHE02ITibd+g6CqjEx%@wIy8P8>L6}tKwWSC5x3lR(E&i=y>kh-R*d@yN14elTbO`( zr3so3jzQ}1Sl54?UTt=uKkLe|M^RMFr;x zE?}dr?4QKDeHrsL6BZ+`hCKx();gI%pk9=dngDDdgf#B{;7Y!n5lgqf?CuDlI^GNx z#Sl{ur(9r)Jy^aDPL4ikv`S%??scg-iwO~)7ZmM8HD5I7)f5Q*Ixq}^FcE0}k`D35 z*rqVLzg{(VwL$1Mk!V0CXmn%FZ(llL)Z3;jd`p}R0VH7?@%kx2XXG3$tU9prRiu@) zkOF$7)?E3<4d4HS%Ki0QJn*(F)pR{({{pBKq2(5gMZ$d>Yxc_90ImnUI(9&qV`|`& zWvqS0L|P^LQ)>Ut9mQc?c@Ix?#=A`8w}dhi*5b(T8uXA)k+lgvJRmEGD~ zir3a4pMvy4vhr(x`vg#1kqWN^$fcG2sS;yQY!R=U{ik z9M=0qgl2hrXPBcrE?Itbt)u^ z&0erb`tEJ+jD8{|1`DRt7X6tyh%avOf~M(wIUVC?gP%F=9L$ksVLo5Ki-yi~Zu8j>G8sJXt`sOyVER{#LONEubA z^W_VA9N(wCEnq(JTOvLQ?%fakc{^}_1f5bV(b40^Ir-KW?G>#UmG|S5>hVL?fv^AZ zDSE5*hvpd)ePIs6!)8eLQPGej zpFAu<8N0gSe$s%&jJjY`qBsL8j`;tf>m9=*+nV>`m=oK!GqG*k zwmoqNGqG*kwkNjjWP*t~ao(PDp5OJq&WHCyx>GBw*Q%Y}b*-w}cimNY#&^tkz!e0T zd*bDpcnR~Lx-6ua`U4oe;F$cOI_jt`fW!e`P|Jm4MB*;)R#qRZ^;GgXSvgM2_u>3`3lquPK5`+aJ2Irf=j??| zbV|-CeF{pYjQQOP84U>c3Xgam@wx^~>OcgDitEn!%^`6_-k5CXo3@ zTX-eJT@|Ep^v8J$vF=@ot~?}EHxf~xV_8F?=Unwh?Gv3vza_**pSbDaYoyusiWE38P5wiGr8J!s26b$3o$hG$~hu6*m_zg_iWAmN6-v zr@ib~#)#D5 zfEcxvCI|VoydQsBPQi2;t&fdUAg&Ya)vf>0O=2ledIrW@jEvZHZ%(E0* zfCiRYf=D6H)t!WlfE*S;{i2K2JWKMWO>C)KVZgJ2nInr6K)HAE^oVG{LH+32PjcOD z$1t_>OeBGP_aNP`G~&nS-8kbr)1~#YNp;%Vo+$})I&NNrWq!|5Z;yyzRB89k7*LhJ z#UFbxrPPu0g|v10F!H;vR{=$xIJ9_G@qmspCGM4>Y(`OaPu-)-R(dU z?}~xHjw~_Ik!AnKkJWz%q9W!$_yLfT>8JPIkqikh{)sQc^#_$#`&y#hI}3NSsN}99 z@w8GDDIY*ogmOXIQ0ZYyDzm&=_$CD*NM|JUZi44cY^b%BpEwun{z+Lc6 zvb=x!)WVH&>tk#p6%$k>x%fgNRmwwwWA{xd;3ReZ%=4sFtkUCl&EF!v*P&8gAlqW$ z<3hZkXbM(vggae9#*8^Jl(rWXOsntf^8+8r|j9+N6Fr$s{UWx)&eW1 zfF@hDdLP{R5PNX0-XZXncum5+z|bVdQR_{nOEF zu8UzfBoxep(~F#og$6}Ej66%{q$2;OkdEi<;0tz0BVP1<<;sW2-)<+ItrQR&HkUbm z$Dyt!2#*3*+3b2N^^i_mgrIAbR(OohfO)iF`&J_8DqWDX(LPpNBdhFa_@7R^vEZ%B z0cSFMEw{t&9SO@90*IRypbnx?E6sPy?sy5ykelboPP&k7q>>Z69Ka#o{pE{Q;D_`B zHWCIdepSl~3_4}M?;1=IxfGqB@p!m@W7%iR2MPZH7B`+hpEmhiL?u34VRT zd)L56gD)K;W+^q=+)_OjW`%zrdY}h)JvL3YxSqu}9za*x#(wWt7V!MIzu&v(K9vxm zQwj215EJ6GkQb|*;Szh)oY%9@M9?kL-)Nf3QqbJgtKMp?4dy*R80w6AT2xpc3BW+w z=O!f8I9-?io^YLl9LX$&^&kQ;&#j^x?-Y^{Zc=;UqWn(bcS?0aPl$5SzpMTE-uSJS z11@z^HsoYe@%>zBk9K?Nm5z-dZ*PbX*FZwpJNUZE!v$xH48Ld@dqmY%h7rG}c0_gh z1bu$FxXwjUA*zXqY+fjy2$$xMpB!QWJawvkUkSC$E4ClPY^!EG0IL9ia#I3>dbz`t zV0047Z6Brd!Z2*;pv(qK>c(plN+K@8J|iM1&8nGA(R#y2kpmmvBXN-QB55HYJcx1^ zH0CE91L*b-Ix1{a%m}J`-Sfzz4%0Wff6e0Z2q-iCfC}#-;}aOhV##^={>m+RoDy5# z8z8oWx>2~RjU)tCdcXp(uAd}f)!d9Qd}v4~qNe8lQ3k>6aZq;H!dqE(=z+Ii2BFkL zORKJ29wD>ir$!o$7Ny14(eIxW1$!vZ^&2d4+?|W|!@US)%wEZ3(FFY?eF=5piITaL zZlrM98Qy3{7nCM_JEUL#JqXv^HN{bRj4 zJ#Bxp02FCrr^uu(_cetHbG4n zQtoE<$2bGeMR3P}M9eJ35GRLA<=>Sev@o?s(X(Ruk_cH?rMifBlri63O6SPMOt{+1 zBKjTlQ`p8>R;hJWydQXmz6r||nuY{%2ZHl}mgQ@#isOfr8Z(ENjnkB$K}$sp_b`;l z&f9h$O55w76<4`Kua!k95S_Hi$%gfk$N|c&mJ|ehA?TU_u3qc>;mq@Wv=NU@#f8?} z{t>~@9VrU={G}3c?}`=(=>>Upe%cb#XR$Bf(?Lj z>{m6O;w1=jwvSn_=r)x+f96!mj|2qAH$!<#pU)Khwg-iSrh~tWC3Sio#i3ZXnHLQ8 z1k|RnC_?i9D01*H0-;H0NW&;g=T5SGpJn#9HFd&qVtS#-kO^o-@zR>r zZ(1T+)w`q;FX#8gajV?!=O`BpD1(x2B?n?6Y zh6ILVrKj%D2JN>0pPQCAR~y%_hzJMvbjPg@x&w}Zo4;wd|F^>X^u9fb_4XwJ*Y=}} z|ArI!+v7FPUwHsSRBGMc zcc*cb9?NtvH{gv?K;t}Aq=1XB9nAGbVt6p8(f|jc@s0c(^WRqC@E7Efjph4CkH@jc6P_c(~#{0>gFywxodI;X(oso>y z0@B}O?yDgFyaYfP-Khr7T0h=u#F^IHMm?U%C;|mTNtT*N)UBzF5MG8Z;&2MO#ZXzP z`o1!4?d-vGNv!K7WpLU3bHnY0NK;%C;V-ts)8p_kz(Z{jS-BTazm|w9R;mp&+T6Xu zBPewQ_68SsCRS4Anf>zRUJxNL3wQM{twSPc**LY>6yUmLA_Rpe_$9?Esn~u+!5?nn zc}o+?c2z&Fn`lf{Flxgf;_{u!ldU|PP*(!x!>}8s4HB=Vq~AmKe%3Oe}(m5 zgFT<(la;h_Pvx0e-c}-j%e`ak{^b6Mpf6ppWi3v?=55ipA%b2|=dtiV!Jq5*b|W-m zE80sS`~<|D&66zuXoxQ9 zD(L%Q)tWaV2RsTl+aFQyBnf7&HIHIH!l)5f834`zcH=k4`%OZ>F^SHVqEFWdM`dJN z+d#reWY=-|b_Tl7WBi{qU2zo}`K1e;0be*WSqXHEK1gU<%Bs|VS6auBe=l>4Xs&+C zEt+Id?|$q?BHgb^qIJ`ubVj+ys8m+m8W;l)2na@=#b~Jf=)x-HlS^b3%O;aK#TsCiK5Qxc( zMqt{vi7YX|TmYVW3+YA%Syz!zua>W(JOsKKJ%&dHk7F zq*=DT$lWHhUy(NLM~W;zZNf$fEy`o?Rm)OOs}s)FOi=MGydj0QZ?dKVG*aO3Cm4X7 zJ<=;eVoh4>hSnlB%$}}+z4QD_DNebtV^xUhBwhQrurC63T38d=h@sSCtD5Z=8Whe( zhT%OWJ$F25P~{=>8*6g1)~YbY@%>tAYtiQuo`lghRFc=YqS{L5&J@P#KWRXAJhOt= z$LCpN!PV~TtAQ=H!8K_>v@rl1%JTrpVM29thuwVGXJ4YId7p?o7~e&mii-8Iyaw90 zX!nU~ce2g~jhOnB!@&n?SiD^gW*{A&#Xod-?e&+V71(Dn2?DJ4rpaX$9=8U=8Ax9_ z1#~91RO(utP41>qIBP33lM=?jl2gE|n@B09m@B2P zi3pcf@T!X%rO7LXn@!4Mj2=BziO*uh0F0fg099BTJDvZY#V8LP1xo5bg@8BD;?S*J zT!F+oeIz|`p%{vLD_Q-9Q`Mz|jjEJYeMw>4vdhpWZlRczn_(jS%veGpRR^e83Qi?Z zG2pnqHijuXMX9W-3$3d9#bI}pdTbVB^FP~(H0(<-Qee`+XzU=nT*&0Yn z*2N&3|9#`|$Mqce1r+zNmDA(DPU&sxXS-OA>-4_u`~X5Z3TxmH{z5t8R~p)~29nvu z&=Hf8*@Id99@re;Qh%xcu2C=)UX$N427{-iSvELW76ee!onqZ(ei9xZ0pK6?wx5K1H=?6oHiC=lsDR(E6#N|=U8Z2uSOKv8!)2?9hqNE#s};_jXnLnRGiNM%Xb zfKb!fLb-xfrsFH6XqIt=WhU%-p*Pez>>CkqaPe4duY0r zlvcgYp#iO=XBEG@BX~{N!OkG!2QsSi%*0v=4NMtnQ>Ny&}j7Bt0m z$M9p{NeVV@-k1R0#y7;Z#G7Xbkwip|-nk!1obrt6dv{!9(@k0j@ojbDjQZuzq1$H=nf$#9i$ z62p)g1xD;4Z_9naQ2LaMZ0KeGe91Ee|4TL9_V?oCnTaT8Zb%~p9OhJqxru=GtrTo6 zQCO`vfnh@c>O9gJ1+W7XExxX>ZIjL>Lg>(hW;UVzuYyWV{f@X_929s)9^Ynq?#7BP z84Z87YbksauX%%RQD)c}EU|L44UgP4PRXIf>epzQx7a^fD3kg|#?U1!v+DL+ z4_)7F(;y^e$^6@(K@MDkaX=TAK^A6z!)qebNa2lo_g3z_GP2Fu(^jaFmiBv5a6nLa zP*9+9cvAbgX6oVB=o3bYDL)fGE~5rmTL$5<}b*(&O1aZWKoVcz|-dw5KfnDXFm@@Q;C z&4G-p9bVGk-xlIhR#~W(kw5X*+7zqxd&Pv~T+Isc*iXU5KcF~!P?ohRBY35-zy4C$ zU7(IoO(AN~)?M>DC)ZVYauc&KfCb1@lef(K2vQJ@MvOuGClq}^P^84hi&L5jq?c&> zzkJWh1s0!oNdAyM!DQH$yY}Jdur4a+J=Dd^pf;Sp4;e+O_2q*txIiZndL#7|Dm2ud zyPiykt;(SUpBcfHXZG8#tt+ra%h;P;+I-7&wQCdv2}=FAo-n}T8o9A^x&p-RJ2DT* zUzyV_7lFU&0{r3xL9c|*1e}vv79!-HdPkV5z+?pG(J!p84)Yxv*7sCAl- z-(kSQsJOg;lYp!&9RDT(?OoTU{_=hc$5&K$^N$b*_Vt+g{Yrb{_~tAJdpuRHpBe?_ zLn~q;Nm~E(z)40zUX-Jm*j=sLfM=4Ydv{;f`CwJDNWckAr)14eca-{YTv5F z743_^{k~~H*=Q+w0m$L=Vv#<8m{QDX(qS5|ZUt=Pzi;}Z$#;LZX;u{YhNN>3*ua_9 ztlYW!cq#b0oiMee&nBOCZ_N2BnhYVx9vhgTiDcDbW*Sq_9(p=DXQzQxIi^<(zbJr1 z0^k;RpF5+@$n{wuC%r(MXu$*De`f95OC7sy!LEHOL-xZFTVSd_Pe!IcZ{=7t}Ct~n7fqPUk3tixM@PCEcL5(fCa_zOt{Q^KDsH9;JPce&NHQk`Pd86!W%?3zv$?Z>1 znENW~wgo)8UrBuvWYQoC$pX8sq7>AKt|r`;t_dqvj8iRD5s)->pv`7jM;<6p=j$do z!1gjzNF3Hf;)2sKsxr$%b+3xssK)b(qJksX_2L(9%}VUa&2*=tsr{%QrhSx2N4F_g z=(G$(1XOVe!5-~p(8ElzB|^+tkN_f1k;(brW@49jl8RQ!wmrDoY=9w*1R(~@)ifzv z<{piNaY8@O!GH~|UEDj@)!?{J1&C|!IFqhh%^k$prb#-n;3uj^S6G^_e7r$ks`Lkf zC2qQCs=-g^qvlN?F(v^nX>*s-1sXWy8?~79Omc;D+c{2pkL_J<1-7JZ1^}jx%rD|Z z$c+8;(N&d4^QJHFk7HkDrIqlV*^Sjl%0ZaOrbWQbt+fY1Xj?1?cu`gIcFI zf&mvfoL-MpcU}(p8@pHnfWb@7p(MAhb9(#jC_x1m{qcMgg8(HL=^7B1?)$B_;AR^h zoBI%%L`Z`VHXx{CZ^*sTfs09{^_M#R&N8wt;wWayHxqLV@eS3#zBJqnY*AhWJY^{d zeuKNU^kaEsrOAGRDj_|Y3!GIs7#l@tISRKt#+Y@5lmhSr8Gwq!g~jh#C6tG3OT?w+ zwA|J35oFU*Stb8C^x|3E-16+B)~Xs5+j3*pHVO*nz)O5)S$S0p&MJvGY+|Hp`T2j7 zxq;sQzmtcw<^SJg<>?AZ1yy^O44c293Loqda3}K8a*n@qX~+R|B&Bf?1s8PxQJ$a6 z>})>aTop@mXpo|mPfOwueO3k1N=89b;?S*FN~1c*A%d1QE$6X6&t3}4`D39=l+RFF90M!0;5P4uhF1I!*^iMivA7ai zDbbAIxc1ioU~k{IntiC=%KHAR3dieCN}xFQuLy?sHj)MM-HVpksx{tq#!G0Fn#LuU``l7F`5)avm2(5od(QFKH?t{fJF_qiwvrO z0m4L+u>{)I#RHNC6ZRVfLaeU~vk%f1vdUba7m5Yyk#; zw(g-+(UOzRqQ(GOV>TMFi@($@{;bozd2!e8g%eAPaP09|P^>0__JcEX^8(i@5Z)hsmWQ?JE#lBb2zOZ-=aq=n*& z3Q%S3LlF2%IYEaTfD>3|CDaEq2@kDT=On~q>>UN@Yx3wzUO~LZ4m3Fp82By_f?|b^ z)HbybnzQqpMZ56@G*wfu??(44rLBSJZV)@fJnX`~t|}!R6WQ*|#X;J+!*3Y9Zl0iy zHn8x8GBOZz^95klBk*7H`xZz$hO8w_0h-%qvy9qxvWVvn!&_=bK-%TBFj?%|dzwya zcVq(KhGr;LGz>W(!r>WUq)v|8_SMZ~A#2irysQVQ@mu7#dVof^j%Bw$C6e7G^doBX zfNkAL?w?wpFmuXoI7a@0b;8mJ-_{MMCkwYiW3j@GI#ctWot1AGXgjfs*fDgD=)J$z z9JtNb8E}T~{FoM>V2vgd8p3HamBh0ulLMg3mV1f@a1 zFLcnk=F<{$^$zQ?lFAVa8>7aVA^l58do0YHkFF6j;QQY)ubRa{b=@gG4|`x!R94$Rdh!ueR(G_m~4(BXtaUUqOC!X)NSCv*}! z20ym#1AHAW&i!x?%CXQ1u0@i3BS%y5(6{%Hx1QEU;`YtFd@wzovqFE9_JlVaf`|7A zH+~tDRlkriQy^_UU#jfvr!$9?l)%w;4a9xgO z$OnD2TfBw2QISfjSBDbd1&`}HwUe->Om;G$ zF(xxDKzGqNFF^MW*@&8re{T6qty`R~JR019Lz^qL>>Z;spJay6m{WK^WWnSo=@~43 z<@$?8y8GB_Ih@(SEC18X)M9fCV8AW6ODVgvRUP0o82Y z@ZQ=f4P`rB)}cLyIADDqFz4pTMDi4F0(^`LyHPW0<)o z=%>}s_L0iS{U6Cj_$3I`yEAF@E?alYf zXWoCIT0Ae;hn)GI-4EI-YB=UP{(1KJ`||iHu%jVMCDu7h`Rt)|t-FR;)ci^?>esV% zyz$SApl(k!VA-GGf@24<1G1N371h7H_0ltYUkM z#`rJyb_WYRA4{Cn_x*=VXTUB+)qJf~LkvUJ^m1j0+p1&2mF`H=j76{XcF7HrE-9uGh)ibJIYXeEnxy6-)g$= zP@9-HJ#ny8G&HeN)6^iK%AUBr;&8Meqg^@(lkxT>eFDkL%L9tY9w3}e71zmr==tL=#bmQOf#iJzsmg&D2Fj>LQVq}Kqm}b#X+4g~2m=*Osgj#V^xVaT8!bu$ zgQf&2tG6O={RB(-s4TVd0sZE@I^5pw(^}vYK~BaUVF>fOJyrIG4fu=-m)0gstM570 z_>zZgkZ>3}+x%T!1AvBaiE<$OgENo!Zl`Z2vo1wdlqW(JAD(6`6(v2tSO%l^*XH3vY&;lt9({a1T-J$T%BIaH0-u@R? zDugPnO4mdqo=+>HI3K^HK?6CpDt+(t_2CY>q%MTPNxViEIpC{fgw9C1ggoV|ozEys z|DAik#myW{Jzcxt0EE1DhFR|CJI?};gbk{Pe-GsRZR@dLQ2h{hB*ZR20GvLb?W>7< zlgpiezv5lZx4$H8mJ@3{x{Tv@nz}=Vun#NNDMHEm8a(V3DVGH3%vTG4*scyf2Zedf z{eQUJ0y}xP0Y(-Q6vIzpfvh`++Y=7^Soa#JJp;!kY;$)yXGy3wSQ+f&f4E9k7KbcQ zj8TYR=H}s7OV8opS0ZbhB|SNGSsC$|5kJ~}Msw1x2p`YSb1zxmPGIw@ex$PpXHhnrnQZJ0ocSGq-~q0{A?)ozU@t5X;phT z`a>AX<;cqJrgqpAPeN*F;=OuH$!Vi5uwl1(-;T$*&$}+% zf|KL^$7st9D#4$L!%6aWyU^~krOlC7F);L;u`ARLly+ck0Lw|xCx!@f%o^A`EOS46 z#3YM>1)%01nCtX=7^{|P4d0FdQ4W*q9$d{!1=Z6i|C}wU`O-NCQAbkagE{DWZA4&} zQ_Q2((2Y_d-uxE`_&lgv>@GeYAiRe=KiLq!8 zZ@#uwlc(~rEC0E0$biG%W8jU{U_{RZWW1QlEJJW;#|O8LN$ue>_V^`7B;^Fh`tr5p~5ly;j#V9F4!A!3WsvK2a7hv{5b;Vc=3&bWs)?M z=%-#P#PszrMXb4~3U6~L-w_n(nJ*Rl?I^%VtR}jOJB;;$#nFUlz@<2QYZ_hk)3&+F7n ztzmw7l2DIMyK~4+>hg4w(F;n{#r4oaswR0Tu7f*4wwgoKMYIgNp_H3kFmTnEE)tM= zaLyRbf1~KQKwq{o4TZd{=h+ z?+Nrz&wyP~0eP95^8OQ~?+RUgf;Y^CH{qewF`sa{A<&%3O;N8;S8zJQ-k)|c<~Pp-RLdNDuTS%BQ|Z&{>f z3AOXlIHA-gRD`f&;hbV}0usii5E%C(Cc}_M=yi4d&N{-gqNvxlXPjk>^Ogd4{&E_= zCB&kyqY*9?Yp6-opLM%B!7@w1FbLQvaKv&$rr)uvB)UE~;6B|A9Q3|~eth6QuX`KE z3jhR?Un6Ut0n5JX+|!C)8n?%{tUmkVI+SZkl^=z^B|2%zi9rB`=hWQBLw`m&_VKS< zD}vV|=hy;h76wZegbef6@jLuC$7bm>mzQ_94%~_|4x-EA@vVI7GrB>{yF4Z{ur^j= zzaCBZ<4Fjlbu&Y?OlJVU%>6U@5GAnS4*@|KG)Cbl^gkK2EI=ZK>Q-T^YV(REn#d#Y zn$XE+v&o?H2$<5)be38s&tclc@vvv1h}Zid88rH!EF@ucB*PG50)!=r8I8ihIM{*^ z-WXN`u=`Mv>D@tPG3w%R=e&JLU8K=CsBTl(qPAepQ}_1m89W`hv&$pQMo zLl;m#OAw$SYwLB35HRX8y1L;xR)Z*dKod}J!MVJ5Ex;&n{dOrP`BGI17{As$W3?2~=IEor>t(V{!eLa^fNim?{K zwvU9FX=poZS{9#2<#`8(L{Cq)&S|US5{O!s3YFNM!qDngsMO7Cs|8{5*aCFYOi#|y zN0Lanf+}*U9o%B-qo-?=in9mOP=`p%!f?m?jk|O0UEH2{NG8jfm1%EbvM7nygq8#G z;`{L1<|@@FQ{)$FmSwDo0#(D?#^%yincr!r?boKyqZMm!XRIGjL-*Tzm@S-Ld@o7hWQ?s&Wo|1y)<;*?RXe&UMz;p~wV&c@HPlr`B#`o?B z>64UG_|3AE*KwItK^G_Ur=%i8#GNn!@ukhUf_}OtZp@R@WFd@w8kT)j{PXN5G@%bc zjMw?J?;FBot3B2O(g=Vr+*}=Pf|8*k?ayAuB~e-p(g>fkg@MY^r0<5WiW}Dvc(1WQ zlzp1u(fz6844=Ctp&$62J-ourURtcuPrh3}yx+0hfv+2?Gn?fjJ3@ZE;dzGv;oBp+ zmn;o?2Cga(pFjO}r}^vmK2oqE*<=qHYNEY=^CEnrXV4?X8|nkPQSXr|WwltOtdMo5 zh8*s8?)DdK(qRa3&Du-5R*XzDV4W^9DHY9{XnBgLpqBcPd{<}(Gv>w}rQ>Cw%XAwe zONTxZDi6J~lE%mtzrxBU4l&Ljn?L)z$N%np%QUOcy4z5b!Pb#qee}2wN);EFA?n?R zYBMVXWh9o{VHt$e5X7lj6P$Ez9Onk~>0%cz{_m1>)+of`Rh}7NrWwQ*XhM zdw@AJ1$K}C=eD3>-=mgg=5m77XZQIVRKR}43oL-ChOl|_q>FpRDog)h2dmd6zGPD3 zbhjZVZ4^5suIF7=+M%B#Sq9c*4m+9@4l;Yh!H5AeN9pJKo!wS+Jjg|Sg1My5V>l6F z0|w)`rOpw#qH9G^!J)&22E(T`+~?--U5E(?OtLN+`xPbw$wLCf6nhpQ78Tu{RhFa( zFhG&RzaRaecXX4=cvR)^5Z&)ZyGXY>XQNn2N!h*VdTEF`TtH%1;)Wardzgjc-0tHK zi|+)8=9Bw4n3|!d+jpsV7fPK$ckpJ6`#D15HWKFX!gc%SRkn zT>j+uFqEubLt>9Zc`F=@ib?1q`h8hNstn}1k1lWh@I{{83YX>yBe0qWzZZT3AGJTB z{%{VP6%LRKiw$}~R?Yx%=dYJ%@auX(KFtJxJjca5sM2Bb>3yLT$}wF{_*R9-N!!A! z#~|GC72lkrIJRqsx=XD{MfN-Dg__2rPw|2da-wGcVrg)mM3Lf)1B;f-z~K3%7I5qaqp7xG`M_9LK@eTcpA0|a}S~XENo&gID?u{M#l=c%PM_UuQ;cQ^zKI zmX}MRm#RIx+Rv1L>v5_}^%dMhuSiA>no|0rj_6)jEZomZejM;m<_>IA;H^mezPHv6>GY1cd*~|2#9Ue>}75RDH*FX7rG& zSGuZui^M$neF!Va@^xkMl6g{Kg}F_|{9wS+phe8WJfQa=NeC|HwLYIZmrCI3?uCnE zt5H28Pm+{%TzkeP#tt3@^CqpqYi9gc)mr^@Q1InFcOp3gBJ%H;Irp@L9QUC@r2$P&ep+A-90u(5ne1*1jnTT9~-GEdEu9vp^yozUuL9x^3_s5Tg zT;l|A#Eq<36fKf#A6G3dlGl zKP`vfD&Wc_mrn?bc6(3*j9JEZCd(*_qq$jT;^qM>2~~%23}JajJk&MlQopiEn6 zSkyvjzpVVY`BjcK!@l?Ll|OrP&7#^YFDx27b+vPIGsNn`Zc=Nf%W15MG{rTo;`j4eext5lHmJoN z@EerUtHiM7TSptyMo@Hs+jW-pI{o)sY~=18wq zniP(VYZ5uipdVw@=&s|-%hjAe1MD1FT7KIauY0G#N)unl=Lt-uNMpyNA2ovuh`NAA zsT`tim0Stg?V}mpFX^41P@d1Qb`Tlc885k|1%S&e0x1%xlb|E)g*2UR^f4;qYfg=t znIXlRhn@7dsBRmbp2(a&pm!zSawrc8+}f5jl!T7G;ATE^J##Q?ee^zXp5Xr*0JU#d zq6-4ejPL){b}(28tE;?nZOnJaWyz!>&^F71vIwTkt~4!$AfjClYRQ_C_Q@H3LjFR;W- zfx--O%cV~KE-qNDei||WiDi=UT}y~`qzysrOkPD4LNqpxc3R=g$xh~zf=%Hoc$0=( zb%?Jt1^67OGo!G}PEm-SJh`9A{WAdi51|Nd00UEozo@_}oJkwXU2&V?d~+*mzn>J= zp9BW2Ym{uNgT3ly+QjFGUuw;?tl)$FZ3u9uG0~N3q@ku?F$1v4cr;4`x~78%F^Hw1 zO=1WFtWCFU)%Tl_MpTeZDT@sf#BZdG+uNe{k{D8m3OqB*)MJbV$5qL%l&b&-2%?n< zdG25d{dnZ+&7|TcdvbP_JT!0-L%Ixi#F9~}MVa=>2TC2PtrSaT#KiNVe>ya>WQi!B zG>pEYM3tI@U!ygG_zP;(Chm4icOW2KvDJyMHG<=%1a6tsSJWqYGUz1p){-h;!K&42 zgk?3Fl3>vHRf~$aDWH^&7yALaWJ}c`SFtD5R(aTD@eQ0A)x7c77_uMzpWJQRz+pMj ze=ooz#Fb7jCKS|r8j*+#vOkY+MX>31Aa2wh*%ip@&t>2ZT#~k9#qhTq`J#1Csn?60 z@tW`o6yNJe&f?Xv^L5SCI0&=U^YkgCIzZ|!}630|)sz8I4#cH`%o_M;@O1gZJEF}*Rc@YY^)sk}ib_dEqz-6{3 zmfJLWM3qnvKjwzF1_=E8ucc8JXSIm{EzRJ6md3{X|8t;ykA*7(9%z(SC~}=z?CRDg zeSaxatWSG)oQaX8oM`YwNQkHeW?o;osG4e0mBS3e!)Pq+e|9hty35_Eo1h)j(a38Mb~Ym{YVLXH$3EY0ub#t!6RjF; zDXBv8qI2^EKFj9@RqYe|(RZvQ2laxMo9IR@Z#mpEmX?u3e=PhK+g0|(>UKUd!iDB! zb$EP0UEc)mTL;%2@yr`BSb?W}t8&-N0z6tAyhX2@()%&!$cQBk;u5UA5_5HyinjFC*UEm{q_I4A+A zsHMrE2C@xFejHRmL8n4lba9*f*2IZq!Ui+|uTIl#S1GVCbMv3IL(q7lQ3_&y{kcbG zrwpFg=m~3yd0%ny5ALj10ZInu96PgFl_@2xi{lM=yR$aor+NcJwrId-vf!-Ar9#_B zB=!j84g*;mj7B^y>y@_L+564tCQ?6?WE<=RRH|b9r1sLLk0hmir4C6;>+pV2?8lM= zG%lJ&Wa(yk0*hKj_kG0@mIvX)4bdr(BK4W>;=sp8^N$tQxRQz^iA;wAw@_mozLcwo zA1CSCM~|_ds-#S{Tx;f@aY5)SaCT1r-o$ zmSd=NXY>ep#@bAHNd1X1vim!_`JpZpAoD&^=~Nm^O(w+$Oi9)lykme-*Wk zn@xx%AdEI(!Z>@--2*UQDbJ(4=Z3Dduw0fIcmjKzqTRM{Kiv_7m z3>YosL|}X=%4843PoBwxroRoBN=*wFqKAvc&Y_@Iw!z}+FI87Jr1)1zyne;Cw1uXW z>qCND!lQwWqnb%-A=Dq}|E6B0$lP9lKww_|1$}gt46e3tyeXUbA$8k8rMlKol zlif45$zJK0ORM?llV*k{d8K3WgW(PGzs6Qn8xZ>+V`KT>v8Maid-Oln)Hg~&j_d<;kt7MADP0X=*uUI;+;*J3=b$H=0!{?x8#Pwsn7y>stXw_HgJ_H!fqut zvq8`kU;R!MHNmwpb-tSP7Ab`-31!7Frh~Ya00UP5zONQg)Dw=7o&|F&GX~f|I^ugB z1lLXBd{60WMH4%NT*P>@mR_EY@KF@d=7a6X+os`B9R3MitWJ8zAYX2iBo;DG-v|k3 zuTmvPkwuWHj5LTH-`)jrsE=Eu4TjokJSC53BofxA+K677Ob{s?RgO$cakoqsvh+0) zTjA8i3w0<|sz&9@t8fOXfCQl4!T|@j7$O=z?u!6%eGEyssR?*7AGJ%wkR-zbv1AfT zQHH*;1>8nJRe-8o|v!r%#WnRLf%m9%DSH(>9T+`-&Bu$xVmqc z<#n!QSX^D^Q4>#t4Kp>%#@~Sy=m-#-akYqCgQ782qZGoXA98*{{3{)jdLP-s7MU!0xd`T`b)j|E7o9Ct$eeTEsP76h`j-WgLlowMC7z+4$YgorC2T zkvY|6@YtydemNE%YZMvNC6Mq+(P$yWH0{Tdww$9cDGpt#Txrgm?i12~jScQ@@=yqP zvg!Tb$;SFWW3vYu8!|A7Zd`200lQAF;8`9}K_G4tgxTMOR9QkR|3ypQ?ud)w{SPlR zSRh1dLq4@*&nEwjt7WdWK2srbH!6zi^m>T9F>V-hE_Bk=x&&$IQi$^wx2^oPsdT|K zjz~31#~;#p4yesPoTtK)4YQ*0BG=nos+Le?2>q z1Dd048^~PEf{sr39CcJ7QIHA@JMq|UZ13rEFm}|5wKw`euo#2mmo~*Ll0PAa3%UT- z`g({8w3vI>7%oC$Nh?Fhzql4YP?_ZZ53acsk0Y6!><_8$blbuLaV=L#{4cHrj*y&) zB$;SE)BZf$dKGJRwG3MM=o2e7&Wir2VeBXQxn}&?( z1pI41e89KKL9*vg3ESp8PiTg^6Rt+;>vG-qN7ObrpNX=Xm22T@-9wL{b70W27@_*@ z&S!&$Nc}u-%)vdN3$f4DTL`1w>4n&Gw5G_YZMFvS{(aPa73|0w>dqutT)C|S z#lh(DsQ;ndEt1I)XqC`M50aGJ{7auNPQoBDJf!NlCC1Uw`3Ttv!*!X#$pVmhHOrs^ z`Z!5~;fnYG7Tgr!fRnBMxRSUMs#^X41!g<^0~&vqSVC<-E{7RVBp@t^@iL2mz^VVn zAqzh{+gpZvSa^WULDYi}I1hm|SzB1sCD+hiLtDF}E?DC8-}I^6IpAtb1AQn$*jI_= z9G}`Z&FZU&owAYgWCD&f<&FCiubRnxynv@JzB^<{qDbCjClG$GwkZ{}?0a1~wKm)* z&}TRZnc6YO`b~(%5JOD255~Wl-Ccw*!~|bnm$LaR#-hfMD#!oQbp7uFaA3{2#8ve;oH2G&d;vC4i51@6VAda;pSok@#K!k=;UHk;S*&;-+%s16khftyt&cDF zzWv9DZML`pPQi2LFC9x9yfB%U=NVVSJb7eww}fJMDtech)VZtaf;tLgm-QUb=8W~`m{yOrY|XHAUq;q?M| zU{tT1_=6O+ZvdpemqJdt-V%4ymCRM2Kc3uo{#E%0I>1n1YQ(RWm{DCEwOyV$$rFHb zeH3v?C$GTp`WyE@g)7)PI!te?wo|r_4YSyNOpi-J^}nniqxPx=*Ab)EXk`?F-UZSW z5Sxs&AVbtR1fZr4jP~x@SiVXG4qalnop<6#&y@mr_KmVvpoD&4;;dSX&M0L6{W6*u=8d3nam!5NKqwAy-7^qC^!oD{T5{c^A%aj{ z&D{7C-QqAe2$evb7=Cy^5o>N~C%{4{x-svEaE9A>HlNRZH@Kl!wf{ESNMgw3~;X1mnJMc~7d zAe|b(n6~TfPsbQUL^g!0*Aj-DtRRBg8LWg0p$bnTV|3FG7tVhIjiw7&H0j?oVIBh>?MRLpy}p@fDx8WF-e){oYo8Y%^M>)vdO0)?Tywyd zNjEbJTF9R1$J)WACrPpp4;9RWVlx#bI|={ftNRlcr*vPE~d& zJoHC}W2NG}+#W|J&1{N3A%}05rdNH48gxrM<6E1#h3bD960zLhHDuZs67FL+#B^hV zL35wZuP6a=eD;8hDIHSPb6Kdwn(L;`ipRx@^HnX#NzK^!seBS^AH1F4KJ}v-pcr1( zmSzFvpNm}BFSSQ~S3eQ-%dIyVOU!HSKK?_*tnZgbCj(+qsL z5M&}+POu!GOt%_aHA;rCc^&uh@t^GbtkA~csZECUaE^e>(!Xc;3!fmAx_A9XN)dvs zRW)P1%68RdL>y`S{vmkN2`M|K;l|FPOUfye{X=I6qbx3k<(8ElwkQ*pQ>NptfE)cE zf`rYPAG^HCr{;@mmVxR{oVSI44y4kIhG zQfB#NG$6B*ZTSQMHzrr^cN@ZLR7^|n3MW}kGMVu=!Q!9RpF5jO%BlW+*HeC7z{-Fo zDn>_+3BcqZH$h$}f z{s8$M#-W(!>CQrmg_X{VTEqprGcUH~#Z8RR5_9 zT%ywaNl!$7f(8H*(hMd9F_F@Z`vVktjt0a~1yU$R6$C;9Qi!b#1f~MtNvXuF>~2B-rx?x@>gzwr&7@cQF#e7p#mSh=U_Qf^1o|;59czp4yiZs8Nht}kc{Mt+SzHk{<_rmpdiEa1GK2f0cdT(G{dW+GK z>8EZ0vuMS~g8hB_aoA&WarDure$x$rHxf0-&4{F!-Xh2(G0lK_eBr`=t3Fky&AqC= z^F8Y6EL)A&z(r4pgPyb35Z}qQP39d(i%6?*L|{cm#o4!=Feyo@f^pH@ndRO2_GUs& zc$FZ0-Ltjm4uwFE!T$zB>)Fnn?Wl{0PhpS+caAE9^YFY^pYb=rL3`xag~bCvb=dc) z$oeWU)12;f9BL%~&A|{I5PlBu^l2Xy=GTp4!A*$GjR?7b#403<^XLwZ86>8hk!Yq@ z4{85jf;mm`=QiIR>f3+u-|ccCEqwFDV?e`9jXBohk#+OjzubccWA1%6l$7)AFpx=( zw;z^4k$bO+N!1m9V8C~eZ-#BnN1tNZYGnY$_O7sgOgX5xFgLKFGk zog`@d8|JNXO@aM8B7+GQqcW1SxT7?tujQsXf#G*Wv-Gc6?9%|enO zDKiEqFuW@;zIa4XJt9vAz&8-27n8}c>TqkFf_-Q`jY}847~aJtjWPomKQwORn6}p|+z#Qq5m0p>RwO1F}8SKX6kHv=*v- zb+(UAjXL=c*Zxt0>Yem9#jCwe-@n}1G;KG@>Gjwlb-g)`Hw}6I`m5f`57w0ULlDrR zFXHWV%D0;;E4G`0w|?;a$AD4i$HJ{mOAY{`#CDx_%N5T1>=FI#ImGEP>OZYWu>*{F zj`=SkJ&zQA>!t6iqqa{X&^TL8zja9NQX-HIo&Xo2yri^s9jNRL1T z|LiDu%N@7}&oekxp0dR0gv$ceG(h_+&7|AO$A-CItt~S-X#|N1It$P_0;2P#*dMJO z4CeOKf4yqWs_U0}`D;+!711#JDx-h1#zz9x)hsQuKWj?G9i6xP_O7fyqM-k%#>D|g z{L5T1G_EJipaF7qG%HCne|INaW>Z84+jI6rJd3sfIJA+^R~PJWd+RPd@}vU0TfWX7 zC{98B(X;@bwODSOn;pPJx6ldzA!y)-2@$r8GZT|Si^~WL4HI1e5)725kC_$Df{oz~ zH8kn1fnbVOh&yW@FqRoJwjwsDwb&2tJS(QW>AGjqicyrc zIFyErQBb&_oUDv|_-^&pLWXV7_x8}=U)h;_#-U``;U2-jD@XyVOw;iWkl1fA`aW6; z;NTFaP%=+3`o=dJKA^@N`X0d$q|)+`*xe(X`sinY`s!MI)$0(N?XEXCncHd&Xxy%r-PYg5zEC57~PafNN^f(Knge>s3}g5Uz> z1@v)!iT$HlaW2N{m(jVL-cr)eeu?s%#MSl!6`Tm$6@mF`dG6z48X$kEfiue{P^@h6 z?e|%*W}8C^yO!yb!rX-EQ`3(JphH;iZiHG2cnv~9@K$ZJXs&# zjJhm@tE@Q9{XCTdO8`lH`{TEw==x(HI|Is}2ZH?PLF_ip+(Zo<);Ok-0u(6|ab}K?Gkd@1GTONPb9f_u4T2vsF^5pr5+pj|$3*`g4 z2@|KY6Q+OG9%}&|K2ulxj7U=B3zD|_+6P&-<&k?(ka!{04Y6A33&y`Bgo9vm$_|~N zs8q(`H0;Pe)ed;^gMz#F6)#!=iAT2I;f{L3cv)h&&_q?j5@^vpQ)GLC3H_2i`KfM* zisIRxQDvkoiu*P>!1g*(2zhBUl{xRhF@wQN)o@z10}&?cR+^XKy3VCAx&-G?(%Qbnn@VKk%{8hK_QuP|=nD zS#2BGY#pT7)ZG28#nnlmwGHPX%|+{j$xREilD@0~ua09z4^wJYbp9JmaYfuasjjGR zyy8G!ane9Ks7UsCdMIlO=uhm%nS%6Y(~(M^4v;GblB5UgE|j?Wg!cU8-7bE z=S#7%#}$;ulF3G*n_H5}E9cX&v6qP`1Iy!%%+A{obzQ0Em&T&X22SVM{>Us6hhu91 zge0EWsaja7WEO>qnc%%}lL88alu0GiS|j(?6eEkorPwe;!ZR9p{;`QdyZ8J5$gDA0 zCaz3sl7>q?tpYPv6>!SNt^}-~*K%P>idwtIY0b zv%Rb?gXpm)24f&jfG+I?9joaN??iwlXsUvSZTzMsz9nUasO;7BdXac|_S!uC=0;hi z)aWU3Eit+kw$V1l$Db7bCe@nkDMZ>4tLG`~7 zjJm@)l^{p1&jIUhUDoDQ0l4I;^%8~En zesgLc1}_++7!BGda68VIi0I5}TlDuIEF}G;gR8dTwg6~Wg!fiueI9&mQ9jRmV{ZEb z8{{njm2JlxRvu4#6;RSG!?- z^_~i&k%0gxre>8;DS93V9JaV79{Qxgaim=#6;y~Dujy52`j#Bk-qj~XX>vn?^$ZL;xjU$D+o4-7{&Hwy-Q;W@t%*#SDr zLe$ib3hBI#;9lpgIQ5bPRey%j?k0QZ{-AD6k>g<_N%MyJ!Zj zx-FKLxJukCN4&~AJInnPpX)L%ump5OXAAkmMHf$?*^?sBk(|imv4maP1PXZPh5M>B zB+tX{eulOaW3F$A)O^_+p5RY!$6#h3oiTuKw7D(sqi}@?AAglYnqH2Na-7W#hw?*+ zyYbS1!uEWmGn!)gkJ5od+k%o0t z`OaA>HJuhmRgqbz4WZru2Ix{*0t#p2dncS!I-Es%P#R98TTnaufs5^FpferY2& zU>(CQ6!ij6aN~UJ1^fiP4R*NM<5PS!?cvDQUt71SUr4uTUO*6Thl~?_x^X46`$v5m z-f(n@b}u`$+nC)viXq$azPYtUH~pgkscvW7Zl0gvQ;VZ@$ZHk}w)U%GRkAnUl#N>D zD~0L1B|bBUb}OqVnggYrQT0yH6Da(5>GM3ZDFc9a5ZXbn=)};w;%lt^iBc8^LU~qP z@us6bmM!@&*GAkuM($2a`N;IPG2b-Fz4sqhaNg@79lk7l8z?H~S`L?)oBq|BJTjj4a_ejNipkm|Zk zN!A6($I;N#{e(|i`SbMh{!|nZu+OoxJP`PbZf_U}N8*S(v&qpp*-7SW`wo>!-qLW% zWJJs{*COyqu&$ZCy^l`dR<8v?72Y`FzF!!e|F-OS4HvmrxS)9jP3egP_+xxl@ECUzlSrkwDsnYo%!a>kWLEps?wHy!)uU#lDic^ zc~mQXYg!AOt*}SoEbXEr`LYB3UP*LRI`Rrzc_RLDQ|oi8qoI=m0y&hZ%03*Yap^r< zzW9T2m~euQBeOmwmS?*ghLw8ET9b4?MKSN-7d|p#^KeleCL&34Qj%zuk~qu}4%sX? zUn<>6c(Q00{F&3<@_Zbjy%b1{l2Q^ND_WFyueCiX>Cf?y{UR7ynTk2!kC6O{R&wba z*qol9;a#s(Vb+ub^7fGS0!RJ5gu-D^iRQ;-b@(1ylbj|CS7EUpWY zuY*i}ng-ay6-*H&YEZgVCD_DyS9GR%t-yO5Oc6P@*y8)l=%lyUVJM4{Vh1q9ge_b2 z&!NAbqJBLM(rjJg;Z z+x~Ev1E7jtl6gj?FqpMv+$b$#2~FuV8|H^%BGFs1D5T*`D@=T0T84#4(5!Jf`qI-A zBI~1fk@jU@=I{;#cAGOFBobWJ z%}sGldynJGY>|y?yOQ*Dkr1w;XC9ceJWm$d9$QhnubtBm+T z)Xch)SjWo?VySX~{6wlgr}{y}L|?ga*|ni{8tB=9_1P!xRuKM<>F+|(Be*BV!4F^o zOMVPKc4n>4t|v^>p|V!N)HVgq6sLEJPcaumJo8b`1iPlGs~ZGm2ywynhzIYUKRY26 z{bf=c)p3+qc~yeYf@DSWOw-z|DY_$Brz{%Q*fuy_v((N2g|5ca?FLcsCLN^3pVY)& zk22EEp%{1@85>BG5={-ezor|l`rMgQow8HXaToS>vy?d^z1Gx(OwM%pFEm;;^7`sl zgV3_H*7`v98xGZ$J(E~6p4Vr|TVq-lvZj=R&~mhV;FD;Sd$Z@k*b)Y^Xh>(WSxscr zQ)>;mK^si~VZ#^}EH0g+p?UPgnWU<@x+Ih;jR6@MZhju2_&`sr872L-O+KAx6zN$@ zRg!^D3&&TQjJnXXm?OOLhc#%>i0UL>aYe}+`;%kUSiea#+m&3MTUl{D3T5s-s^|b= z8xtplAVBW`)6YM|w$OKe%0PYZoP}z?dNDtpyTa21FlM;oc{ItAT0BY$+ExQV5aj6J z#_GN@U3Uzan?`n2RR^6Vg_(uW5o$cCxz@a!EP#Z31Re!RDs}UmS4dO2ME0)a)L6B{ zPpiZ8Pds`OuE;r8+tcA$>_ogjuW(~P3!BUOp8S3n_B_}6vCQ!RHO3ZfzO%{cdV~iO zjP*JQSN{6%dc-?)Q;Y@Zg%#x0+GvJqvR*$Zg*5lSkxjHUfRRm*y{D?SnONP;=|Y1` z@?Ga+>3MG=2;9XuWiu@JnP4Tc?-YcoV&Bf-eS*KEkd!``D9`PQlDT4SF<@?cGmRvR zwu1@-RzLV9ZLB^7kug@nL8|Z5> zE$v!D?o57~WFxjz=e^nong?}s(4ffkMd|EtuNcRxTa=aE9NE6|_GPLd7?2GcVkba5 z-1^&Bmi4x*!cHzA^|oY)f|ZF#!AevEthvf7l@ZqaDN}LoW}e^_XnBXq(@ZJ!Z9p|JDsRYe0O_5MHKARMDCam(T zQzX{7sAKA&{pm1HZrXvH#jgJPeuZ3@PosIeeFyZ`!F^}#wo61CC_GuFGF}`3n2b6> zfDxxvTVgVQql4`gG+9BW!E|<=UTyazsDD;%G%R&+|H)rJjEYRCH-{toSpXM#>5qY% zCN+TT5v>dDtm||f_MMc0O+{5f#GZ2!We|O@`{@=;P&X9+^)b`=TnNj9%sg|NNV@2X zsIB>#D*0Df>z>=UP0=kA{bg8pfKc%Lx?Z%|TsvPUGIeczG=5L6cj!xAdA#JdAs8q@ z$MpX5@po$*VddlDr_P>*;KDtoxtQ&?ip@+9WHbnoe2MNF_3uRB_~l{slfpv2Wov09 z61IVNnXoG98xm|D4QqoU+Z%+;9WU)4T8tL$A7;0hfB37?GCt zc`A$p@$t0K3Cg8GArm~mGOF358N_>yL(}#_TdbgV5^AIi(dOx&7(0Y2apz;FD8xbH z4^ox$E8=?tutA|ez%OD%M*KMuSC9m|Qe!{%sRXzhRw%utOol41A>N*0xyHmUjS56t z5+GZ)hY}K*i>$}OqkA!;00iGyQ8Xx#W5^LPmL~9Jmr=E}xVpjB;ga0o=%^ZgX`6_K zWRE?%`^MrWirTpixP6>!oM*U-O}Q{dVV zJh{Rc&0X^2(|uClle)!evT>2N(mc^Sy2mi;w@aw1cFnd{$ON~3@1dcbkphu;vbTpj zM%+S!Sc9~Dz%3fwv56~+Ut!`=ukZalD%Uw(+i}>4W&yv*+)3O*Gw>8ZK7Y1r^2bTz zz!!;}7Bqb)(3b$2SAaFH(tAF~z`cAyt8%gE6V%MA`9|?5PXr**IbChDbjb({67;nZ z(M~ybH#<&%wXAL6XA~cgs)orLd)e@Xu~$0?W>rf7yP?{#!^+hcaLv)4GwQ15#r38i zv2T|5Z7FX-^FNlTB@gF+ScRjbo|e~JnYLxFbVdh-Gj^~yOaRyy<{OI|4K33(j&=F^ z_!S9b=^*R}Z)IjZKGK#2ungZG-BGkUq>@^#37<~XD;8(GNtE6iDH`NcsxD|=c(h3H z1P(`AW2?P7CYO$CI|b?@Me`jyE#;G|%5JA2g)^%KwR#uZf*vXjI;@`Su5f4Jp;_%K ziWUNm6D|Gv; zhk$m;<~}b-`R_>1g+VJqI4M6AQ8+m7iY)+%El3hW(qx&nUirDOdQe5G&~^jR zbos`ZQ?5h4WlA#mG`XE1X2aW4gg+?`D%rCDw~dPnkc}7L!QH`2pC@S!qH#+rNYHU| z1Gh;B6r-`Fhimiar;^s_<>n`VdhD!roXGcneA6L~zT#z@M zo;q!JHCJ=*Dmo{aC96JE3Lu6smW!&C7&sA{Ykpqr6#kL08atuDQw%TZfi^J-Ol z%gjLQt*+P5UTzaz-V@Uj!mnSZdS6a~xh3}nU=L};;G8%pO9hp8?VNaR!(IOR-ZM~W z-{!!CV8m-ItH^P?D-gpA8PnGCjwYtQWH{{sdff1d1lrn$!KPEy=r338+-QX3p?lw$ z{(xFyw+r*s)=Pjsk}X96%1Q;NRI7B_VJ~@gA$gHCxENPyUdU&H$-g}<6`u66LLl#} z`wXio{044Jo8xw|4+bDgA8)FE!=9|}x<7XTo&I6&vrLlgsl>Udp0aXVZF^;+FJ>jA znYQ}pCv)$ETfhTpH?p?>{{CaQtY{1fWv4_Q*bnI-?~T6g1z}omwEeCoy9H4AFL1GiHq95t22JNZyG8c^OE4Q_q@`P=GxK1 zzopx9ZNF(-=oP-mnUU5n2S3*0KQ9$UF zM}jw$K@>iiU7Xp*{=yY1P%DD!FSwJRZB%(ol??^QNEpjr{G$7;JV)H}mOoRp95nu6 z7^JxYZwx%KB|VcmsWbG(kphrKlaVjXGpn@o+RKwqn{87gj6|kr2+))y@iIGKw)1vB z@8}pR0$@dW^4U1}pTR5ThEa{sr^!%E@e&4uRzN7tj#mkJ&!JXHLd$7R6(p&KdQ#mB zDPzwfH7$!bFJPd5n+o=}?=(bX6d1VJIJKk8`M4B50jln#7UH|Q8A zsgPLVTgAnq)~qAIQFd;eW~Fn9`5JkU--5?=*%-dLvcVxUn{+Ow;uLdoX`6~_`>Sn}XW5ttbjZ;HRcZVoPXBI!c8;Rvpe>Fd&SwgVy> zq2!>ra8!5OaVd>@9)8=~1_?|)V_F(@29gYPLdL2D9xJfG*%_6H$4?HV+A%guW68#1 zL1oe^{aWw-Nzk^OO_jVBNbB%|-6`=WfksrmzV#^z57EwZR)y04ZH!k9-*QwE#~#0d z>>v+*l1QvhfJL&eUve`myG}VB64RbMq5>qtLQc#Mq8yAp)EPGgXGNgjpih^?-3oBR{`rY+gzhT|(eOSRxLK4G< z_9|$(_WUzV?i01Vzobac@SyN@e}5EX^jm2W%7y*o#Vul$#2`*l4ViESgDxOLCjYBZ zG8|*#rOam>+-Au@ zNMeTC*ZZoU@_2`GE|c*>+&msm(AGf$- zzp8zKB7R(vDR;`F$+(8oI|0DKk4D^qqae@eEOpbsEUlUEq!gabk@Zr*yli9laxUs=1vd2JH+=)`BGgPLWyQcd= zA^=I~jNs;U>T++0w)9cYmv3HLIsE8*wbND0@n7NTjtxp(nW<{~&dizpF1dtZ^?gsn z&tniLLF!wGKr}%#Ii?LkG-;^MkrBmW zp}E|s?XPLOL4hJ1SONk~$Cbj%feVKtFrB{R-za4KB~&hK22jc%N}qZXcbgk~%858w zzv9Kn2qe(;2A2@~;yVfpAqpW{J7P=lA5M=DXTga+GEia#c=ZMcck~3q(cfwNz)Ytg zVrS5ubfePI`;z;RBW94-G8wReqt%KSh^R$#f6Hge9UEYpIi3S_!~ItTeKFj?)pMa} z>-7L6v@kT)VA9h1kotjrrjQPSa4cK@b8(ar5~m)eZN1`ELV$jlw;J z8+ejy`TD7&paYIq^J@`CC84JwNT>!_ksMLzsQ8RxQDyj40zwDuk<*NXLOqdlAaWqU z$$JMzLZUpOqfyn2BNB!4=JBddwY!AO-8PWKulBy`J@qnhzU(d(W$%67lCC)cuzyBp z?QNM>DzQ6l>@=d~5nB(rGcEOT{Ah`53FF1rK@f(rf&^HZXqGEYX#V7CmTI557j4n6 ztQyc>pgByl&FJbwSv2>E)?`{)GOX3ah`+d+B}7i!{PX65cP6dth#u!~;4yMu|6{%J!O3|cgU;$co1$*Z z2PXVT|7KlUoiBN7M>;9(*Byt~qWIjLnT>Pqz6KsSA>7#!O;xsZ`mKHPv`q`idk(qt z__}LrK$OmAc2hu9>C~962o`^&=<64{JpXUbAn*W2XOxXgLdl019u0{>vR+3j28@L;{1K)mW$F?EJkjJ^0Zw@D6#)_m3Syuy5k9Q($YGlRawC zm0rx4@a0jyR=!r!`Cs{#HaE1ll!PYq=^ey+f$ooSiWcr<+6q(xJIPhz?~UX_b(2d% z0P<4tGR9KI=m{kifSD%I(E>4>)UT!A$WhS;^cDF=I>%C! zqQY-MBh|@YgnkF*6FP9ipnKdjca)y9IEh0o=ShXe-God3?tkMHJtTo4#nF&4PAFty zdn!KZrLoQnr<~+z~Lgey(yr?0T65-LlFs#G^5c@GS1_I@${s5LUd)2GuVeYWXH+lHrlHHQlRK z#ZEM!nQ0aEBYfKy%iv9gr%D3u|%wPvqE{x?&9RfdG|r*2fq z)vzlAsqZI`E7uC@r4ifUpY^&Q)dtsoxwA9I?qWHluLkD!rkYz>iQSMpvVJ{{pGaDL zs=o$)TN)Z8P8^I}bXuhw5dG-HqG0N1O{;J`{+j6u6;32JcRBM3+GM>0Y6Afm5qaLQ z1_1)%%>180KRe665mC~0?DDz(@lu4G_(&uBj5tn#V>1?kUdkFN(m;D*sfw~&Zw_W0 zal-cUU`6DEmZ2Y1IP?9UL}XCFn|mm_i}&^Uu%hJ$h$!dvQ2R2L8{#u?4)k%vOqjb6 zISI(nj{I#C;=|dp+dLETX8B8hd6{h8pF%Z z1dZ7H64)8@{?P0sZ-NKnZ`PS1>Fo0lf8W!ajSJk{){3R8%3fk z{~?QhhEjOTJBPq&_3N!#@`29!JMAY}PPjl{_m~W%_hF0hE?X1B3 zQIJ3P@^+&Sacgb&6V;z-Wz5;b)T5)A4)yGDK7UZ#!Q(~59-Zp`gWqo?XY)w0kyb1= z#>J9iFE4v~dOl{LM^5{^%3I%}K|J1#359F}Nr&B+_j#Irmf444mFRFJxnPk2aQD>z zh@F&1gWO*{$YW%!AX6HGkGmMvz&x8n^_0VVd*1GK(}hBL$Kd!)D8qCL?p#i+KgOQ< zI<+)PR!(~j>Y+XAUARE>lEnBsl1VUwk~=x95g>|-&Tbl))?xZ$N737bt z)_-TBz8If{RgdN>D~nh9%PArMBh=aQWU{#=hyG z6h=@S*5MLa+q4NZ`1+Ms&W2G(3s1uZY|+3-{lV}+)1inJokyKloe{$7t-dj^TzI>T zQ@0M2)u7anhVNX?iAS5UfpPt{(OyTr!aQ~}aYTOrc1M7C=x)CQ_0TBY@Rat4tQYnE zgi&7aK8GA?9%p^D*?AiP?Wb&+(TerVjmQm~w_N7Pj)47mvA3rbKbJW&-0rrP#kwlZ zz@IFohMwYg;8y)vKiIEoNxG0bl!hBRWd_q!sf7vRhoz7K_y)6qzU4vhMih0;6Wuoh zxu9wTvme11#3FdsB`I#_W+VnEY>~B5lngzEc-tPHuneg(-)CO{CB{wwrNxdj|9sSg zAP?(s*LM@fZl0D-2|GDV=eTgUFmD2}V{j8)qadmgVw|PQPvS0DPF!QuDRc5ZC%U9r ziMlY=;0VJ39z&#}(jiOg4(xJG4HISBC7|0j8c0XeQm}j@D|Wv*B@0d*jY8ZAr9fOw zBo54|fmyjS^#MzOwc&z?=2S@G#X?<}Nr7}Zsq0U1TATbhRa&E_LRO23H{(%T8MS^fWOLO+A9XbwdALBq->&%|pYXLb) zn|RRghRRm>r347IpSl0r2Y`{tBDZt$^eHF>;9pAeMe3DZnh^HT)>9P`n?_@Q>3d`5 z?C%C?8EvbAlQ?>5|7Uf{o$8?(i_h1MTosxS1(99&G@&m~>rPv5n_kVls~zgCh)-b4 zP5kqFfu`w4AR3$V;?ev9M0HgJe?$aNaA~uB%CqgYfA(*rFx)@qnxzIT?mhrHZvaYa z1UY1O*JSb=yC!xItoBMlsPO4)*E)hf?9IRRM(~9yll38g&vYK8aoDV;Pq_BE8eXcw zZ$AjgfWxEW*l^lg-y1{3QyJV-!F4$EorS_*(J4n0_I+V$fO(dUW2W=L_5CWC$^eTz6P@vUY6E<;>4_9l>b=NLXywhycnzIc%#oEJ?vk> zO1(^U{ z3rGh>QPfVGbsuZ0y7j0P+G&+pOvJJ@27mEg1s4M$oqJI@hz&gvO(Xibra}iQCXTIZ z{rod>xm$)>kcu9=Z?`A-2pY}`uu0Ykuc27ZG}=UHVfTI*egd%#P{Uh)NxraejN4l= zK_-i<4d(Rag{5@XEI*ekUIx6gC-IHW+XN~%qc=-MXyxKJoh$Xy#%l_fmR6MV!&wGe zmR?LHVEi z)ktdrvjweBjUo6#!?_j%>35?Udn0?Jgl~oR!$@Np|E+_++{2u$dJ~ z#U5R~lCEM)1IA=i9jML?3^nR(k_Lqc%gW%$EFKYUI6?Fj%G5@Hyylq7Q<(_t+ps|C}Ld z(X}h!qchQS`)xkzEQKTbLXKk1REy(hIL@#*^k66CS`kv^nRYs+Q>iu4w@}D>0)S=w zQLZ4|Uf{RflY{w&tio*uu!aLr8J}Bpzjj9!ADnBk*kYvOyDGh)>)mjGW`ME9^2K$6 z(QkH>9a_}pE2YCwu^a0k3peG9mGXJob+J9kq4%~ZG;2cJ6Kt`k>e+~;$8!|+lU;9a zP-D^35{LZUGi7)`fzhBQDIph)Q`MypUf8$Bu|7w##Ya?DiMh-{uhUx;qvRs!t#xKQ z&T|`?wtgdu=y~SU7P>G%J>mMtGvXxjZ>wx|9m6`_oG5GO5xX3Yc#3%!vf#Fi%8v`n z_Wz5kcMOj#YTAWk+fF97ZA@%+>||n_9oyE#b|%)u#>BR5^W=Hn@0{y;zaQQE+P&AV zy{davtzK2D?mJuB!9nN8Sr)zpM*nl{qF$drn)7STkZ;nh=p~7>4Pz>(kuO{==X)Ee zvEdK_W1^{?(c^LNI2l!&80~}`$)pvkrspI2Rg8uwN2#C(@yp%r``jLF2$DM7NVE|1%L%jf;jq=R$R8$`z z#xUyENXNh^%IajjqA77L@jr&ekh#_^?pP__s($OZrdyqukoZ>)pgd|jdZFx4i8+3e z*ZRZ|>ri>PhZS;W+Gw6%l?o3$KwIAf!Nx|kGkVhz0INwwU%%FcyWmMzK~JaeW$67t z-aZu%^1hbIFz;dYM0&<7@J8Mp;N9j_!57Hr>lj&hN?hBXrbYa#i?x0Fa9>ysLFtLr zZh9DH;Z?-B^td~nz42-@bkXPIDn-uW#m|vd3J^O-f3}kr?}ZZTda3|oeZr#5%r?N< zn3MmNj^vT`0LdgvkNhDvD#lrqiW0!W>+0*4vz@_*pkqBt zOIHb?$O2rDR7Y)SC+X8`HC3!M?t(W;nBO+5F@&jgYE&>56$BNP$bn{ySu^NpBhO{B zLf$`FFJ!JX(n8BGB@a^zf3sOM*=Rp7R99O)FI@`#Z)?pgrEClPw$>m2&ssUS{>NIc z6nB}wr_(nLdbYN83Ya(8ez6Hp3(-Cr&^?N8?5${My>;GmUd7KhYp%#7OdLj84;FOn zKZ3qF_T3v{HO0=Khu*Vv+tY~C8C8pzT44JSs@MWKqo^6bHE%ti%GmUSA>J<&$X!Ec zn=bk@_+bdLruChkfN|3;X z>3am+(GO|>j^&7Y5tv<3_RSJeCjwrBiMk28Kb{3c)54o7fb&O=-I9b{@^gt=HEKIX z{?a4S1$IvOg6v_Jvz{p-IPqE892R8`%p`Vc!yzvOv89tHDb&ZFIMfKVA#=ZCKQio259YN>jAk&|j} zITdr^xx1q0nKUkIgVPJi!Mds|a5YwdZNN4WOsmz&b_GSinh$hKIR)h(;~V%&~xO~&@P&~u=oSSPBjxz>^kHDiw3 z4rel+b$BAP0k7*ywa;A=5R1(LwaS~+<6z7b-3M_M{d&2od{+zK zB&8iSU2ZqQ1nX8PS6gr8(S!!T~?**IIEu zyMQ5w;E{+?Cdykf+Q_!EmvHP$J)>^!0tf-dbj?ayx6-#fQ*~dyKGMD`B~mhO?Y|}$ ztueDmbDx5kh!dGIG=LqsVPnL8iBOLB?P0MCIlGd39%w)3mb%Q`mfXF7_*#SrNJD*T5-rZb|)5FfY>%T?44j{DsVrEb--R_%8ArF~Ov{bL$Pcs{C4r1){Q5Ce6d4wF%r;9U}l zckaMlK?!%_{7wq-u3%H;!0BDzJ0J-w{|>IPY?XGV0BO@GNFt%~rmNqkdQfp30Un4c zN5(YJI;HU>c~r^qd9`!w+x)kU3b=Q)zjK)X$e9`_XczG~2Xyk2txGnuhNO;8GjfZ} z^5mIRsDy)7kJ%mLP(C;lpj{GA5jt0H>#fbU@QFK>cYJuuYk^n@iep#nwvQ7vGgMJm zNE7`g7P25`{&6Pd=yI&beeSfE82Naq+{#u>b-lH3(KrO$Cid{_`F?-*5$p%{fxFfE z^7@y#S5w6Smpkfy5!HIfJSs=!*~dJpMCF;sJgP=9l=o)#*I?in9J5A{)%o*4aZh zP2azsK2GI~t5z{>ja!2F$*wW~z=HVRV1@ z=SBcs0qZ(>_m9SrMJEKi6-)Ei9mI~|BEiGM)w?zb6(87@EgF?#*Y`&KcV5YOi}6AH zWB8D#Q6e2qYeTIUzzB3{LF(7~rT6oX73ufite@hi*2QvCBy%Dj!W`8$6v=uogmKU) zzbw-x(8|HOlXgHzyT=!w^vIoPBRsw#O6ks0qzY;VG=0xWR7$tE0i=$j&=GD5xR)qP zH+5316Jq2lq!g&hR|}ifeJw)`s3%gqBfFVAwY#cTxZU4ijlXn?R>?)M$BR-~Ex`n< zfn(g80VS|}tP3Tu{Q2>KDIfNTjJO)<@Oit)X@x4htRuU%bY^B;mpt`B<5A5D!X$et zK#a>>DlE#4NFRAPd?r{u4%?{!tUF<)0#FNKQ#W6HLlsMdQG~rc!9utYAF4mjjPeGC4BC!QxWM4B)ddO zmKCS0Z&NE+X^XB$`q|S`Tmi$qTl4Ec#WJNj-jD-+G+H!lXIo=jCzDc5Ce=eZ{-w<( z_Kf+P2fW6R;!mvT*S0ypOH>}+^wVf>G+Y`6Lx>`nqn!Aqo9QE&oc#Bo^5K@bCmyuv z2K)K&=bS7U)0ou>VTXaJnKZ#8F!beLw4TANezG3rCviZx7q(|hzR*fl@~JZJi+im% zjpyGVr}!=`U^wlKpiyzD-)WW-LK$g`pBE^Eh}W;D;#j4YH?k zDyy~xu|vEkF%|KUBl|5?M2pu(zf^gKlomCLhtah#8c~?hx%}rlnhvQzOecGnG@Jct z>98|XAu$on{T2_-#V?5%38B~V6L_1&lr+;ZYqPz#IqbdZr^ISx1H|Ull0*brWlenv z0kQL6*yC@rz1s zZGA0Ub+RHE8w%}c*RtB`NY?%~IZvdL-r%AEJrlpw%|U4foj%j=P;@dzHKD*XJA8s1 zbM$=geiuJ*F$nAfy@y&`a51!`mCPL#6^J`kp;Pzmny`_3#au%6Z;iiw=;1iE9b-> z_os+Q)fL^nd)I_Hssnf8D6d+~PZS2wB3}L7epnbn{e`u;#(2t7cUcwNUtg6Q*44_f zG6$oW5DUe|8!^0nFZA$7&UDFBw$u%r#F zx#^>Rn#k`eE{Ue;y>yus>IH=wu2I`~5t|}vDJtO!g&rTVn))Y4oWHO^mJqd_y?;LY zXdx5q3+HS5+BZ2yY;J^o^%p%W?)QTcvrss@YX2^Mwz+5-!u;gm-8v`3j$AE{2L zU`+)+BPF;d!X=}fB4UB!`S$&22oGpo;Z5EbRCgp5K;ocEpo;1GO>;Bhh*y9fS^;yf zU21Q-Qug2-k6SKc+DUX*JVzyGze%O16CXzsnR*hLg|nw)lXxi(G|>1q&~;kShvgN@@OyTBekgsvs4EF=Lcg%< zfENmN?s0T%hVE{OV4Oj8*mb{~>$v_2Uidd@$<{+Ihq6#US@fgai=sC{@}c>gEvsTx zQ9uH$!5;&VQ;o#6>S8f8yJGMso(*wnSP~88{S4`P@Kg+~!||XA%Ifk5$GO8{v`(|m z{Q$zV?J>ycJ0QKwla^e<%z?v0ATvW^z?I=W+%iuQVK@$J^vYQ6DRt{`P4B8{(sCu{ zXLr`iM-ddX2S3SlIt9bcAniu zy!=kM8nuH|SCXUnPq8Jwxpq-mgd^(4`3T|*-HjfQjf{EBJlwzapzTd!m%6aMK;bT~ z8}sLXP^ZmEqr3zL+(iyv^E9jHx+abAksKB+g@0qfBce`z$xiimE?Z(ZHawk|IZjN8 zv=BA4)V3S@Z+hF!bE8j+v}D(wA<;pGau?BM)8sKS;7vrOT13Uhi?oD~sz+7%Ja=YU z#}qYA)7tyh_87R7AJfN@0_CuMfq0H}PB%_^SwiF{x{%PY0EJfNp8%i5I^CZLh;7l9tC`4M8bZGW?F@7*gjJtyiV^ zojtbAjoFReZzqLa%9@!SsYb2z4C>9oR@gkytHE6_%@xAtjOiTG;S-W&3rrWQ9;B=R z8=fxKwpoj+mRJxC0YkqlvzJBJk-yUn6f-ow2CIqC33SXtP-I02?uT;wQ0NaG6j|_x=|m!EkT)!! zSpg(k;gdTiCakJb??{;1n!6bwM$~>oc!^W zUyn5B8_p^e(Rtk`TO!h!(KbT;DcJf%B?O&hGc@JpK}_{IRKLD8Z=xa2NKjaoGrjom z+63n|_0U|s%^!iS!Df$Ey9`4oKMRhgzw6DV|6=4^H=i(WxOBBg-2q4BAYOLrsE#kU zw-Wj{iA$!CQ^3SC1&F;Vb!W)qdSQp_<&;Q}$$kQAeJBs9H}O%3jP1j|+z}(&3AzJ{X*~bINtZeol=puVZc(8sJHhcOvg`j{yiEv;c6=7 z?1`>x7g-bd!JtAR&n%M>E5+MKuAT|$t26VP-QdRLFCTn!E&i=%>ierdG013OVLr28 z0%u#IIVM8kl&#h12&gVvpW*Q8AXjf^pFynUGjIh>gGnI7TQn;Z8WtpF4oOsXt_Kip z|D42%FM;j*fN`=x67cY$T_grF3Yu5}_MmAH!U7(L`|&E(jFIUcq#Uw-XH#yaqxS1A zmyBoh!Js>DMJC#P=)OlJ_z}n7@4_+G{g?_>_dSvb@Mc!6a+=FL8}|fQ-&b7~p_$BH zUfhWp!o{)l2b5$foYmj?HH+|r!8aM?ui1CyfU*feJdfZ63VX+Vs5pVwwdvZFF0d^k zr?JW_P3-AQiLwhj+NFYLOUVMi)Fft=SJu0#-gsz*lA6r_0LZLyvm+?E7BBuS$t@oV zJ2*@SZkdd{yXwc`;zna77##`UI-7dLB7BXDbhJu}=M&!X<S2GX}SHzM;@ z14lwV?wi09R!C7U)=8cT!gHu%w+s~-_Eb53zsByWi6W4E^8!GIN|m<5Xg0|6;cbL0Xe26FRo|2MVMm1_N8lC170 z4b9I9im4b)((=U_1*zh1@*c6u3b=@T0D2aMg5=kSjhGA^DswWXh-t!-;E}J7&xt|J zEJSAleQEX!iYo#POq7S*N?%w=dW(PuuI_#5RU3(=1E??%;j%CJ`8riHKfcTGI$R09 zRRTUe78s)gvO?*1>OP!1e+EiPj;3Pog79G(@Qo(N65gtxP^P2|&5u|f{mpTpw-S4J z^p@CTD7;Hb+A#|~HJ8PV_Pq;3^ip3q6ARX?cFq_uME6BotN|ORAK+IZ{6~>R$2%lT z#18FGK|`=GGa-^scrja9J7723lhSEWyf5i<99V0UMG>rcnr+w9QlH#ZzX29ItK$~) zz9SeFacgd3{dE!i&L~yW=656)pMvuTJ5d?+Pq^9*;PoAj4UaYd9#_$@ZbVc9@&pDJ zu*FmQ{L1C zdZ4{dJwRxQ4e9RE7ty|hX46{J9EA9WTds!-i}H$RQuaR7nlC0_(#l%6hAN~v6QWST z!05^k@hy|WmC{@O4B^o|I{|qYi!+PCZGH`-!%&2zH-i+DgeXzhijXSi^u3uvr)`&mDA^b!f*JBR3jyq9U>qSFDxcS>n2 zoj0N`U+Ruha&*!CdsdURgTh%k=h3{VYZ9AqWJ%PlJ=IsH+2gBP!R%*)oZhbrHsxwr zoOyyN>)bz822-q=VJECV{>kRpcP-LK{?nh-KUug(@*d=%`}|qUk##5J)x|XM#~9DG zPO8`B^?qlrU-Ia_|1bgf;-X~kDmCr0yM=)Oj1M0!{xPVk|9iZKBK#*(N&@8iFA7yt z+JA`xhPSR%HT@7N+z8Of6D#m9g6G3vD!Me)zZr0}DNQ^e_OydEMreDub^T z$C2WI_d-bq|sH zfDhKX?f0<&vCD%G;0hrS~weJFQhK~x#(z-3uIid+r=6a3whzw#arR1vR-eMsSd#s8o4d@-Zg%8f&722qq&g1~SHA(6f0aQ(CirP7$(4pQxjHQ# zTQupISV>-NMPI#Zt9Hk;!Wf)>G}fHRUCwQD zsc$jmY%1&tPyNjFY4&gqGcK5mah+?9CqnJyyFrx9i+ApyRojv|8@2eWX**c)cz>qf zyLsUBQIlC^0Km8U=asEzlji7_(8kARsybb#(WU+l*}~5Y=1B^B>+yp&;(L&@{KqMi zq;2Yg!2;Lpc9~JWNeeMjYvBi`P$P;~H=5B@zEKUjmMgv~3md=vv1>M?=i4eQ4Ncy3 zHCQA)I9m=-P?C+UU9%L{gN(HB+aEt5{*OOyKz43B_q-imFx0F&h z{i}PKd9h3%i5bvK5pfrOp82`M--Sdr3W=cW%|!GcuEHhHPqna0V1+!8lHUvRpknWv zMHZkd)yiW8@b^X?LPnVwP7@@^90^&iMKv8`YY$jvOYlYVf-!0`R=f(+m(MTv0+JdR zV33VFTKx!8={J&>0fuy^y8e#m@Rb<}qdz|%M`KmZjBo#UYgZ`=6v!*ffM87Oi7nrR zzA$S3buH3$a~1tQDGk_sV45P=8fWqT5jYkvUgUXzn7fsq_akXl{~7|S;8-?=|Jv98 zse0TbBOC5kVziqMix#JzH^Ww*4rpvBkt#Sb_F*z=dHvNo96g3;70hy)*>sW**JOgc zriH9HwR#%q3VDiOXYWZsxeX1UL|Uj7vvJLQiqKJ*w-yUlTbW|1eKFmYB*w)Tq;LER zbqhoGB*wy7rMlKrCJVoV>Z5Z3!hwyCL1a zaX-OZK@C3N>+Y*+(?iLx4Vun_6vq2L=^Y|~UlmQUhyUWVg@}bbd1CrunBsCZ7sn$W z7PWRYs=0b6BGT2)o}G^}2L0NDe!ST}0pEUa88lN-*wDsa)9)S!DclmHTRp2WflHbr zdo&-q#s(FOX-@X~=!d8?FWtbk#11d({d1`P`A64#;EPpn>j3gF&FR>hDc!d|ajUaP zqxw5*GhLRF;%|J$=DNP6vv_a(UcqtdD#^guqB=?rBfTgWHqjZdVPZRgNa%v>48(We z=F*rSY;?7Gg8r==;ie)~h1};XrxmxOTb!iT=vLsrsgKUIdb)5n|4^XZdeL#AnDzl; zb)h-KXI!_5%2o(uH~fW=HF-?DaP{|x`+WY*+x&(0a2ParM{FjPHE(}Jb@iTu=UGC> zqdn+NVcmxpA!B-&_NYdJ>FR^bG!PasJ?LlcZ8lvrs>?qX|9UnGyl&v zz#^YG9bHae3Wwqj+Cpv6$PETwN00P8gFl)$d|qTEEn)|_nzBkck9)i^2T(ESAQBn< z8JsvC%cO7ji~qWF8^1(DFpdGT+9J?USo=|to zS26wF6qOHxE-n1}6c})mH;3hSL>L+AtbKcd%|wQTso-~vk+S_mr%Vg-x8*}K!*nH> z#)9QJvp*1sxBZem0rOb+6IiX9uk9L8{cDS9E&oq)MPNCw_zv6p%%@C_sh>0rR1)yB zRkE7wyo3wVcBHG_fiOVQy!9!4QiMFxtTkx`!8@Io)~p1;fy{$@kBFSdWhzaInD1Vh zlB%RU>JnmZx@l??;7eHL+v57Z4gli}(}Aoy<=~6N-ubnc&#H}O2lW45ylbgBOnOCX zrWjVjo>;rd6AB@M2VbpRArHi0>Ha(NB~xBdfC^DxVCvMltcK*g0|Ybx946h=dZ4`M zzOeyQ|AP%!o3*ZGt%+$~{Vk#7q6+Q%md$akJIlk>{3nlLBS=+MT)}+uywUYLx;BF{ zsZMu(1ysJVHHr zJg5ztPAG%gcJ<1zsw18$_V&c~37ZBTz7pu{%H*ydwk#WvEJ|L2T#p0 zeFEoHA}U|hLaR07`||(mpWOs*g`8Sb(o@Dg7aoFZ;fPXY>o30l+c={k^Zz!^UP#XW ze~q000-^0Qzsm6c+dtrcI%vm^dn%FjefU-@h4~w}aMEr5Ik_7d3Whq#Qi@PR>!-R{ zdSRpsy2Ctis%^fV1V3g(?n9Is`kh+I#*>^tZ#aZ>1#S7Hdcw(_U(s_XF^%ArB;LQb zgx5Pi)7wts4F3O~qF#3bA!3m^Ob^8v|7rwQ^2Ykt00ZZ+!#8hiAvYQekqfG3p(^7+ zh}`73jFxf#0LX#2TRb46ztvQ_8lDWnr1oZnDuiCKUl=BILP~I0G|0VPnXcEM4p;YE zhR!hqa6xAO3po!KwJ!}K+O57<3y0XAwq?b#OshM!SAizak2El*naC0*p6Lmq-Whpu zN`M6%z+wbx&{UF|@iL+WiL{5Ud>W3PM%wnbl!8NXP4UzQK`Vj`cbTJV{8bJrm5oQD zGMPS&R|-wSEkI&kir9#yfYy4Qp$lGGZ3e^MyPpgo69Flwf+0zQ05we{@n=VaK#307Q>S$xBK_lPf}NVj)8!wLKPvFoV1iA19CV>?$Ag3<#VSq&Cp03DFdW9Ohm1-<^As)VB;-0K~*Lwg(FuWq{y;B%FWS9l5D_C6XpHc z|G=We%ai0m2D*UF$Qh+7`TvB4WM;6Cp|;3_Jd}onk)!>OQVh(Kbi%itV5kgAa&-Su z$|69*7_@>4>px0OWgcLWDBA%8zO_28^7I1*yMzB9ty};(#{bdk_(Sc;6Un^Xl}hsGbo{Q6`bDfqOCk+Yu@ zbE=Gm8oVYY%a=bug~ShzGt7{mBbdRDk5hK3Q+A9#E?rQ8K6|-izni*zn__Y9j92%i zrM$vMm8n%{y>X7FFlgdC?eJ&>GboZmu`c5%O;ci4A9$E4< z%#Z>Iy%(Ii*P+-92)!7%-xa+ZDT4Xrn;Mi!mU2wv)`p-5DXr37%D)^12Q_~qOd#;$ z$PMG(5L;P?8pV#-$H!`+X~EdHg|k*RQTOL=DRq6{i-GVvt@9)$kIlt@Xfvt*LWYuj z+(E_3Ha4==Q`V=EnmX+%nONf0*7=RE?rH~YoNr@MJMs!3lTwJm5>bo% z-4d`B&UbSqK(D22ri9tTfH|J#!Cbl}ezM{!dL=agJ*E~#j$y+LBMjR#_RL~NMb!4x zHUiu5Ko-2)ZwUJ!t-WZCTA{XRt#zg_cY>SCe+|nkq!t5IO|T*azC+-t(dD=+ZjJzd z4@odaQNOB6OU!ls4o`#@ymMO6cc7B`O7s+?efE&;#XA_m{k$7(?3AGO7)}UxzaQ%q z`zs^kIUJrlJDMgF^r_5tg|m2d*@m#nqTz~LL~;9%_4w--F1haJ`&CWgCKUOA3ECf) z1H0ctMNH`q=*M>EJrtMqnyc!+J*v=vyIZ->m+8LGV?%#y*P}5J|Ds{5#fO-2I|H~= zCWoRKgXL6aRF*mLd7Y22z6$Hz?NGYlS$-Eab#xqD@@?Ka$JkRvGu(v8at^HqUH14j z4(d6@x?YuiP2j~YmwxWl8O2|$kQvg^vTP?R;Z4sX-I7&(>Oei^mBgA*iIphbQa zus%4I3vy)Z=4XayO7L&5S6+xbyuV-`)2~#UMv=*p4y6RP$h4#Z{l5@+`pYeOkvw#R zJ^0AY!#Lm-V@n2ZMxZ)QLeirTdAK-7RxK_;-_AeyXoq z&ZIW@f;9?9^y9VPPBqjX>4T=@I ze93_~+8-X*rj4JPp6Pnpd_>)2=9(UFbV)=>FFuoPRl_{bM^m6cppNuW-je+1Y4rAQ z7hz3V^Blh3R$_(cRlK%W}eV39%m$DC}iqCZso$ z$=S@OtGDDU1flGTeq9q%V$ykh%ANQsj*r3TO7v{nwdo{s2~up3`tG6EfyWEFDK;nc zB~2536Ly~58wGs03pxwuZZKXgTx8ybiu(@&i-)pHo_}%yHKDgz9+IcDhkcOWXbv7e zAdb0_$dFE4bG%@SI@Cj!Y)fFT7t3^$L;x|GNi%f?=lYrV5EbNE3bfU?9_=na!W6R1 zrqejb0V%`Bd5qT<`Nu!Z3_O#GPPrcA=XEN6YtD!(Srf0;%HrnKRhZ8F z4BjBAP}~m#uDyZ?m;cSt_bmX(`@}3QO&3Y~W?sO`$(X$jJP_i|bNLf_7eBa~J+Opq zzbg0$d0)2vCb4?SKbbQB%n_tZ*O>v+p>9s}ogVsqvgtob(PauaA*weZqn2g`dJSlD z>D;Ec_kce0c=lY@rvE#;9>@jxgJE~=CwwDtVEG6ML?>`PpNTgI+6k?sJn^Qw_53n; zq&1va1h>i9h1xPijMA50LPHvys&43_&Pj>`$>m3Wr`9>g0M(rb=@98wEwnGkU*}g$ zO7Z(M`#XSYg0M`f*6PwBP6+ApF%h8=sJp}D8iLBKE2Xz%#s_pf1%mvqg@22WJ(v;# zY}Rq^Q}TDPs`J0WDj)~*f9qG9QuXY!nEzY9N^fuko@Gy?WGh=LZl#*6*6|&X#mHWy zt!Fc7Z|wF94Gt!!H$@eP(Q@#4&k55IB+_L(`cJ^BINKBDf&KprSV6P#obg`IcH_ux zsY)MyLV^T=MECRDY;(kkmj4p@(mw-nHJMXUGzH?U_U93w57d+>N|E0k=KyrAW)o(N zkVtD&$;WOv!hDESnpkruANwDTFE_CvUd7PNQF%tBj~qDdrcDC(>wQlJwY6A{Y6|(3j3JQc%ScJk=%jhYT-h7iXnZy;RMJPggo) zQea*j!Z;(xebj+s!kykIuEqejym7pKg@{BD!O^vKJk!OVstfG^9kNXkrKxl-+8@-Y z>wL{0s>K*|t|7gE7Q8~d@`YJB^085 zxn%IUzGwamxJo8*kjdUR!l@%}OJWkU+J{(Htte^R7~(Z}g0RTNkA!|55;E#7Gnd$Y zcv{ABsyXg!+eVnDV^zfGdV_g>SZcDQ)35K(3;veQ_9wvB%B!QUqoyk~X8I;(wg%{E zI9}KEXn2%2nUF!nxqnEsTre$Ld}F%@gV7 zkNWyA%XdmII9{4LJs56FwI5hN5u8cuKWv}xBJ97I|Fix2Hz+s^@IrIVZjBqo_eukX zwpr1U{0%gAs=)N;WH!p$b0qx3LZn5(q0#D_exYX#>?Ahle7fUysHb< z_ba?0@S715QLc5~Y60_XWL?lUfoMue_h%X1E9BlJW;8XW7mQpfUzf0s95wNoQI1U{ z`zVnFi*_$*ahj>DH%P5Hko@een?&3cd=z|b-ch%O3Sip=q`$OcJJo19Uc-=B`Coe z(uTTww_d;9Jb+@Q6j@R25w0yb7BNg)RU8?=Hz7EQ+?dj%{mfz3kW)u&AV}i@1H->}E|Lb@GS3$R zuiC1DqC0>Ef_pewclPYFYY&H4o=A`Ww+4yD|+Lv1(v9-o#dwsh(X_SXFMu^ z9eVoA2cVoyD+M4>l|xZ_iu#dOg#bTH#MmzoD@cjjTWFTzPa#`!1SLkEL7zC!{}Kqq zPuq|O;X_StEw|BS&~c*A-UUW*1%sM%2VDfftlIC$OA`u|hY)M!S?&A=Cwylkyr~RY z!r=9Dy%v)U3%}8CUMI)JgHfM@BhPOqM`hZ!yGFylcOM<)9ADX?9$OqIw}znH(@s(; zzCbL;;EMn8+d13R%yGwnTl?fGwN44xWlylgHM6!++QA7!mH}J6Drk4*K5)3WeOPd0 z#b*J0D%_y3ERu1*sSL;@)t8+rkosd%ILD_@>RF*69i)D`&o#d1vRZoT5+*i7aDTCq zZ_)ADtCS2q&XT2bss!;RLM_9{`xX`w+>ZugKm0H9=jd=<zt5S^m$8sVa5eXsW|J9LFGlLrMLamWlZGcBcF5?&t`* zo3P8r)#r9sk=Xx^n1GJYd9Xpq_xkK)PW*LyOX#y-63FLwv%mjP31l+h7kGI_ zhK45ocnSOB_ww<&o*Yjy_}rWMCkcGr{!D5T6XZ_+{2GVm-G_$GI)sZ+^_oc?sGxUi5UFV78Dftys&tf{C@KL{>sgs+SPQ`DWrBus=8Z{k8wD5LxikAn)n;+P|yIq{vh#fSd2DdkMPTiN+w8 zpU2DZt5|<>W_^RUzIOw^uY+0X|x)vqZ(TF$?> zX_7+kbA#O0d4#ZJuWX9UH2cr?CkgVmBL}KmRbZ*q`l_akCzkGkX;UyAl+TL zcyboU$Q)#3tbmyVe`S718KU@>oGJJ3M-up2N4@l2{<;G~cx`A+7xxFrZHA2B*^1ur zlHBN$*y`n92(P}TaDkt67yvyU-YQp^!LI)j%B;Kr$fZZlYT2s8tx1kt5C_V*FRo9@+<( znl-tO1?8pcMY2#d_$#TaT&Lsq!q-cMMX2)yk;(uu3!_d%Z+3P>P=M0t#+h;4*FmC; zwwUBCusnuLxIP$<8KZMHBaY;0;!53$Ff_lImBo4~FlNyqei$DI=pG=1LBrtag75;% zMJUk-tGhTqqG(5Y4lZIWcnv9d6)Go%wDBj1f#s31M6QD1)su)FMUVH=S@}1do$08s zv`Lgvm5TJUp|@e>ryvz*LmZk@oN-lluMGF;19bY zV{`;h(FN-v=U}!>q!dkd_npnOco0NZaij4<;7MbVc@dfvq8lWL0&c1+aCp1K4CgvEp57f` zfcBGwiXpxvX#ed)9W;q&XiN`-mE?Wz)N7@3tZz($#%V|4NZEe)r?ozl=I+f^^P#SN}ADR$RW^KB8> zK(nne@}293$4Aa?o{dj*t2$$+IyVhagq}Eci(?Jq(f{=@81d z3*X5o!PpH4CDC&np1Gw|%v+aDTSx-xpqOQhFA$ZZccoaE6&F%tJ;@VeH>LL#m6aBm z&{7CMJyiE;{`aVVfBuOiviT)%#xv2gQLGRTaWjB!UPDj|&^KUwP2 za_{c^l%Zc!xd3Ddgn%3})f$pAjxkhMZ&j-*RVS!(;p}w6R>H?hi#{^a7=@19fOqgY z#E+oF0i2{x$q@wTBp%~jK>5=Z zT^Hmev$7U!HZQprX#P{4oU<^Ad6}qLylPdn(lL_octy~n`xrMFXQ)+R?dU>uVy!0I zLakkMW1vG4rmcyDz&rQKEhuUvasFnKKxJNCkU#uKhcHc&5+IkTjBXHEXa%OO(i_-` zX^4^O&p|z0wR*ZC=N646n8_k~EBMEQ=0=0UFBx|^IxSm8k=ptIp(X8HD(KImm)KLm zr4s~}n({Z|dY*+;9i-#7^L9fM=g)l)o;0d^!x|?jcr!C6FI4O@zVET(3meMN$$>bg z6Lda2Fcx?!T%OJ#YT5xr>+Y3kfyf<|00WU64U}Ez1Yje0cXnn$a|VlF%`eS`g*uV{ zR0MJP?%+LqyFwyKDWU)EyWqk$@SB zJX1y<@0F0m+Wkr~-I=O%!LKWAeK7sP8$B_gkR`rxp z?NpF)0C?(R@JMi@X4 zkY)ghp*y6dl@gF2dHeMV9;t)1|DNtsfn8Bpf;H=q_2 z5xHU|%TX3pK}Mgd+#=(ZpaJ#|hv(W>xZCL&iURvqU?eugLBLI!lqqq!8C9%8H0Y<% zx$6oDiF|_Th@dbUuai?(OtjCsrw*KIeBkQ#5sG6ov})d$roB13B^Z57(ss2j^+D5@ zx^c{f8LbpcUwg8Nez(#UaK16s0rZZyQZ@hN1KHF>Z0E=fEJ~*SYI`t2($>q7?$to^ z=|tUI{4KBZ)aOZJgffgm97%;N~JTrD}*}b{S&#hx@9e1K$^wSJi zhJB+*{*(g1kCs;!XF|99fQhN3PB^jq)>E?HGGzB-c^XHHp;%1XRMImOzXzbs3w>&J z3lvyM0ULWQtp!?UycU0+g8P0BztjCmAjPP|A^O zv14X7!<*{caV$0a{W{(kW&1RqRE0{+>`vkxelR&w$Z|bxrS=N<(Hk*eeA&Z9Oe!~< zOpGr_`wc4F9N_F%-1u6*Dk}v@^S)v(?`y_4+#*;?cB11iGlII@{IX*qb#~0rOWo`` zBj!OVq5P`*I`0wYHuQ!0ONL68>lr-q$4CYT`y{@&&&VY_G?ImSv4m?8&zxpzp6x7_u$7&3e?Yu?W2%88$Td(+Tun(2I+^Kk=yt(oM|HddCdQR9INR}r zX%bNmTYZpEc-<|exLq1&Dj+46+_&C#nr*n@?c?++r@|$pBq33td_L=kpl)w|UrmFi z614$G2!$@hHDZ2mnxMa6oMm>0e85VfqP!${x@`Iw%Gz*B)>5AD6-`T#aziJUL%2QC zi@6JhEAN2d()G*}PaZ@76BtZua$|099Yw)8p5dT%6+r?Du+68l) zMwI)~d+H^+kQpSNg;=;B0P56rqxqj;xI9P3y6t6FRBaxR4nOtoa|sac@~-YdVX3$- zIyk?@OQ4*1W9#rN&&KQaHNnTqDsXY_hJ^!QR#f)r>)>}EiE>9|kS^T$N=0M9yKT_9 z3A)BO!Ltg!K#Vb5puvFE#1drlq*Vh>>)!8^Cwy+XdvBq|P0Ac3u+iTmpyak1yHs#C z%phmOdPm~)RuFgRqzt8`j2^MRED2o}-1YJ}5I0(CcW|nL1gI#OOEwDX&|$S0$Z&i& zlcvot{^2lVC1DAGq!+PEC~j3d-#E1Bs>9qUn71@$MYCcKw3+$BhzvJ&WjEne6BylR*7E6aF57({a1w-bN@>6J~_Nft=?9{*7gm+E#5X@DWn1N`Clab{dn7lqetd2}K z3MwJLDfx~Ltc6mjuv#m{;6*k1H5x2>6V&X|HMdWUaMC@mitH9S0&j=OcdC>HjFm5n zE?YNEzYAqj4VB|T)6p^TjCvKJuBjr=@A}*KM?O{=UCpO=Rmmzk*aZryu?jI#@->7J zNv~Tt=&ikwhiNk@dvM1&lBCtfPY{a4;qaML!=1u2fo(O1A1q2UAO)$>6wlIizW1)P z*e4~DSdK%s5MIhT9%0%jtD2-pwK|m;uB+~m;R^L7-{WzWt`^pf{o+|O@s0XvVvMgY zOZ%g=^zJuSJm5yTJfzT;v*ZOdk+hffbI`ITGjx=D{5fLg&GWLV_Q3bW6bybRVFjX;@sj;=}IF+%InV&Rp;nR!BvL@Fal@( zU`5dgiqzc}Z)T2wxFYY(s~~B|H!}vP$`+2y?*ebCx)5W{9Vb+G@w4pamuC7KBzasu zHZ(SPo@bODaWD*5cAN!fkm}+J&yVPkirS)+rmb3?ml8U0$rs8J@DFTK(9(P;E!NkA z9?@zumK+8j*M5vZT;%bYg#6$`%sy=M=^k>F=u7rG7QT(om8hfD;wZC66wbr9;BBRC zwFXj436ycXnh0;2BX(X>^^muxKA2=q{Z>k_RNll_CFw^>#m8{&;_~5wdYohsxUtTk z^V15ev>I*(I{t%f&fi3bh&Z_?g0w|-sZ4)RcZ|48GEDM^gJ`r$88B3arEEc-F$({S z2Ff7Qa?LK=D7E>e95_haPftjrO@mp z4^BdSyCapvx4P*^H&B ziTEluH3{jzyah3exQSJ{Mi_DL$`!Wh$E!UE$HFwPw?LtK_SAI8Pl+L za+lg{4C4}$DF~*Wwv6cw&QT5Y#7q)ay|@7${>t7vJv-VF_cEU@Rf&<=I~@l0fxD7&A4Ns9AkwAYT|7F3O9@t?(9BF41wi z91crsyI>SY_%nyn6jDjqacs_@v1XK%f%@V|yDLwvj z&h$Ww(=*>7aNka2)(OPfFGN;K=*HC^GIYvgU|9~5S{htbsPSYjzvELRr1a52D$kT? z=g~f8;sSjrC9CiS^&S|S>t6F%V(hN*z`3Y@yjyUb8(K1p4#)b6YLu?oVIB(IBtt^Q2JiqUjG0@n_uDRcHCoSQ;#W9LFc2IscwR-rZ(2Kl91Ix5=c`3 zv|)wZQh!@Sl$1xEQG8!P=K@j=b_rssB?1P%VC74q8 zrrCBg;J;V+f>*+ouCJe!II`o7B?;eBW`5X7Efn7~r_=lSw3+>eID~?DClATwL&1=a0RD>nUuzD61L|;+q^|I9oc4CR}$vC zBuA$B;&ly;X5N*keg$S7f___N%=u2W+DEliHHv#r|Fe@nr%C-{!x0fT^_Uwz_fybs zgC&c^+#j;$Z6tDH-H)e3!<$lkmQV>u$~6Dz^?idZ)ap28VI#_PY14!ndEf}kobw{~ zcvCm=Da>XYFdLYx1Ie_1%?2@3!brY#n_ z$1MQ9a2RY(CF-@Jk56`S=6gBmsm-?BTGZ3w(9-g@_Gp-pU{UPL=@Ac<5uXhjeCM}2 zUozsiI|3z+gscf!LSO6WX;B8vopTG$pxs;T&nqs9+B+OK0?#@3#JL#eF=lGCJ|k5A ztT`3+K!?5U2t^;|;p-%{aliP)>55_1S5}uwKVHx zGC#Yo*@U*&fM3vMt&$!T_81b6VSpOj*B!IXf;>G)XEG<}@{AtA*Ju`Yy|Tu9y9Bg} z!$98flDhE41{%&i9Q2o@E63t$&(&@CIb@Qjv9dFC1|Y`;#9zQCL=YqpX}hdjnpAZTRLn%|I{BF-*N$9_eUEghqbSu>7*Wi4YOPvFM93sHTkR)8~eK=i?!q#ci|Af0gmsA z9@GomUO*Yh33U7hO7&5Jy*k8(Qdesd*}iLK!j^;K!;%+1;+&xU1226?CB`vpOrZXl(8$4gH^#Df+Q=Fh`6vz?+3xB$v!39Kyg@k0TE}To2=IMd5b$DCnamP{NpVW-6jg;b%21$1 z-*j}$pGHv)JPUiw^$eZU5FiHVEYaT^dk}r4RezyaJz8!9#ryHms&>wxu}Qj9XUrlG zZzgqwo+sSyGMzTc(ZFcTtLBWTYr;Onq%j_2T4$tdDq+uM(%Vo@aL z>RdfF>cV(Vyc{uus6Z-wx$Me4Ka?aL0SN_e&7=>O1nOI(`F?&;wb7Xj(vr852qX6P zjX`XGOh}=>K|@-x5G4K3%n#sG^PQ^19ln@(wdTpOu-4t)nw+z|)Ya)ka*2B7TJ)^& zZ>?P2Om@vOmGYp8--PY~dc43y&>9zjQD(0)n{V;X&vG~8*9{{hNfMh`-Q03Q*OCt+ z>#Ng6WboMt;);tSi7sicqKBbYSPF73tBEe(SC_Kdke!phBC1=?%)}Jb#-2W}I@$Z$ zMPgOhMV)T0uW0g;;KS0y=jrhCZF-K^h>Y39nR>*(Kg5=PvQV5-(Q*a44qdQgs(w49 zHE!>1uKif+H2X|^#8JXLE~LTbJ2{a7h->Fi{Vn|pR5z#0TCsfeO=5}Da*=BU`ItJW zc0&u8ztC-2^l46KnIRHzE52JE}X$Bj;ncrU~Y|5(gsbWrWqi{FOQ#OCzB#qVpS@zQ!SGX`u4lg zQYQ(XYQV0RV-+=9Cm?^wbN8Qp}oHs29Q!=kICG$#<4O6)(y>uDqY-_TO z0UT+Lbp={+iGje<{#{z{l985UmpXa3khtk+MrkCo(%rKDUpGtENp=F;5nX6LV-wyR zEb-ngX}a@LDxT!8%Kv=oc@D}r)sUxE+jYRu<+*cFY)$aNCh_eidn8v6CnU@orjEAqZW!y>N@YB4K)0PJm z;#Ia0S}mQ)?jG@OUWn`7kHI&zzUH9j5O6ZJ;V5%|(Zg(c!xzCB;eAUB{bi+XnIjd4 z+@|!7sF2mc5VinQ1SQU(omc5*#{<)i!k2J`IJv(csEj!**Md*XpSidkoJ$b>;$zus z{b5@uqp|YN3VSUpk3p2^&g`$MtgowH3}5in$HTLU#Y4a>*aMsoqoOV$vyh(lZ_bpu z{#v931K1{!b#yUX8eF>t=WtGYkiFWSU7P6;TlMM1avxz*?)YNX6A|c~bP)A`DTfmp zqFt*u5Z$XL6Y+51r3pZTy*(KqM2>}%M2O8~CkUq_0Lo*QZpUVVOzlbKDK{S4=L)M7 zF09sQ2S^c~2bY|ql(UY31j9v(q`ydqWi)7cnvH6j;nSF$C&3=jTOqtNw#~b&C**$W zqDzzB1D>sEFQm`wq4Jw)P~Y^pFUqOtczLuy3x?2c?e5{ReH~}XNb0VldoJv^UR*?W zIWq>`dg^P+*xbA!P#+A`#9jvf@B_NLJ#{_?u{eLbi_jKi!LJ4VOfdqb&zE}Xoj(>5 zzUh{MN?0pfF79R=!c!A$#(yuy3DW+VwR&fYq>E0>mDEdwP9Jo}0%w{yl&y~`5GNr6 zl!@c4$dt(X8gEh$a7)ZHBupKBPFpr-jc1|hhyO)^_@hGERw`n{y?kLwd6uv=RDz?2 zEKlb;Ka5p>=Ncl&Qv^r;i@SkqUotdSAzjUgJL_tUp*N@9>PQPddptjU!L>Uyd--$!GhUR=sFU-7=Peo~ncO*?t zXtv}QARHOvipjQ0GS*0Nxh-$kp%`l8g4%Co7PMpC#*O?lTVxf!GjIPm(Tm+1K{(Z6 zcMa{tdJE#bN~&;*j9iMl(VpyYjPz(QKxq8Zl;76R7uSxSBETS3t)>&#vM>L01Sn9- z52@7xPwM{iTPw;Vw3a|4P&1c6DO+t@>!B!=HYpw3UNEUh%az9QM-kP)2oa7dlqcZL zL$U|e-k{Y}lrX^Js`(1I<8J1DztL7Ai zC94gyn7pfJ)?#RxB=OWB&!esHu=NcA;>ecXz5|1Lq=G$~SVwnI3khiKa$J$bmvdAV zn$IC(2Qn|3ufIajc^r(zE#6dAv_f2n*qrx}CgyUg7Q0)BD^fKZBdRk`cVTy>xN3N_ zyv;)aO8O-+0~0x*%G~m=Skgc5{$wZ^Z%z#H>G$H4m*5MxDiz46ou-r>pVyI*N!8ot zZY-WyptcD;bS)W4Hd!m%{sGtps3*`(v9hcL9^#~DdM#>PgYwwssZ6cid)$xFf?ifR zBERq`<5}xfvfg!Y5t_BD9tLW9dySDM_vvj9W2-L0Z`;n>6c~PdcF$xfviVJ@mn*uI zp6)zW$|$$FQqLGAM`GtHWqq|C1=As}^F5ig3WfTbUBKLd_WhAsMM!)S>-9`k60|f%5~pw_=uPsKSum1?d#4v~W&^X)6)FbQ{pbu`O`)H-alB>a8xl zI-*`I2BLE6YtOdKYkCvXST8Ozif7@m;u7UH*kDH!*G88T&}_-upu9`=fM|1GCWD+K zksnJh(_$6J%Ds*$Y~3(_OhBAFml`4}+RglFT6LBUpgu`KW5xW&nK_V;A<6@C&(4m z`~nkCR&3qSzZl7zBl!Y(S5S@U?X^yyis|KR(KESj8oj6^@gtA?$gPp z2Xtc2ztn4tI5~&@7xF;9tmKz;y&DI(1U6gbQf$PSV$jkWBkROnk8@!c|r*%yJ_;@Y+LX=`OdtOw#^5G@2RZSOfcX0(w zJX3MrCbW^%kvF6Q%ln!(kyf06bV&2>YFV;Np%NpJ)PCouXY*sBwGyc3_=B5!b-`RE zLVaH)&E6%%Gwv`;S;Wk2D1{)2Fh-?tl^kgrq$07I&f=Qs{7D^)+<_)@r6SwR=(_X5b1xfPSX> zx_q{-s&mX1*u5fPUq;&bsdX^Fb`wbv^ERYi{p9p~IW)1VyhnZFoo23p1(%l*_+5Z~+se1@y02Tamuid@ogO{+lSLj$9JQVo5@ zx;G&h2gWJ?S{_?EI`Cv)?mZIsBJ2zMn9?3hx#vat*>wB8&4yoaOAiIj@VCMD5k2F| zq;X~TipA_>(3oj%d3nOLf^rY{MU49iJ8fAC5>B_(DZvf|MSimzY4>l1)*23iG8`3% zNOW#OTmznckm4-G4UAO#S6H8%Qu8QNZQQ=A4FmBG4PVPZnRZ@cMihI$@wBZ_@Ap0> zeJ?6J6a3W+c8g*~uW*YajafR3XN+N>z4nZT*;zOxjQUmVnBq|AT$zZe;p4No?!ay0 zC*)SoN#w#A#^XSv0Jb^R237OD1jksFz)V5HP+u@8E`2J5o>D8Wu{<-^Y#vkb(<>hC zCg8Hfh$l`CgGOVEpC>}L+q=|;40@ct6~+^3z;l6Vr4s?wLlId&*tloNK3CeiQ6CN6wy4j@YYXwI}hqmm4}l0M~}hfPlrdav{T z95H`x$Y@AXZyKFp8zQ-j;|iMCoSO2g0}|RzYw?Gf_ZnNurl7Rp@6VHJ8J*RzZute2 z;vSVc4m-Q|Wg`>1k<4Xi*JZdWYw7D`(a^``J)gD8YxZ`mOS7Z!w<&+ z{bGw9Y87U?u|3u4-+4o~q)8w(Nz7Q}3V&P5I`*8}+IW7jM9F1vxhm3TomBklPgrnbaE3A4X z4>Hm`v z7tv_-_h@zDU+BVCs0H*Mg=Z<6tbc{nw-l#}zP%r0+gTgo$Ze4;lo-C7o7*2a?(sJg zTdd`1Q*T)HZQrqpYb(qAIv8Bi-jMgRot`6``aLh?7X+`hm|qNPi*kYn42+DAsjMa6 zjW{6HjArnFs|F%Szdp`nQZ)u>3>WG)BK4l79i?zFjO1afvJ)$nf!C}WZ2^u7nur59 z1BvHGyu}{MsV0(xmt7Sz*WaVHAU@yvIyT1BnevEmX_*gR)}d;SrRUFyQ6WkUd$<|- ztWKTuCC6%O#$gFHdhhlDb2!nHOhMn`dq6T6B=1Q=mtLxUkCbK+g7VW*b^^#<-3X5< z-Uc8pLVmRQ2eO=}3ms2SSAVlJIfO*-;TM-J;Q@#SLImFtNNwt%TdLLQEh6?sy1XqO z8`U0fIgjHtdN&>7tSu@!7O0XzKZie++B(^$gGRFzOH&bh2mnJ&3dNcrPO^_%6_>?Vv%f}}m#+#?5ve?IjhE z#%vJEk?cUYS7lq9z!#Rpy4Wretc($%ki>OK~Wee{-tfsRe3Bh^udv3q<@omDQ^=_&KU~-O>mF9uD7wH9cmaP@4 zWoe1eaV^9g4J=Y7`k~GdfUmAT152FRU~RAdC(}^AD41$kEecsTU#zz92=TejD6I)G zxs2E6ysB0m_PrUR3R2)Mebs~Ar!h>H%!Iyz9xk4BnRju4TeuGJkm>0038%0Tz_lmz z4=Y8fC+x*XAhrpogYxDluFU{lroVJ3 zYVnm}@BAPawf1Xh-Qs#x1>($W5LmxPWuCtLuK0--pB~YJYr%R+)@1mK;3Cm{5)vAi zVqcB`O$)rB$@P?qE+m&PL7qfSn(f}zMjA|r6_0V`238YpCu6x)Ir zS4@Y8A~2f)`4~R(%6atQ6YXvB@F;(+o88>BDoWU@qrF}zyp1xN(BA2(YviW_T?KVg zeFkc}TL0@z#ca2lW(Cx3z87p;D@Bf1!5&-;)d!`yal@wO_2T&0)M@uZ2j9UHRRt}! zA{1>(ws1NsW0-~P4CN}Hdp9mSe%5E_5RrJnikO{z%AEpR=|=nJ7`D+z~#3$4-3C43t zCSHZ^~PIV0Z#WLs)2Onb!oVMP6!fsSugP`zX8?nTO6*S z60XX0CcT&oTJKA8zcrxD$aQ^K!x4{l#kP?c3Pw#Ba*UO$SvO4>zFY9SsdGhsgWC$w z{gzhHGJAe`At?a2Hz*yjUgvL(sbgW~*_?f1yAOxjT7vvSOS^i+M@A9~jH&jmoq!hV zXEzw~mfALyPC=c!^vRN3*od6$u^tHCVN_y-j1n@i<5=&V*$K5J#c61u{5CJxY_$o+42m+-ITjlBj0L(`y|dQR z!rD@ha@@F|OID9h)f`}GkR`D;DSjaHOdCvl!=5^^8;YbQ6%_Pk&vuMiEdhKt0U!m| z1r{?DzGY5vMA*7!5|I&Nwo|uann+1)u5{KROY+D`BrKq2v1L1>HyHMel$VeRD`Rld zZ-8j~(rW%>CJo3D#I<6g-=-5=OLM*<&Lr7AIs~XvyrMCA#iOdt#EnR7gn}%|19>x; zsCa#XMC`)23YC-6CT%IE4LrbzV0#PHmDRwDSTb5lu^u{9>NCl;9%HLtaaEsKbeEft z%^`KJ>I&ioXB<&5sH<0-oU7#tcfup$l#{#g)arbm)uo`IfMgTeqP5JSwue>yS@L?J zf1rm)m_(~(ZhIc(8Rszysy(z5Jf-j*#B4BYl_BR<$8mH;`Sn9|dr;HXsk$9V6$chO zpk88zy|)`FnmQ;U;Hpbo27;y;-=gVSbgZQnJJR_m$E7k^ju-uYu1uJ(pSV1|SAx)& zR&heTRpTes`ceWetgu-pMJv@D51^to@Q^ooFVr(fgT>s=F^vjC*9k zO?qXHXYDiO=-$Mz0l5^_>1TOBBrmIpJ?1H%0IBY1h*NG!2`>Te6IftC3 zyS6m|Kd@7l5&7saz;D5F=rm3Fj`(QvHvTZgN3M%Bsoo4e&PXw+17#@-&P_QOh$NhT zs0c&k@NUW%ol|)_a6j}KqSi;8M&JnM%q4b;6rA#!r~3q8ckGN_V?d&`ft*7R*(E6+ z^`Lrke9gt;T55gWCYJ-UYO<|lG$3i(wGOw}i?Mr1kOIsE#4iHABX2CCe{Uo-@x`tcLYjq;1;870yI#P$kiYk>PtwQpI8$|? z%(}dDHn*j?51z7-QVyCZM0}NHDd?o5<@j+<^N@zJ#1lE%I<;nYn8v~g@E$`EO6bm$ zOyGxIMIOo=tH3#;w&G}CcuQg2iuf}v^A3^KwS@AD!dM9LCnP2qUT+Q?`+~yQZiOUy zfNdZ;IQVQi0NgbVzyn%*?`X4vmHf_3X%mU_-f`eD;|uAnzD^`?Ho?m1;%3mIY^IOc z8*HzT(o{+)&`e>Ilkt$3I7`9C#v$j(hq^~*2kn<}8t{cQv{NzNvk@&3y*eI$KLlo@ zybu24bbYY$2~6LqY8|HXC^8XtG!+RrHF2>>==M z6?!}nEfxd^H2w+s`O6#q8i<)J`mlSecATBHFg`T7+!=Vh3w~wPUdg`HGcn7Dy>tcr zyGo|j^Z_mqwti)NXPiDRTkPT2_*xFD+TE{)<*Pr?@gbBrRZ1w??d)liTyZ~J_Ao!S zQR?GTnw(uAr}M&lx44{p-ytqC1!&klEznq#QYW(Nu z<`0ln4A^kD2V0Q&S`65H*S~i=3N{lq4!*z9657o1zUpLQGkvhNT6(xWncujFsR7#q z&u;!a7zh8EJfR%AWrImN18a?Mc7WeeDChQ8KVkPQbppK~qBn}G!N4Hjhq?_A8`zBX z@OFdH43;ukeG6K5d+S8{lZ_I53<~;Fo;9jhJ>Owh{p#N1!KgL+wtvWNzheL9P|PT} zXzStV&(2BoAz1A7!41fCG!dK=?Dq3CI>_vB^l%7;-g{{job#~QcfVM53Vd(py*%iV zGk?B!dEOD^vUP28z3?$-m_JByuU898;qot zgNGraj?v!naDGyE2woO7R=u3*%lbVV7a?=QZHh$bABra z=>M@sZO||9rfH|+&O4;@R$|#S5LSY8{#pc9(DNohz+ABUWE7BIJpv@OIA?mei>uun zn7&CFF26i5YrFsgZ99RTcfk%@E@2XkCrtFD4ht)J`_>^Oib9naOmeZub9vu{lUD}5vi>9-wrFa42xb_!B`Q+qy73O4}^sg$*8h{UQMfR64M)E`;)4g7Z`TtF!Q~cFhUV}MAC-?gB|FZ-r z|Jp+%|Cd9Zb(ljtDzL{oK!i*v-8;nzHvB2rq>%pIm;c?HkJRA7b$}dz^A*^113(I9 z-2kux1Zf_DCV-yyNjSU#pd@=3BKUBp4+ke<1qVm)FB?xARyy#rO#lNK?11@J!#uPj z!@&{%hZj>|QV1-GlG!GJ6CfQ5YmH-)3m^qZj{#S10bY|qds-;6U%=Q!@Nks>;Y%qt={;<(2)1GN>2i~Zb11;( zkL}pJq<4^);Ht+qOMVhnE;kr!2iD%tPpT=#2dnJ>cmVCCur?LA=uwVY4yN9Pm1{fN z0k8ouD<6RhAhq^!OAe0R1+W7;nv*^^z5<_b0&tRSzu;gz4&y0CLRw)x^h9smf*;)V@^tzcO>0|H>BApc|U-IxDr0T)rgh6gY$+{3?Gc?U2L-e-UNC{Izq zR|l{d9}U5UXL=3?Hy-j&D?vAZwZwnJe1&e{|L#VDB@yTNCu0QL3LXKP!4o)r1Zzf5z{LpWUhxDrxhHt z{!0aL!jcGI0r1Hn%i+^Hr@qiP4!IlblZ``9X?zkHh?L=Y$piVsbq(*@1Y>F|Y_jiTUTQr&RxC zB0OGJ{?5E0L!Iz195}eK*nd*ZJ07Xz04}b-OmONcECSz+{uP2pPhk=6HSq{k0B@jA zLYFg`(0=9#v^@fY`A0woMmvXnDb1FifWaf^*?R&dkD%iYe0&9?T|NTn!xJFSfJXtV zT)={F7XUuK1CW5(v*1y|nU4|#pMcyA z?3#W!KbWcW3=U3E^PdxHCiItv#KFTM@D%r8^BdTlo=QEbr#`AvXCR_=!mbUj^Z!&o zQu|+Z&i_3m)sO1Gjh@su9@S%F_Z#M6mzTHybqZ54f1+{U!f1bs)Wbq)ll-4v>}>wh z5IJ~w{uNCBE}Q*NE{VfmE&_}T<~RiqApNb`3(ma--~;BI|J_G@1v_j0yEZ5s9MylE z$RX}eBZE~7eFkQ{gB@NH(4&M5>~RN+p{mFy(D?|CKRg0uz*x+a(C8j!`u~bQz~=2g zO)r9;nDv1Bj69eILE-Vc-N(v>6?%2i3Up`M5O%hY#jhNqW?H>$5aS#Zya2_oE==9*nAvZt=)XyD7f0XJ(g)! ZS3-i_8^OVSfc?E>hJ(X4goPX2{{V`|#N7Y@ diff --git a/simscape-micro-station.org b/simscape-micro-station.org index 6f4258f..e293b7b 100644 --- a/simscape-micro-station.org +++ b/simscape-micro-station.org @@ -43,15 +43,9 @@ #+PROPERTY: header-args:latex+ :mkdirp yes #+PROPERTY: header-args:latex+ :output-dir figs #+PROPERTY: header-args:latex+ :post pdf2svg(file=*this*, ext="png") -:END: - -#+begin_export html -


-

This report is also available as a pdf.

-
-#+end_export #+latex: \clearpage +:END: * Build :noexport: #+NAME: startblock @@ -112,13 +106,17 @@ From modal analysis: validation of the multi-body model. *Notes*: - Do not talk about Nano-Hexapod yet - Do not talk about external metrology +- Therefore, do not talk about computation of the sample position / error Based on: -- [ ] [[file:~/Cloud/work-projects/ID31-NASS/matlab/nass-simscape/org/kinematics.org][kinematics]] -- [ ] [[file:~/Cloud/work-projects/ID31-NASS/matlab/nass-simscape/org/simscape_subsystems.org][simscape_subsystems]]: general presentation of the micro-station. Used model: solid body + joints. Presentation of each stage. -- [ ] [[file:~/Cloud/work-projects/ID31-NASS/documents/work-package-1/work-package-1.org::*Specification of requirements][Specification of requirements]] -- [ ] [[file:~/Cloud/work-projects/ID31-NASS/matlab/nass-simscape/org/identification.org][identification]]: comparison of measurements and simscape model (not so good?) +- [X] [[file:~/Cloud/work-projects/ID31-NASS/matlab/nass-simscape/org/kinematics.org][kinematics]]: compute sample's motion from each stage motion +- [X] [[file:~/Cloud/work-projects/ID31-NASS/matlab/nass-simscape/org/simscape_subsystems.org][simscape_subsystems]]: general presentation of the micro-station. Used model: solid body + joints. Presentation of each stage. +- [X] [[file:~/Cloud/work-projects/ID31-NASS/documents/work-package-1/work-package-1.org::*Specification of requirements][Specification of requirements]] +- [X] [[file:~/Cloud/work-projects/ID31-NASS/matlab/nass-simscape/org/identification.org][identification]]: comparison of measurements and simscape model (not so good?) +- [ ] file:/home/thomas/Cloud/meetings/esrf-meetings/2018-04-24-Simscape-Model/2018-04-24-Simscape-Model.pdf - [ ] [[file:~/Cloud/work-projects/ID31-NASS/matlab/nass-simscape/org/experiments.org][experiments]]: simulation of experiments with the Simscape model +- [ ] Disturbances: Similar to what was done for the uniaxial model (the same?) + - [[file:~/Cloud/work-projects/ID31-NASS/matlab/nass-simscape/org/disturbances.org::+TITLE: Identification of the disturbances]] - [ ] Measurement of disturbances / things that will have to be corrected using the NASS: - [ ] [[file:~/Cloud/work-projects/ID31-NASS/matlab/nass-measurements/static-to-dynamic/index.org]] - [ ] [[file:~/Cloud/work-projects/ID31-NASS/matlab/nass-measurements/disturbance-control-system/index.org]] @@ -168,7 +166,14 @@ initializeController( 'type', 'open-loop'); ** TODO [#B] Make good "init" for the Simscape model -** TODO [#C] Verify that we get "correct" compliance +** TODO [#A] Verify that we get "correct" compliance +SCHEDULED: <2024-10-30 Wed> + +** TODO [#B] Just keep smallest number of variants for each stage + +- [ ] rigid +- [ ] flexible +- [X] Init => Removed * Introduction :ignore: @@ -224,11 +229,444 @@ initializeController( 'type', 'open-loop'); <> #+end_src -** Granite -** Translation Stage -** Tilt Stage -** Spindle -** Micro-Hexapod +** Motion Stages +*** Translation Stage +*** Tilt Stage +*** Spindle +*** Micro-Hexapod +** Specification for each stage + <> + +For each stage, after a quick presentation, the specifications (stroke, precision, ...) of the stage, the metrology used with that stage and the parasitic motions associated to it are given. + +*** Translation along Y +**** Presentation +This is the first stage, it is fixed directly on the granite. +In order to minimize the parasitic motions, two cylinders are used to guide the stage. +The motor used to drive the stage is one linear motor. +The 3D model of this translation stage is shown figure ref:fig:stage_translation. + +#+name: fig:stage_translation +#+caption: Translation stage +[[./figures/stages/stage_translation.pdf]] + +**** Specifications +#+attr_latex: :align |c|c|c|c|c| :placement [!htpb] +#+CAPTION: Specifications for the translation stage along Y +#+NAME: fig:spec-t-y +|--------+------------------------+--------------------------+--------------+--------------| +| Motion | Mode | Stroke | Repetability | MIM[fn:3] | +|--------+------------------------+--------------------------+--------------+--------------| +| $T_y$ | P[fn:1]/S[fn:2] | $\pm5 mm$ | $0.04 \mu m$ | $0.02 \mu m$ | +| | rotation stage along Y | ($\pm10 mm$ if possible) | | | +|--------+------------------------+--------------------------+--------------+--------------| + +**** Metrology +A linear digital encoder is used to measure the displacement of the translation stage along the y axis. + +**** Parasitic motions +#+attr_latex: :align |c|c|c| :placement [!htpb] +#+CAPTION: Parasitic motions for the translation stage along Y +#+NAME: fig:parasitic-motions-t-y +|--------------------+-----------------------+------------------------------| +| Axial Motion ($y$) | Radial Motion ($y-z$) | Rotation motion ($\theta-z$) | +|--------------------+-----------------------+------------------------------| +| $10nm$ | $20nm$ | $< 1.7 \mu rad$ | +|--------------------+-----------------------+------------------------------| + +*** Rotation around Y +**** Presentation +This stage is mainly use for the reflectivity experiment. This permit to make the sample rotates around the y axis. +The rotation axis should be parallel to the y-axis and cross the X-ray. + +As it is located below the Spindle, it make the axis of rotation of the spindle to also tilt with respect to the X-ray. + +4 joints are used in order to pre-stress the system. + +The model of the stage is shown figure ref:fig:stage_tilt. + +#+name: fig:stage_tilt +#+caption: Tilt Stage +[[./figures/stages/stage_tilt.pdf]] + +**** Specifications +#+attr_latex: :align |c|c|c|c|c| :placement [!htpb] +#+CAPTION: Specifications for the rotation stage along Y +#+NAME: fig:spec-r-y +|------------+------+----------------------+--------------+-------------| +| Motion | Mode | Stroke | Repetability | MIM | +|------------+------+----------------------+--------------+-------------| +| $\theta_y$ | S | $\pm51 mrad$ | $5 \mu rad$ | $2 \mu rad$ | +| | | Speed: $\pm 3^o/min$ | | | +|------------+------+----------------------+--------------+-------------| + +**** Metrology +Two linear digital encoders are used (one on each side). + +**** Parasitic motions +#+attr_latex: :align |c|c|c| :placement [!htpb] +#+CAPTION: Parasitic motions for the rotation stage along Y +#+NAME: fig:parasitic-motions-r-y +|-------------------+--------------------+---------------| +| Axial Error ($y$) | Radial Error ($z$) | Tilt error () | +|-------------------+--------------------+---------------| +| $0.5\mu m$ | $10nm$ | $1.5 \mu rad$ | +|-------------------+--------------------+---------------| + +*** Spindle +**** Presentation +The Spindle consist of one stator (attached to the tilt stage) and one rotor. + +The rotor is separated from the stator thanks to an air bearing. + +The spindle is represented figure ref:fig:stage_spindle. + +It has been developed by Lab-Leuven[fn:5]. + +#+name: fig:stage_spindle +#+caption: Spindle +[[./figures/stages/stage_spindle.pdf]] + +**** Specifications +#+attr_latex: :align |c|c|c|c|c| :placement [!htpb] +#+CAPTION: Specifications for the Spindle +#+NAME: fig:spec-r-y +|------------+------+----------------------+--------------+-------------| +| Motion | Mode | Stroke | Repetability | MIM | +|------------+------+----------------------+--------------+-------------| +| $\theta_z$ | S | $\pm51 mrad$ | $5 \mu rad$ | $2 \mu rad$ | +| | | Speed: $\pm 3^o/min$ | | | +|------------+------+----------------------+--------------+-------------| + +**** Metrology +There is an incremental rotation encoder. + +**** Parasitic motions +#+attr_latex: :align |c|c| :placement [!htpb] +#+CAPTION: Parasitic motions for the Spindle +#+NAME: fig:parasitic-motions-r-z +|------------------------+----------------------| +| Radial Error ($x$-$y$) | Vertical Error ($z$) | +|------------------------+----------------------| +| $0.33\mu m$ | $0.07\mu m$ | +|------------------------+----------------------| + +More complete measurements have been conducted at the PEL[fn:7]. + +*** Long Stroke Hexapod +**** Presentation +The long stroke hexapod consists of 6 legs, each composed of: +- one linear actuators +- one limit switch +- one absolute linear encoder +- one ball joint at each side, one is fixed on the fixed platform, the other on the mobile platform + +This long stroke hexapod has been developed by Symetrie[fn:4] and is shown figure ref:fig:stage_hexapod. + +#+name: fig:stage_hexapod +#+caption: Hexapod Symetrie +[[./figures/stages/stage_hexapod.pdf]] + +**** Specifications +#+attr_latex: :align |c|c|c|c|c| :placement [!htpb] +#+CAPTION: Specifications for the long stroke hexapod +#+NAME: fig:spec-hexa +|------------------+--------------+----------------+--------------+---------------| +| Motion | Stroke | Repetability | MIM | Stiffness | +|------------------+--------------+----------------+--------------+---------------| +| $T_{\mu_x}$ | $\pm10mm$ | $\pm1\mu m$ | $0.5\mu m$ | $>12N/\mu m$ | +| $T_{\mu_y}$ | $\pm10mm$ | $\pm1\mu m$ | $0.5\mu m$ | $>12N/\mu m$ | +| $T_{\mu_z}$ | $\pm10mm$ | $\pm1\mu m$ | $0.5\mu m$ | $>135N/\mu m$ | +| $\theta_{\mu_x}$ | $\pm3 deg$ | $\pm5 \mu rad$ | $2.5\mu rad$ | | +| $\theta_{\mu_y}$ | $\pm3 deg$ | $\pm5 \mu rad$ | $2.5\mu rad$ | | +| $\theta_{\mu_z}$ | $\pm0.5 deg$ | $\pm5 \mu rad$ | $2.5\mu rad$ | | +|------------------+--------------+----------------+--------------+---------------| + +**** Metrology +The metrology consist of one absolute linear encoder in each leg. + +**** Parasitic motions +#+attr_latex: :align |c|c|c| :placement [!htpb] +#+CAPTION: Parasitic motions for the Spindle +#+NAME: fig:parasitic-motions-r-z +|------------------+--------------+----------------| +| Movement | Resolution | Repeatability | +|------------------+--------------+----------------| +| $T_{\mu_x}$ | $0.5\mu m$ | $\pm 1\mu m$ | +| $T_{\mu_y}$ | $0.5\mu m$ | $\pm 1\mu m$ | +| $T_{\mu_z}$ | $0.1\mu m$ | $\pm 1\mu m$ | +| $\theta_{\mu_x}$ | $2.5\mu rad$ | $\pm 4\mu rad$ | +| $\theta_{\mu_y}$ | $2.5\mu rad$ | $\pm 4\mu rad$ | +|------------------+--------------+----------------| +*** Short Stroke Hexapod +**** Presentation +This last stage is located just below the sample to study. +This is the only stage that is not yet build nor designed. + +**** Specifications +#+attr_latex: :align |c|c|c|c|c| :placement [!htpb] +#+CAPTION: Specifications for the nano-stage +#+NAME: fig:spec-nano +|------------------+----------------+--------------+-------| +| Motion | Stroke | Repetability | MIM | +|------------------+----------------+--------------+-------| +| $T_{\nu_x}$ | $\pm10\mu m$ | $10nm$ | $3nm$ | +| $T_{\nu_y}$ | $\pm10\mu m$ | $10nm$ | $3nm$ | +| $T_{\nu_z}$ | $\pm10\mu m$ | $10nm$ | $3nm$ | +| $\theta_{\nu_x}$ | $\pm10\mu rad$ | $1.7\mu rad$ | | +| $\theta_{\nu_y}$ | $\pm10\mu rad$ | $1.7\mu rad$ | | +| $\theta_{\nu_z}$ | $\pm10\mu rad$ | | | +|------------------+----------------+--------------+-------| + +**** Dimensions +- Bottom plate : + - Inner diameter: $>150mm$ + - External diameter: $<305mm$ +- Top plate + - External diameter: $<300mm$ +- Height: $90mm$ +- Location of the rotation point: Centered, at $175mm$ above the top platform + +** Compute sample's motion from stage motion +*** Introduction :ignore: +#+begin_quote +Rx = [1 0 0; + 0 cos(t) -sin(t); + 0 sin(t) cos(t)]; + +Ry = [ cos(t) 0 sin(t); + 0 1 0; + -sin(t) 0 cos(t)]; + +Rz = [cos(t) -sin(t) 0; + sin(t) cos(t) 0; + 0 0 1]; +#+end_quote + +Let's define the following frames: +- $\{W\}$ the frame that is *fixed to the granite* and its origin at the theoretical meeting point between the X-ray and the spindle axis. +- $\{S\}$ the frame *attached to the sample* (in reality attached to the top platform of the nano-hexapod) with its origin at 175mm above the top platform of the nano-hexapod. + Its origin is $O_S$. +- $\{T\}$ the theoretical wanted frame that correspond to the wanted pose of the frame $\{S\}$. + $\{T\}$ is computed from the wanted position of each stage. It is thus theoretical and does not correspond to a real position. + The origin of $T$ is $O_T$ and is the wanted position of the sample. + +Thus: +- the *measurement* of the position of the sample corresponds to ${}^W O_S = \begin{bmatrix} {}^WP_{x,m} & {}^WP_{y,m} & {}^WP_{z,m} \end{bmatrix}^T$ in translation and to $\theta_m {}^W\bm{s}_m = \theta_m \cdot \begin{bmatrix} {}^Ws_{x,m} & {}^Ws_{y,m} & {}^Ws_{z,m} \end{bmatrix}^T$ in rotations +- the *wanted position* of the sample expressed w.r.t. the granite is ${}^W O_T = \begin{bmatrix} {}^WP_{x,r} & {}^WP_{y,r} & {}^WP_{z,r} \end{bmatrix}^T$ in translation and to $\theta_r {}^W\bm{s}_r = \theta_r \cdot \begin{bmatrix} {}^Ws_{x,r} & {}^Ws_{y,r} & {}^Ws_{z,r} \end{bmatrix}^T$ in rotations + +*** Wanted Position of the Sample with respect to the Granite +Let's define the wanted position of each stage. +#+begin_src matlab + Ty = 0; % [m] + Ry = 3*pi/180; % [rad] + Rz = 180*pi/180; % [rad] + + % Hexapod (first consider only translations) + Thx = 0; % [m] + Thy = 0; % [m] + Thz = 0; % [m] +#+end_src + +Now, we compute the corresponding wanted translation and rotation of the sample with respect to the granite frame $\{W\}$. +This corresponds to ${}^WO_T$ and $\theta_m {}^Ws_m$. + +To do so, we have to define the homogeneous transformation for each stage. +#+begin_src matlab + % Translation Stage + Rty = [1 0 0 0; + 0 1 0 Ty; + 0 0 1 0; + 0 0 0 1]; + + % Tilt Stage - Pure rotating aligned with Ob + Rry = [ cos(Ry) 0 sin(Ry) 0; + 0 1 0 0; + -sin(Ry) 0 cos(Ry) 0; + 0 0 0 1]; + + % Spindle - Rotation along the Z axis + Rrz = [cos(Rz) -sin(Rz) 0 0 ; + sin(Rz) cos(Rz) 0 0 ; + 0 0 1 0 ; + 0 0 0 1 ]; + + % Micro-Hexapod (only rotations first) + Rh = [1 0 0 Thx ; + 0 1 0 Thy ; + 0 0 1 Thz ; + 0 0 0 1 ]; +#+end_src + +We combine the individual homogeneous transformations into one homogeneous transformation for all the station. +#+begin_src matlab + Ttot = Rty*Rry*Rrz*Rh; +#+end_src + +Using this homogeneous transformation, we can compute the wanted position and orientation of the sample with respect to the granite. + +Translation. +#+begin_src matlab + WOr = Ttot*[0;0;0;1]; + WOr = WOr(1:3); +#+end_src + +Rotation. +#+begin_src matlab + thetar = acos((trace(Ttot(1:3, 1:3))-1)/2) + if thetar == 0 + WSr = [0; 0; 0]; + else + [V, D] = eig(Ttot(1:3, 1:3)); + WSr = thetar*V(:, abs(diag(D) - 1) < eps(1)); + end +#+end_src + +#+begin_src matlab + WPr = [WOr ; WSr]; +#+end_src + +*** Measured Position of the Sample with respect to the Granite +The measurement of the position of the sample using the metrology system gives the position and orientation of the sample with respect to the granite. +#+begin_src matlab + % Measurements: Xm, Ym, Zm, Rx, Ry, Rz + Dxm = 0; % [m] + Dym = 0; % [m] + Dzm = 0; % [m] + + Rxm = 0*pi/180; % [rad] + Rym = 0*pi/180; % [rad] + Rzm = 180*pi/180; % [rad] +#+end_src + +Let's compute the corresponding orientation using screw axis. +#+begin_src matlab + Trxm = [1 0 0; + 0 cos(Rxm) -sin(Rxm); + 0 sin(Rxm) cos(Rxm)]; + Trym = [ cos(Rym) 0 sin(Rym); + 0 1 0; + -sin(Rym) 0 cos(Rym)]; + Trzm = [cos(Rzm) -sin(Rzm) 0; + sin(Rzm) cos(Rzm) 0; + 0 0 1]; + + STw = [[ Trym*Trxm*Trzm , [Dxm; Dym; Dzm]]; 0 0 0 1]; +#+end_src + +We then obtain the orientation measurement in the form of screw coordinate $\theta_m ({}^Ws_{x,m},\ {}^Ws_{y,m},\ {}^Ws_{z,m})^T$ where: +- $\theta_m = \cos^{-1} \frac{\text{Tr}(R) - 1}{2}$ +- ${}^W\bm{s}_m$ is the eigen vector of the rotation matrix $R$ corresponding to the eigen value $\lambda = 1$ + +#+begin_src matlab + thetam = acos((trace(STw(1:3, 1:3))-1)/2); % [rad] + if thetam == 0 + WSm = [0; 0; 0]; + else + [V, D] = eig(STw(1:3, 1:3)); + WSm = thetam*V(:, abs(diag(D) - 1) < eps(1)); + end +#+end_src + +#+begin_src matlab + WPm = [Dxm ; Dym ; Dzm ; WSm]; +#+end_src + +*** Positioning Error with respect to the Granite +The wanted position expressed with respect to the granite is ${}^WO_T$ and the measured position with respect to the granite is ${}^WO_S$, thus the *position error* expressed in $\{W\}$ is +\[ {}^W E = {}^W O_T - {}^W O_S \] +The same is true for rotations: +\[ \theta_\epsilon {}^W\bm{s}_\epsilon = \theta_r {}^W\bm{s}_r - \theta_m {}^W\bm{s}_m \] + +#+begin_src matlab + WPe = WPr - WPm; +#+end_src + +#+begin_quote +Now we want to express this error in a frame attached to the *base of the nano-hexapod* with its origin at the same point where the Jacobian of the nano-hexapod is computed (175mm above the top platform + 90mm of total height of the nano-hexapod). + +Or maybe should we want to express this error with respect to the *top platform of the nano-hexapod*? +We are measuring the position of the top-platform, and we don't know exactly the position of the bottom platform. +We could compute the position of the bottom platform in two ways: +- from the encoders of each stage +- from the measurement of the nano-hexapod top platform + the internal metrology in the nano-hexapod (capacitive sensors e.g) + +A third option is to say that the maximum stroke of the nano-hexapod is so small that the error should no change to much by the change of base. +#+end_quote + +*** Position Error Expressed in the Nano-Hexapod Frame +We now want the position error to be expressed in $\{S\}$ (the frame attach to the sample) for control: +\[ {}^S E = {}^S T_W \cdot {}^W E \] + +Thus we need to compute the homogeneous transformation ${}^ST_W$. +Fortunately, this homogeneous transformation can be computed from the measurement of the sample position and orientation with respect to the granite. +#+begin_src matlab + Trxm = [1 0 0; + 0 cos(Rxm) -sin(Rxm); + 0 sin(Rxm) cos(Rxm)]; + Trym = [ cos(Rym) 0 sin(Rym); + 0 1 0; + -sin(Rym) 0 cos(Rym)]; + Trzm = [cos(Rzm) -sin(Rzm) 0; + sin(Rzm) cos(Rzm) 0; + 0 0 1]; + + STw = [[ Trym*Trxm*Trzm , [Dxm; Dym; Dzm]]; 0 0 0 1]; +#+end_src + +Translation Error. +#+begin_src matlab + SEm = STw * [WPe(1:3); 0]; + SEm = SEm(1:3); +#+end_src + +Rotation Error. +#+begin_src matlab + SEr = STw * [WPe(4:6); 0]; + SEr = SEr(1:3); +#+end_src + +#+begin_src matlab + Etot = [SEm ; SEr] +#+end_src +*** Another try +Let's denote: +- $\{W\}$ the initial fixed frame +- $\{R\}$ the reference frame corresponding to the wanted pose of the sample +- $\{M\}$ the frame corresponding to the measured pose of the sample + +We have then computed: +- ${}^WT_R$ +- ${}^WT_M$ + +We have: +\begin{align} + {}^MT_R &= {}^MT_W {}^WT_R \\ + &= {}^WT_M^t {}^WT_R +\end{align} + +#+begin_src matlab + MTr = STw'*Ttot; +#+end_src + +Position error: +#+begin_src matlab + MTr(1:3, 1:4)*[0; 0; 0; 1] +#+end_src + +Orientation error: +#+begin_src matlab + MTr(1:3, 1:3) +#+end_src + +*** Verification +How can we verify that the computation is correct? +Options: +- Test with simscape multi-body + - Impose motion on each stage + - Measure the position error w.r.t. the NASS + - Compare with the computation + * Stage Modeling :PROPERTIES: :HEADER-ARGS:matlab+: :tangle matlab/.m @@ -249,6 +687,10 @@ Finally, this should help to tune the parameters of the model such that the dyna # - Compare model and measurement ** Matlab Init :noexport:ignore: +#+begin_src matlab +%% .m +#+end_src + #+begin_src matlab :tangle no :exports none :results silent :noweb yes :var current_dir=(file-name-directory buffer-file-name) <> #+end_src @@ -265,11 +707,16 @@ Finally, this should help to tune the parameters of the model such that the dyna <> #+end_src +#+begin_src matlab :noweb yes +<> +#+end_src + #+begin_src matlab :noweb yes <> #+end_src ** Some notes about the Simscape Model + The Simscape Model of the micro-station consists of several solid bodies: - Bottom Granite - Top Granite @@ -285,257 +732,109 @@ Then, the solid bodies are connected with springs and dampers. Some of the springs and dampers values can be estimated from the joints/stages specifications, however, we here prefer to tune these values based on the measurements. ** Compare with measurements at the CoM of each element -*** Matlab Init :noexport:ignore: -#+begin_src matlab :tangle no :exports none :results silent :noweb yes :var current_dir=(file-name-directory buffer-file-name) - <> -#+end_src - -#+begin_src matlab :exports none :results silent :noweb yes - <> -#+end_src - -#+begin_src matlab :tangle no - simulinkproject('../'); -#+end_src - -*** Prepare the Simulation -We load the configuration. #+begin_src matlab - load('mat/conf_simulink.mat'); +%% We load the configuration. +load('conf_simulink.mat'); + +% We set a small =StopTime=. +set_param(conf_simulink, 'StopTime', '0.5'); + +%% We initialize all the stages. +initializeGround( 'type', 'rigid'); +initializeGranite( 'type', 'modal-analysis'); +initializeTy( 'type', 'modal-analysis'); +initializeRy( 'type', 'modal-analysis'); +initializeRz( 'type', 'modal-analysis'); +initializeMicroHexapod('type', 'modal-analysis'); + +initializeLoggingConfiguration('log', 'none'); + +initializeReferences(); +initializeDisturbances('enable', false); #+end_src -We set a small =StopTime=. -#+begin_src matlab - set_param(conf_simulink, 'StopTime', '0.5'); -#+end_src - -We initialize all the stages. -#+begin_src matlab - initializeGround( 'type', 'rigid'); - initializeGranite( 'type', 'modal-analysis'); - initializeTy( 'type', 'modal-analysis'); - initializeRy( 'type', 'modal-analysis'); - initializeRz( 'type', 'modal-analysis'); - initializeMicroHexapod('type', 'modal-analysis'); - initializeAxisc( 'type', 'flexible'); - - initializeMirror( 'type', 'none'); - initializeNanoHexapod( 'type', 'none'); - initializeSample( 'type', 'none'); - - initializeController( 'type', 'open-loop'); - - initializeLoggingConfiguration('log', 'none'); - - initializeReferences(); - initializeDisturbances('enable', false); -#+end_src - -*** Estimate the position of the CoM of each solid and compare with the one took for the Measurement Analysis -Thanks to the [[https://fr.mathworks.com/help/physmod/sm/ref/inertiasensor.html][Inertia Sensor]] simscape block, it is possible to estimate the position of the Center of Mass of a solid body with respect to a defined frame. - -#+begin_src matlab - sim('nass_model') -#+end_src - -The results are shown in the table [[tab:com_simscape]]. - -#+begin_src matlab :exports results :results value table replace :tangle no :post addhdr(*this*) - stages_com = 1e3*[granite_bot_com.Data(end, :) ; - granite_top_com.Data(end, :) ; - ty_com.Data(end, :) ; - ry_com.Data(end, :) ; - rz_com.Data(end, :) ; - hexa_com.Data(end, :) ]'; - - data2orgtable(stages_com, {'X [mm]', 'Y [mm]', 'Z [mm]'}, {'granite bot', 'granite top', 'ty', 'ry', 'rz', 'hexa'}, ' %.1f '); -#+end_src - -#+name: tab:com_simscape -#+caption: Center of Mass of each solid body as defined in Simscape -#+RESULTS: -| | granite bot | granite top | ty | ry | rz | hexa | -|--------+-------------+-------------+--------+--------+--------+--------| -| X [mm] | 52.4 | 51.7 | 0.9 | -0.1 | 0.0 | -0.0 | -| Y [mm] | 190.4 | 263.2 | 0.7 | 5.2 | -0.0 | 0.1 | -| Z [mm] | -1200.0 | -777.1 | -598.9 | -627.7 | -643.2 | -317.1 | - -We can compare the obtained center of mass (table [[tab:com_simscape]]) with the one used for the Modal Analysis shown in table [[tab:com_solidworks]]. - -#+name: tab:com_solidworks -#+caption: Estimated Center of Mass of each solid body using Solidworks -| | granite bot | granite top | ty | ry | rz | hexa | -|--------+-------------+-------------+------+------+------+------| -| X [mm] | 45 | 52 | 0 | 0 | 0 | -4 | -| Y [mm] | 144 | 258 | 14 | -5 | 0 | 6 | -| Z [mm] | -1251 | -778 | -600 | -628 | -580 | -319 | - -The results are quite similar. -The differences can be explained by some differences in the chosen density of the materials or by the fact that not exactly all the same elements have been chosen for each stage. - -For instance, on simscape, the fixed part of the translation stage counts for the top granite solid body. -However, in SolidWorks, this has probably not be included with the top granite. - -*** Create a frame at the CoM of each solid body -Now we use one =inertiasensor= block connected on each solid body that measured the center of mass of this solid with respect to the same connected frame. - -We do that in order to position an accelerometer on the Simscape model at this particular point. - -#+begin_src matlab - open('identification/matlab/sim_micro_station_com_estimation.slx') -#+end_src - -#+begin_src matlab - sim('sim_micro_station_com_estimation') -#+end_src - -#+begin_src matlab :exports results :results value table replace :tangle no :post addhdr(*this*) - stages_com = 1e3*[granite_bot_com.Data(end, :) ; - granite_top_com.Data(end, :) ; - ty_com.Data(end, :) ; - ry_com.Data(end, :) ; - rz_com.Data(end, :) ; - hexa_com.Data(end, :) ]'; - - data2orgtable(stages_com, {'X [mm]', 'Y [mm]', 'Z [mm]'}, {'granite bot', 'granite top', 'ty', 'ry', 'rz', 'hexa'}, ' %.1f '); -#+end_src - -#+RESULTS: -| | granite bot | granite top | ty | ry | rz | hexa | -|--------+-------------+-------------+-------+--------+-------+-------| -| X [mm] | 0.0 | 51.7 | 0.9 | -0.1 | 0.0 | -0.0 | -| Y [mm] | 0.0 | 753.2 | 0.7 | 5.2 | -0.0 | 0.1 | -| Z [mm] | -250.0 | 22.9 | -17.1 | -146.5 | -23.2 | -47.1 | - -We now same this for further use: -#+begin_src matlab - granite_bot_com = granite_bot_com.Data(end, :)'; - granite_top_com = granite_top_com.Data(end, :)'; - ty_com = ty_com.Data(end, :)'; - ry_com = ry_com.Data(end, :)'; - rz_com = rz_com.Data(end, :)'; - hexa_com = hexa_com.Data(end, :)'; - - save('./mat/solids_com.mat', 'granite_bot_com', 'granite_top_com', 'ty_com', 'ry_com', 'rz_com', 'hexa_com'); -#+end_src - -Then, we use the obtained results to add a =rigidTransform= block in order to create a new frame at the center of mass of each solid body. - -*** Identification of the dynamics of the Simscape Model We now use a new Simscape Model where 6DoF inertial sensors are located at the Center of Mass of each solid body. -#+begin_src matlab - % load('mat/solids_com.mat', 'granite_bot_com', 'granite_top_com', 'ty_com', 'ry_com', 'rz_com', 'hexa_com'); -#+end_src - -#+begin_src matlab - open('nass_model.slx') -#+end_src - We use the =linearize= function in order to estimate the dynamics from forces applied on the Translation stage at the same position used for the real modal analysis to the inertial sensors. #+begin_src matlab - %% Options for Linearized - options = linearizeOptions; - options.SampleTime = 0; +%% Identification +% Input/Output definition +clear io; io_i = 1; +io(io_i) = linio([mdl, '/Micro-Station/Translation Stage/Modal Analysis/F_hammer'], 1, 'openinput'); io_i = io_i + 1; +io(io_i) = linio([mdl, '/Micro-Station/Granite/Modal Analysis/accelerometer'], 1, 'openoutput'); io_i = io_i + 1; +io(io_i) = linio([mdl, '/Micro-Station/Translation Stage/Modal Analysis/accelerometer'], 1, 'openoutput'); io_i = io_i + 1; +io(io_i) = linio([mdl, '/Micro-Station/Tilt Stage/Modal Analysis/accelerometer'], 1, 'openoutput'); io_i = io_i + 1; +io(io_i) = linio([mdl, '/Micro-Station/Spindle/Modal Analysis/accelerometer'], 1, 'openoutput'); io_i = io_i + 1; +io(io_i) = linio([mdl, '/Micro-Station/Micro Hexapod/Modal Analysis/accelerometer'], 1, 'openoutput'); io_i = io_i + 1; - %% Name of the Simulink File - mdl = 'nass_model'; +% Run the linearization +G_ms = linearize(mdl, io, 0); - %% Input/Output definition - clear io; io_i = 1; - io(io_i) = linio([mdl, '/Micro-Station/Translation Stage/Modal Analysis/F_hammer'], 1, 'openinput'); io_i = io_i + 1; - io(io_i) = linio([mdl, '/Micro-Station/Granite/Modal Analysis/accelerometer'], 1, 'openoutput'); io_i = io_i + 1; - io(io_i) = linio([mdl, '/Micro-Station/Translation Stage/Modal Analysis/accelerometer'], 1, 'openoutput'); io_i = io_i + 1; - io(io_i) = linio([mdl, '/Micro-Station/Tilt Stage/Modal Analysis/accelerometer'], 1, 'openoutput'); io_i = io_i + 1; - io(io_i) = linio([mdl, '/Micro-Station/Spindle/Modal Analysis/accelerometer'], 1, 'openoutput'); io_i = io_i + 1; - io(io_i) = linio([mdl, '/Micro-Station/Micro Hexapod/Modal Analysis/accelerometer'], 1, 'openoutput'); io_i = io_i + 1; +% Input/Output definition +G_ms.InputName = {'Fx', 'Fy', 'Fz'}; +G_ms.OutputName = {'gtop_x', 'gtop_y', 'gtop_z', 'gtop_rx', 'gtop_ry', 'gtop_rz', ... + 'ty_x', 'ty_y', 'ty_z', 'ty_rx', 'ty_ry', 'ty_rz', ... + 'ry_x', 'ry_y', 'ry_z', 'ry_rx', 'ry_ry', 'ry_rz', ... + 'rz_x', 'rz_y', 'rz_z', 'rz_rx', 'rz_ry', 'rz_rz', ... + 'hexa_x', 'hexa_y', 'hexa_z', 'hexa_rx', 'hexa_ry', 'hexa_rz'}; + +% Put the output of G in displacements instead of acceleration +G_ms = G_ms/s^2; #+end_src #+begin_src matlab - % Run the linearization - G_ms = linearize(mdl, io, 0); - - %% Input/Output definition - G_ms.InputName = {'Fx', 'Fy', 'Fz'}; - G_ms.OutputName = {'gtop_x', 'gtop_y', 'gtop_z', 'gtop_rx', 'gtop_ry', 'gtop_rz', ... - 'ty_x', 'ty_y', 'ty_z', 'ty_rx', 'ty_ry', 'ty_rz', ... - 'ry_x', 'ry_y', 'ry_z', 'ry_rx', 'ry_ry', 'ry_rz', ... - 'rz_x', 'rz_y', 'rz_z', 'rz_rx', 'rz_ry', 'rz_rz', ... - 'hexa_x', 'hexa_y', 'hexa_z', 'hexa_rx', 'hexa_ry', 'hexa_rz'}; -#+end_src - -The output of =G_ms= is the acceleration of each solid body. -In order to obtain a displacement, we divide the obtained transfer function by $1/s^{2}$; -#+begin_src matlab - G_ms = G_ms/s^2; -#+end_src - -*** Compare with measurements -We now load the Frequency Response Functions measurements during the Modal Analysis (accessible [[file:../../meas/modal-analysis/index.org][here]]). - -#+begin_src matlab - load('../meas/modal-analysis/mat/frf_coh_matrices.mat', 'freqs'); - load('../meas/modal-analysis/mat/frf_com.mat', 'FRFs_CoM'); -#+end_src - -We then compare the measurements with the identified transfer functions using the Simscape Model. - -#+begin_src matlab :exports none - dirs = {'x', 'y', 'z', 'rx', 'ry', 'rz'}; - stages = {'gbot', 'gtop', 'ty', 'ry', 'rz', 'hexa'} - - n_stg = 3; - n_dir = 6; % x, y, z, Rx, Ry, Rz - n_exc = 2; % x, y, z - - f = logspace(0, 3, 1000); - - figure; - hold on; - plot(freqs, abs(squeeze(FRFs_CoM(6*(n_stg-1) + n_dir, n_exc, :)))./((2*pi*freqs).^2)'); - plot(f, abs(squeeze(freqresp(G_ms([stages{n_stg}, '_', dirs{n_dir}], ['F', dirs{n_exc}]), f, 'Hz')))); - set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); - ylabel('Amplitude [m/N]'); - hold off; - xlim([1, 200]); +%% Load estimated FRF at CoM +load('/home/thomas/Cloud/work-projects/ID31-NASS/phd-thesis-chapters/A3-micro-station-modal-analysis/matlab/mat/frf_matrix.mat', 'freqs'); +load('/home/thomas/Cloud/work-projects/ID31-NASS/phd-thesis-chapters/A3-micro-station-modal-analysis/matlab/mat/frf_com.mat', 'frfs_CoM'); #+end_src #+begin_src matlab :exports none - dirs = {'x', 'y', 'z', 'rx', 'ry', 'rz'}; - stages = {'gtop', 'ty', 'ry', 'rz', 'hexa'} +%% Compare the two +dirs = {'x', 'y', 'z', 'rx', 'ry', 'rz'}; +stages = {'gbot', 'gtop', 'ty', 'ry', 'rz', 'hexa'} - f = logspace(1, 3, 1000); +n_stg = 3; +n_dir = 6; % x, y, z, Rx, Ry, Rz +n_exc = 2; % x, y, z - figure; - for n_stg = 1:2 +f = logspace(0, 3, 1000); + +figure; +hold on; +plot(freqs, abs(squeeze(frfs_CoM(6*(n_stg-1) + n_dir, n_exc, :)))./((2*pi*freqs).^2)'); +plot(f, abs(squeeze(freqresp(G_ms([stages{n_stg}, '_', dirs{n_dir}], ['F', dirs{n_exc}]), f, 'Hz')))); +set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); +ylabel('Amplitude [m/N]'); +hold off; +xlim([1, 200]); +#+end_src + +#+begin_src matlab :exports none +dirs = {'x', 'y', 'z', 'rx', 'ry', 'rz'}; +stages = {'gtop', 'ty', 'ry', 'rz', 'hexa'} + +f = logspace(1, 3, 1000); + +figure; +for n_stg = 1:2 for n_dir = 1:3 - subplot(3, 2, (n_dir-1)*2 + n_stg); - title(['F ', dirs{n_dir}, ' to ', stages{n_stg}, ' ', dirs{n_dir}]); - hold on; - plot(freqs, abs(squeeze(FRFs_CoM(6*(n_stg) + n_dir, n_dir, :)))./((2*pi*freqs).^2)'); - plot(f, abs(squeeze(freqresp(G_ms([stages{n_stg}, '_', dirs{n_dir}], ['F', dirs{n_dir}]), f, 'Hz')))); - set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); - ylabel('Amplitude [m/N]'); - if n_dir == 3 - xlabel('Frequency [Hz]'); - end - hold off; - xlim([10, 1000]); - ylim([1e-12, 1e-6]); + subplot(3, 2, (n_dir-1)*2 + n_stg); + title(['F ', dirs{n_dir}, ' to ', stages{n_stg}, ' ', dirs{n_dir}]); + hold on; + plot(freqs, abs(squeeze(frfs_CoM(6*(n_stg) + n_dir, n_dir, :)))./((2*pi*freqs).^2)'); + plot(f, abs(squeeze(freqresp(G_ms([stages{n_stg}, '_', dirs{n_dir}], ['F', dirs{n_dir}]), f, 'Hz')))); + set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); + ylabel('Amplitude [m/N]'); + if n_dir == 3 + xlabel('Frequency [Hz]'); + end + hold off; + xlim([10, 1000]); + ylim([1e-12, 1e-6]); end - end +end #+end_src -#+HEADER: :tangle no :exports results :results none :noweb yes -#+begin_src matlab :var filepath="figs/identification_comp_bot_stages.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png") - <> -#+end_src - -#+NAME: fig:identification_comp_bot_stages -#+CAPTION: caption ([[./figs/identification_comp_bot_stages.png][png]], [[./figs/identification_comp_bot_stages.pdf][pdf]]) -[[file:figs/identification_comp_bot_stages.png]] - - #+begin_src matlab :exports none dirs = {'x', 'y', 'z', 'rx', 'ry', 'rz'}; stages = {'ry', 'rz', 'hexa'} @@ -548,7 +847,7 @@ We then compare the measurements with the identified transfer functions using th subplot(3, 2, (n_dir-1)*2 + n_stg); title(['F ', dirs{n_dir}, ' to ', stages{n_stg}, ' ', dirs{n_dir}]); hold on; - plot(freqs, abs(squeeze(FRFs_CoM(6*(n_stg+2) + n_dir, n_dir, :)))./((2*pi*freqs).^2)'); + plot(freqs, abs(squeeze(frfs_CoM(6*(n_stg+2) + n_dir, n_dir, :)))./((2*pi*freqs).^2)'); plot(f, abs(squeeze(freqresp(G_ms([stages{n_stg}, '_', dirs{n_dir}], ['F', dirs{n_dir}]), f, 'Hz')))); set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); ylabel('Amplitude [m/N]'); @@ -562,16 +861,6 @@ We then compare the measurements with the identified transfer functions using th end #+end_src -#+HEADER: :tangle no :exports results :results none :noweb yes -#+begin_src matlab :var filepath="figs/identification_comp_mid_stages.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png") - <> -#+end_src - -#+NAME: fig:identification_comp_mid_stages -#+CAPTION: caption ([[./figs/identification_comp_mid_stages.png][png]], [[./figs/identification_comp_mid_stages.pdf][pdf]]) -[[file:figs/identification_comp_mid_stages.png]] - - #+begin_src matlab :exports none dirs = {'x', 'y', 'z', 'rx', 'ry', 'rz'}; stages = {'hexa'} @@ -584,7 +873,7 @@ We then compare the measurements with the identified transfer functions using th subplot(3, 1, (n_dir-1) + n_stg); title(['F ', dirs{n_dir}, ' to ', stages{n_stg}, ' ', dirs{n_dir}]); hold on; - plot(freqs, abs(squeeze(FRFs_CoM(6*(n_stg+4) + n_dir, n_dir, :)))./((2*pi*freqs).^2)'); + plot(freqs, abs(squeeze(frfs_CoM(6*(n_stg+4) + n_dir, n_dir, :)))./((2*pi*freqs).^2)'); plot(f, abs(squeeze(freqresp(G_ms([stages{n_stg}, '_', dirs{n_dir}], ['F', dirs{n_dir}]), f, 'Hz')))); set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); ylabel('Amplitude [m/N]'); @@ -598,114 +887,61 @@ We then compare the measurements with the identified transfer functions using th end #+end_src -#+HEADER: :tangle no :exports results :results none :noweb yes -#+begin_src matlab :var filepath="figs/identification_comp_top_stages.pdf" :var figsize="full-tall" :post pdf2svg(file=*this*, ext="png") - <> -#+end_src - -#+NAME: fig:identification_comp_top_stages -#+CAPTION: caption ([[./figs/identification_comp_top_stages.png][png]], [[./figs/identification_comp_top_stages.pdf][pdf]]) -[[file:figs/identification_comp_top_stages.png]] - - ** Obtained Compliance of the Micro-Station -*** Matlab Init :noexport:ignore: -#+begin_src matlab :tangle no :exports none :results silent :noweb yes :var current_dir=(file-name-directory buffer-file-name) - <> -#+end_src - -#+begin_src matlab :exports none :results silent :noweb yes - <> -#+end_src - -#+begin_src matlab :tangle no - simulinkproject('../'); -#+end_src - #+begin_src matlab - open('nass_model.slx') -#+end_src +%% Initialize simulation with default parameters (flexible elements) +initializeGround(); +initializeGranite(); +initializeTy(); +initializeRy(); +initializeRz(); +initializeMicroHexapod('type', 'compliance'); -*** Initialization -We initialize all the stages with the default parameters. -#+begin_src matlab - initializeGround(); - initializeGranite(); - initializeTy(); - initializeRy(); - initializeRz(); - initializeMicroHexapod('type', 'compliance'); -#+end_src - -We put nothing on top of the micro-hexapod. -#+begin_src matlab - initializeAxisc('type', 'none'); - initializeMirror('type', 'none'); - initializeNanoHexapod('type', 'none'); - initializeSample('type', 'none'); -#+end_src - -#+begin_src matlab - initializeReferences(); - initializeDisturbances(); - initializeController(); - initializeSimscapeConfiguration(); - initializeLoggingConfiguration(); +initializeReferences(); +initializeDisturbances(); +initializeSimscapeConfiguration(); +initializeLoggingConfiguration(); #+end_src And we identify the dynamics from forces/torques applied on the micro-hexapod top platform to the motion of the micro-hexapod top platform at the same point. -The obtained compliance is shown in Figure [[fig:compliance_micro_station]]. #+begin_src matlab - %% Name of the Simulink File - mdl = 'nass_model'; +%% Identification of the compliance +% Input/Output definition +clear io; io_i = 1; +io(io_i) = linio([mdl, '/Micro-Station/Micro Hexapod/Compliance/Fm'], 1, 'openinput'); io_i = io_i + 1; % Direct Forces/Torques applied on the micro-hexapod top platform +io(io_i) = linio([mdl, '/Micro-Station/Micro Hexapod/Compliance/Dm'], 1, 'output'); io_i = io_i + 1; % Absolute displacement of the top platform - %% Input/Output definition - clear io; io_i = 1; - io(io_i) = linio([mdl, '/Micro-Station/Micro Hexapod/Compliance/Fm'], 1, 'openinput'); io_i = io_i + 1; % Direct Forces/Torques applied on the micro-hexapod top platform - io(io_i) = linio([mdl, '/Micro-Station/Micro Hexapod/Compliance/Dm'], 1, 'output'); io_i = io_i + 1; % Absolute displacement of the top platform - - %% Run the linearization - Gm = linearize(mdl, io, 0); - Gm.InputName = {'Fmx', 'Fmy', 'Fmz', 'Mmx', 'Mmy', 'Mmz'}; - Gm.OutputName = {'Dx', 'Dy', 'Dz', 'Drx', 'Dry', 'Drz'}; -#+end_src - -#+begin_src matlab - save('../meas/micro-station-compliance/mat/model.mat', 'Gm'); +% Run the linearization +Gm = linearize(mdl, io, 0); +Gm.InputName = {'Fmx', 'Fmy', 'Fmz', 'Mmx', 'Mmy', 'Mmz'}; +Gm.OutputName = {'Dx', 'Dy', 'Dz', 'Drx', 'Dry', 'Drz'}; #+end_src #+begin_src matlab :exports none - labels = {'$D_x/F_{x}$', '$D_y/F_{y}$', '$D_z/F_{z}$', '$R_{x}/M_{x}$', '$R_{y}/M_{y}$', '$R_{R}/M_{z}$'}; +%% Plot of the compliance curves +labels = {'$D_x/F_{x}$', '$D_y/F_{y}$', '$D_z/F_{z}$', '$R_{x}/M_{x}$', '$R_{y}/M_{y}$', '$R_{R}/M_{z}$'}; - freqs = logspace(1, 3, 1000); +freqs = logspace(1, 3, 1000); - figure; +figure; - hold on; - for i = 1:6 +hold on; +for i = 1:6 plot(freqs, abs(squeeze(freqresp(Gm(i, i), freqs, 'Hz'))), 'DisplayName', labels{i}); - end - hold off; - set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); - xlabel('Frequency [Hz]'); - ylabel('Compliance'); - legend('location', 'northwest'); +end +hold off; +set(gca, 'XScale', 'log'); set(gca, 'YScale', 'log'); +xlabel('Frequency [Hz]'); +ylabel('Compliance'); +legend('location', 'northwest'); #+end_src -#+header: :tangle no :exports results :results none :noweb yes -#+begin_src matlab :var filepath="figs/compliance_micro_station.pdf" :var figsize="wide-tall" :post pdf2svg(file=*this*, ext="png") - <> -#+end_src - -#+name: fig:compliance_micro_station -#+caption: Obtained compliance of the Micro-Station ([[./figs/compliance_micro_station.png][png]], [[./figs/compliance_micro_station.pdf][pdf]]) -[[file:figs/compliance_micro_station.png]] +- [ ] Comparison with the estimated (or measured) compliance ** Conclusion -#+begin_important - For such a complex system, we believe that the Simscape Model represents the dynamics of the system with enough fidelity. -#+end_important +For such a complex system, we believe that the Simscape Model represents the dynamics of the system with enough fidelity. + * Measurement of Positioning Errors :PROPERTIES: :HEADER-ARGS:matlab+: :tangle matlab/ustation_2_kinematics.m @@ -1013,8 +1249,7 @@ end :END: #+begin_src matlab arguments - args.type char {mustBeMember(args.type,{'rigid', 'flexible', 'none', 'modal-analysis', 'init'})} = 'flexible' - args.Foffset logical {mustBeNumericOrLogical} = false + args.type char {mustBeMember(args.type,{'rigid', 'flexible', 'none', 'modal-analysis'})} = 'flexible' args.density (1,1) double {mustBeNumeric, mustBeNonnegative} = 2800 % Density [kg/m3] args.K (3,1) double {mustBeNumeric, mustBeNonnegative} = [4e9; 3e8; 8e8] % [N/m] args.C (3,1) double {mustBeNumeric, mustBeNonnegative} = [4.0e5; 1.1e5; 9.0e5] % [N/(m/s)] @@ -1048,8 +1283,6 @@ First, we initialize the =granite= structure. granite.type = 2; case 'modal-analysis' granite.type = 3; - case 'init' - granite.type = 4; end #+end_src @@ -1079,20 +1312,6 @@ Z-offset for the initial position of the sample with respect to the granite top granite.C = args.C; % [N/(m/s)] #+end_src -*** Equilibrium position of the each joint. -:PROPERTIES: -:UNNUMBERED: t -:END: - -#+begin_src matlab - if args.Foffset && ~strcmp(args.type, 'none') && ~strcmp(args.type, 'rigid') && ~strcmp(args.type, 'init') - load('Foffset.mat', 'Fgm'); - granite.Deq = -Fgm'./granite.K; - else - granite.Deq = zeros(6,1); - end -#+end_src - *** Save the Structure #+begin_src matlab if exist('./mat', 'dir') @@ -1130,8 +1349,7 @@ end :END: #+begin_src matlab arguments - args.type char {mustBeMember(args.type,{'none', 'rigid', 'flexible', 'modal-analysis', 'init'})} = 'flexible' - args.Foffset logical {mustBeNumericOrLogical} = false + args.type char {mustBeMember(args.type,{'none', 'rigid', 'flexible', 'modal-analysis'})} = 'flexible' end #+end_src @@ -1158,8 +1376,6 @@ First, we initialize the =ty= structure. ty.type = 2; case 'modal-analysis' ty.type = 3; - case 'init' - ty.type = 4; end #+end_src @@ -1216,20 +1432,6 @@ Define the density of the materials as well as the geometry (STEP files). ty.C = [8e4; 5e4; 8e4; 2e4; 3e4; 2e4]; % [N/(m/s), N*m/(rad/s)] #+end_src -*** Equilibrium position of the each joint. -:PROPERTIES: -:UNNUMBERED: t -:END: - -#+begin_src matlab - if args.Foffset && ~strcmp(args.type, 'none') && ~strcmp(args.type, 'rigid') && ~strcmp(args.type, 'init') - load('Foffset.mat', 'Ftym'); - ty.Deq = -Ftym'./ty.K; - else - ty.Deq = zeros(6,1); - end -#+end_src - *** Save the Structure #+begin_src matlab if exist('./mat', 'dir') @@ -1267,8 +1469,7 @@ end :END: #+begin_src matlab arguments - args.type char {mustBeMember(args.type,{'none', 'rigid', 'flexible', 'modal-analysis', 'init'})} = 'flexible' - args.Foffset logical {mustBeNumericOrLogical} = false + args.type char {mustBeMember(args.type,{'none', 'rigid', 'flexible', 'modal-analysis'})} = 'flexible' args.Ry_init (1,1) double {mustBeNumeric} = 0 end #+end_src @@ -1297,8 +1498,6 @@ First, we initialize the =ry= structure. ry.type = 2; case 'modal-analysis' ry.type = 3; - case 'init' - ry.type = 4; end #+end_src @@ -1344,20 +1543,6 @@ Z-Offset so that the center of rotation matches the sample center; ry.C = [1e5; 1e5; 1e5; 3e4; 1e3; 3e4]; #+end_src -*** Equilibrium position of the each joint. -:PROPERTIES: -:UNNUMBERED: t -:END: - -#+begin_src matlab - if args.Foffset && ~strcmp(args.type, 'none') && ~strcmp(args.type, 'rigid') && ~strcmp(args.type, 'init') - load('Foffset.mat', 'Fym'); - ry.Deq = -Fym'./ry.K; - else - ry.Deq = zeros(6,1); - end -#+end_src - *** Save the Structure #+begin_src matlab if exist('./mat', 'dir') @@ -1395,8 +1580,7 @@ end :END: #+begin_src matlab arguments - args.type char {mustBeMember(args.type,{'none', 'rigid', 'flexible', 'modal-analysis', 'init'})} = 'flexible' - args.Foffset logical {mustBeNumericOrLogical} = false + args.type char {mustBeMember(args.type,{'none', 'rigid', 'flexible', 'modal-analysis'})} = 'flexible' end #+end_src @@ -1423,8 +1607,6 @@ First, we initialize the =rz= structure. rz.type = 2; case 'modal-analysis' rz.type = 3; - case 'init' - rz.type = 4; end #+end_src @@ -1458,20 +1640,6 @@ Properties of the Material and link to the geometry of the spindle. rz.C = [4e4; 4e4; 7e4; 1e4; 1e4; 1e4]; #+end_src -*** Equilibrium position of the each joint. -:PROPERTIES: -:UNNUMBERED: t -:END: - -#+begin_src matlab - if args.Foffset && ~strcmp(args.type, 'none') && ~strcmp(args.type, 'rigid') && ~strcmp(args.type, 'init') - load('Foffset.mat', 'Fzm'); - rz.Deq = -Fzm'./rz.K; - else - rz.Deq = zeros(6,1); - end -#+end_src - *** Save the Structure #+begin_src matlab if exist('./mat', 'dir') @@ -1509,7 +1677,7 @@ end :END: #+begin_src matlab arguments - args.type char {mustBeMember(args.type,{'none', 'rigid', 'flexible', 'modal-analysis', 'init', 'compliance'})} = 'flexible' + args.type char {mustBeMember(args.type,{'none', 'rigid', 'flexible', 'modal-analysis', 'compliance'})} = 'flexible' % initializeFramesPositions args.H (1,1) double {mustBeNumeric, mustBePositive} = 350e-3 args.MO_B (1,1) double {mustBeNumeric} = 270e-3 @@ -1540,8 +1708,6 @@ end % inverseKinematics args.AP (3,1) double {mustBeNumeric} = zeros(3,1) args.ARB (3,3) double {mustBeNumeric} = eye(3) - % Force that stiffness of each joint should apply at t=0 - args.Foffset logical {mustBeNumericOrLogical} = false end #+end_src @@ -1605,16 +1771,6 @@ end stewart = initializeInertialSensor(stewart, 'type', 'none'); #+end_src -Equilibrium position of the each joint. -#+begin_src matlab - if args.Foffset && ~strcmp(args.type, 'none') && ~strcmp(args.type, 'rigid') && ~strcmp(args.type, 'init') - load('Foffset.mat', 'Fhm'); - stewart.actuators.dLeq = -Fhm'./args.Ki; - else - stewart.actuators.dLeq = zeros(6,1); - end -#+end_src - *** Add Type :PROPERTIES: :UNNUMBERED: t @@ -1629,8 +1785,6 @@ Equilibrium position of the each joint. stewart.type = 2; case 'modal-analysis' stewart.type = 3; - case 'init' - stewart.type = 4; case 'compliance' stewart.type = 5; end @@ -1889,73 +2043,19 @@ end Dhl = struct('time', t, 'signals', struct('values', Dhl)); #+end_src -*** Axis Compensation -:PROPERTIES: -:UNNUMBERED: t -:END: -#+begin_src matlab - %% Axis Compensation - Rm - t = [0, Ts]; - - Rm = [args.Rm_pos, args.Rm_pos]; - Rm = struct('time', t, 'signals', struct('values', Rm)); -#+end_src - -*** Nano Hexapod -:PROPERTIES: -:UNNUMBERED: t -:END: -#+begin_src matlab - %% Nano-Hexapod - t = [0, Ts]; - Dn = zeros(length(t), 6); - - switch args.Dn_type - case 'constant' - Dn = [args.Dn_pos, args.Dn_pos]; - - load('nass_stages.mat', 'nano_hexapod'); - - AP = [args.Dn_pos(1) ; args.Dn_pos(2) ; args.Dn_pos(3)]; - - tx = args.Dn_pos(4); - ty = args.Dn_pos(5); - tz = args.Dn_pos(6); - - ARB = [cos(tz) -sin(tz) 0; - sin(tz) cos(tz) 0; - 0 0 1]*... - [ cos(ty) 0 sin(ty); - 0 1 0; - -sin(ty) 0 cos(ty)]*... - [1 0 0; - 0 cos(tx) -sin(tx); - 0 sin(tx) cos(tx)]; - - [~, Dnl] = inverseKinematics(nano_hexapod, 'AP', AP, 'ARB', ARB); - Dnl = [Dnl, Dnl]; - otherwise - warning('Dn_type is not set correctly'); - end - - Dn = struct('time', t, 'signals', struct('values', Dn)); - Dnl = struct('time', t, 'signals', struct('values', Dnl)); -#+end_src - *** Save the Structure #+begin_src matlab -micro_hexapod = stewart; if exist('./mat', 'dir') if exist('./mat/nass_references.mat', 'file') - save('mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'Rm', 'Dn', 'Dnl', 'args', 'Ts', '-append'); + save('mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'args', 'Ts', '-append'); else - save('mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'Rm', 'Dn', 'Dnl', 'args', 'Ts'); + save('mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'args', 'Ts'); end elseif exist('./matlab', 'dir') if exist('./matlab/mat/nass_references.mat', 'file') - save('matlab/mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'Rm', 'Dn', 'Dnl', 'args', 'Ts', '-append'); + save('matlab/mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'args', 'Ts', '-append'); else - save('matlab/mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'Rm', 'Dn', 'Dnl', 'args', 'Ts'); + save('matlab/mat/nass_references.mat', 'Dy', 'Ry', 'Rz', 'Dh', 'Dhl', 'args', 'Ts'); end end #+end_src @@ -2012,7 +2112,7 @@ end :UNNUMBERED: t :END: #+begin_src matlab - load('./mat/dist_psd.mat', 'dist_f'); + load('dist_psd.mat', 'dist_f'); #+end_src We remove the first frequency point that usually is very large. @@ -2176,7 +2276,6 @@ We define some parameters that will be used in the algorithm. *** Save the Structure #+begin_src matlab -micro_hexapod = stewart; if exist('./mat', 'dir') if exist('./mat/nass_disturbances.mat', 'file') save('mat/nass_disturbances.mat', 'Dwx', 'Dwy', 'Dwz', 'Fty_x', 'Fty_z', 'Frz_z', 'Fd', 'Ts', 't', 'args', '-append'); @@ -2192,87 +2291,1543 @@ elseif exist('./matlab', 'dir') end #+end_src -** Z-Axis Geophone +** =initializeStewartPlatform=: Initialize the Stewart Platform structure :PROPERTIES: -:header-args:matlab+: :tangle matlab/src/initializeZAxisGeophone.m +:header-args:matlab+: :tangle matlab/src/initializeStewartPlatform.m +:header-args:matlab+: :comments none :mkdirp yes :eval no +:END: + +*** Documentation +:PROPERTIES: +:UNNUMBERED: t +:END: + +#+name: fig:stewart-frames-position +#+caption: Definition of the position of the frames +[[file:figs/stewart-frames-position.png]] + +*** Function description +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + function [stewart] = initializeStewartPlatform() + % initializeStewartPlatform - Initialize the stewart structure + % + % Syntax: [stewart] = initializeStewartPlatform(args) + % + % Outputs: + % - stewart - A structure with the following sub-structures: + % - platform_F - + % - platform_M - + % - joints_F - + % - joints_M - + % - struts_F - + % - struts_M - + % - actuators - + % - geometry - + % - properties - +#+end_src + +*** Initialize the Stewart structure +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + stewart = struct(); + stewart.platform_F = struct(); + stewart.platform_M = struct(); + stewart.joints_F = struct(); + stewart.joints_M = struct(); + stewart.struts_F = struct(); + stewart.struts_M = struct(); + stewart.actuators = struct(); + stewart.sensors = struct(); + stewart.sensors.inertial = struct(); + stewart.sensors.force = struct(); + stewart.sensors.relative = struct(); + stewart.geometry = struct(); + stewart.kinematics = struct(); +#+end_src + +** =initializeFramesPositions=: Initialize the positions of frames {A}, {B}, {F} and {M} +:PROPERTIES: +:header-args:matlab+: :tangle matlab/src/initializeFramesPositions.m +:header-args:matlab+: :comments none :mkdirp yes :eval no +:END: + +*** Documentation +:PROPERTIES: +:UNNUMBERED: t +:END: + +#+name: fig:stewart-frames-position +#+caption: Definition of the position of the frames +[[file:figs/stewart-frames-position.png]] + +*** Function description +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + function [stewart] = initializeFramesPositions(stewart, args) + % initializeFramesPositions - Initialize the positions of frames {A}, {B}, {F} and {M} + % + % Syntax: [stewart] = initializeFramesPositions(stewart, args) + % + % Inputs: + % - args - Can have the following fields: + % - H [1x1] - Total Height of the Stewart Platform (height from {F} to {M}) [m] + % - MO_B [1x1] - Height of the frame {B} with respect to {M} [m] + % + % Outputs: + % - stewart - A structure with the following fields: + % - geometry.H [1x1] - Total Height of the Stewart Platform [m] + % - geometry.FO_M [3x1] - Position of {M} with respect to {F} [m] + % - platform_M.MO_B [3x1] - Position of {B} with respect to {M} [m] + % - platform_F.FO_A [3x1] - Position of {A} with respect to {F} [m] +#+end_src + +*** Optional Parameters +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + arguments + stewart + args.H (1,1) double {mustBeNumeric, mustBePositive} = 90e-3 + args.MO_B (1,1) double {mustBeNumeric} = 50e-3 + end +#+end_src + +*** Compute the position of each frame +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + H = args.H; % Total Height of the Stewart Platform [m] + + FO_M = [0; 0; H]; % Position of {M} with respect to {F} [m] + + MO_B = [0; 0; args.MO_B]; % Position of {B} with respect to {M} [m] + + FO_A = MO_B + FO_M; % Position of {A} with respect to {F} [m] +#+end_src + +*** Populate the =stewart= structure +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + stewart.geometry.H = H; + stewart.geometry.FO_M = FO_M; + stewart.platform_M.MO_B = MO_B; + stewart.platform_F.FO_A = FO_A; +#+end_src + +** =generateGeneralConfiguration=: Generate a Very General Configuration +:PROPERTIES: +:header-args:matlab+: :tangle matlab/src/generateGeneralConfiguration.m +:header-args:matlab+: :comments none :mkdirp yes :eval no +:END: + +*** Documentation +:PROPERTIES: +:UNNUMBERED: t +:END: +Joints are positions on a circle centered with the Z axis of {F} and {M} and at a chosen distance from {F} and {M}. +The radius of the circles can be chosen as well as the angles where the joints are located (see Figure [[fig:joint_position_general]]). + +#+begin_src latex :file stewart_bottom_plate.pdf :tangle no + \begin{tikzpicture} + % Internal and external limit + \draw[fill=white!80!black] (0, 0) circle [radius=3]; + % Circle where the joints are located + \draw[dashed] (0, 0) circle [radius=2.5]; + + % Bullets for the positions of the joints + \node[] (J1) at ( 80:2.5){$\bullet$}; + \node[] (J2) at (100:2.5){$\bullet$}; + \node[] (J3) at (200:2.5){$\bullet$}; + \node[] (J4) at (220:2.5){$\bullet$}; + \node[] (J5) at (320:2.5){$\bullet$}; + \node[] (J6) at (340:2.5){$\bullet$}; + + % Name of the points + \node[above right] at (J1) {$a_{1}$}; + \node[above left] at (J2) {$a_{2}$}; + \node[above left] at (J3) {$a_{3}$}; + \node[right ] at (J4) {$a_{4}$}; + \node[left ] at (J5) {$a_{5}$}; + \node[above right] at (J6) {$a_{6}$}; + + % First 2 angles + \draw[dashed, ->] (0:1) arc [start angle=0, end angle=80, radius=1] node[below right]{$\theta_{1}$}; + \draw[dashed, ->] (0:1.5) arc [start angle=0, end angle=100, radius=1.5] node[left ]{$\theta_{2}$}; + + % Division of 360 degrees by 3 + \draw[dashed] (0, 0) -- ( 80:3.2); + \draw[dashed] (0, 0) -- (100:3.2); + \draw[dashed] (0, 0) -- (200:3.2); + \draw[dashed] (0, 0) -- (220:3.2); + \draw[dashed] (0, 0) -- (320:3.2); + \draw[dashed] (0, 0) -- (340:3.2); + + % Radius for the position of the joints + \draw[<->] (0, 0) --node[near end, above]{$R$} (180:2.5); + + \draw[->] (0, 0) -- ++(3.4, 0) node[above]{$x$}; + \draw[->] (0, 0) -- ++(0, 3.4) node[left]{$y$}; + \end{tikzpicture} +#+end_src + +#+name: fig:joint_position_general +#+caption: Position of the joints +#+RESULTS: +[[file:figs/stewart_bottom_plate.png]] + +*** Function description +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + function [stewart] = generateGeneralConfiguration(stewart, args) + % generateGeneralConfiguration - Generate a Very General Configuration + % + % Syntax: [stewart] = generateGeneralConfiguration(stewart, args) + % + % Inputs: + % - args - Can have the following fields: + % - FH [1x1] - Height of the position of the fixed joints with respect to the frame {F} [m] + % - FR [1x1] - Radius of the position of the fixed joints in the X-Y [m] + % - FTh [6x1] - Angles of the fixed joints in the X-Y plane with respect to the X axis [rad] + % - MH [1x1] - Height of the position of the mobile joints with respect to the frame {M} [m] + % - FR [1x1] - Radius of the position of the mobile joints in the X-Y [m] + % - MTh [6x1] - Angles of the mobile joints in the X-Y plane with respect to the X axis [rad] + % + % Outputs: + % - stewart - updated Stewart structure with the added fields: + % - platform_F.Fa [3x6] - Its i'th column is the position vector of joint ai with respect to {F} + % - platform_M.Mb [3x6] - Its i'th column is the position vector of joint bi with respect to {M} +#+end_src + +*** Optional Parameters +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + arguments + stewart + args.FH (1,1) double {mustBeNumeric, mustBePositive} = 15e-3 + args.FR (1,1) double {mustBeNumeric, mustBePositive} = 115e-3; + args.FTh (6,1) double {mustBeNumeric} = [-10, 10, 120-10, 120+10, 240-10, 240+10]*(pi/180); + args.MH (1,1) double {mustBeNumeric, mustBePositive} = 15e-3 + args.MR (1,1) double {mustBeNumeric, mustBePositive} = 90e-3; + args.MTh (6,1) double {mustBeNumeric} = [-60+10, 60-10, 60+10, 180-10, 180+10, -60-10]*(pi/180); + end +#+end_src + +*** Compute the pose +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + Fa = zeros(3,6); + Mb = zeros(3,6); +#+end_src + +#+begin_src matlab + for i = 1:6 + Fa(:,i) = [args.FR*cos(args.FTh(i)); args.FR*sin(args.FTh(i)); args.FH]; + Mb(:,i) = [args.MR*cos(args.MTh(i)); args.MR*sin(args.MTh(i)); -args.MH]; + end +#+end_src + +*** Populate the =stewart= structure +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + stewart.platform_F.Fa = Fa; + stewart.platform_M.Mb = Mb; +#+end_src + +** =computeJointsPose=: Compute the Pose of the Joints +:PROPERTIES: +:header-args:matlab+: :tangle matlab/src/computeJointsPose.m +:header-args:matlab+: :comments none :mkdirp yes :eval no +:END: + +*** Documentation +:PROPERTIES: +:UNNUMBERED: t +:END: + +#+name: fig:stewart-struts +#+caption: Position and orientation of the struts +[[file:figs/stewart-struts.png]] + +*** Function description +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + function [stewart] = computeJointsPose(stewart) + % computeJointsPose - + % + % Syntax: [stewart] = computeJointsPose(stewart) + % + % Inputs: + % - stewart - A structure with the following fields + % - platform_F.Fa [3x6] - Its i'th column is the position vector of joint ai with respect to {F} + % - platform_M.Mb [3x6] - Its i'th column is the position vector of joint bi with respect to {M} + % - platform_F.FO_A [3x1] - Position of {A} with respect to {F} + % - platform_M.MO_B [3x1] - Position of {B} with respect to {M} + % - geometry.FO_M [3x1] - Position of {M} with respect to {F} + % + % Outputs: + % - stewart - A structure with the following added fields + % - geometry.Aa [3x6] - The i'th column is the position of ai with respect to {A} + % - geometry.Ab [3x6] - The i'th column is the position of bi with respect to {A} + % - geometry.Ba [3x6] - The i'th column is the position of ai with respect to {B} + % - geometry.Bb [3x6] - The i'th column is the position of bi with respect to {B} + % - geometry.l [6x1] - The i'th element is the initial length of strut i + % - geometry.As [3x6] - The i'th column is the unit vector of strut i expressed in {A} + % - geometry.Bs [3x6] - The i'th column is the unit vector of strut i expressed in {B} + % - struts_F.l [6x1] - Length of the Fixed part of the i'th strut + % - struts_M.l [6x1] - Length of the Mobile part of the i'th strut + % - platform_F.FRa [3x3x6] - The i'th 3x3 array is the rotation matrix to orientate the bottom of the i'th strut from {F} + % - platform_M.MRb [3x3x6] - The i'th 3x3 array is the rotation matrix to orientate the top of the i'th strut from {M} +#+end_src + +*** Check the =stewart= structure elements +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + assert(isfield(stewart.platform_F, 'Fa'), 'stewart.platform_F should have attribute Fa') + Fa = stewart.platform_F.Fa; + + assert(isfield(stewart.platform_M, 'Mb'), 'stewart.platform_M should have attribute Mb') + Mb = stewart.platform_M.Mb; + + assert(isfield(stewart.platform_F, 'FO_A'), 'stewart.platform_F should have attribute FO_A') + FO_A = stewart.platform_F.FO_A; + + assert(isfield(stewart.platform_M, 'MO_B'), 'stewart.platform_M should have attribute MO_B') + MO_B = stewart.platform_M.MO_B; + + assert(isfield(stewart.geometry, 'FO_M'), 'stewart.geometry should have attribute FO_M') + FO_M = stewart.geometry.FO_M; +#+end_src + +*** Compute the position of the Joints +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + Aa = Fa - repmat(FO_A, [1, 6]); + Bb = Mb - repmat(MO_B, [1, 6]); + + Ab = Bb - repmat(-MO_B-FO_M+FO_A, [1, 6]); + Ba = Aa - repmat( MO_B+FO_M-FO_A, [1, 6]); +#+end_src + +*** Compute the strut length and orientation +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + As = (Ab - Aa)./vecnorm(Ab - Aa); % As_i is the i'th vector of As + + l = vecnorm(Ab - Aa)'; +#+end_src + +#+begin_src matlab + Bs = (Bb - Ba)./vecnorm(Bb - Ba); +#+end_src + +*** Compute the orientation of the Joints +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + FRa = zeros(3,3,6); + MRb = zeros(3,3,6); + + for i = 1:6 + FRa(:,:,i) = [cross([0;1;0], As(:,i)) , cross(As(:,i), cross([0;1;0], As(:,i))) , As(:,i)]; + FRa(:,:,i) = FRa(:,:,i)./vecnorm(FRa(:,:,i)); + + MRb(:,:,i) = [cross([0;1;0], Bs(:,i)) , cross(Bs(:,i), cross([0;1;0], Bs(:,i))) , Bs(:,i)]; + MRb(:,:,i) = MRb(:,:,i)./vecnorm(MRb(:,:,i)); + end +#+end_src + +*** Populate the =stewart= structure +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + stewart.geometry.Aa = Aa; + stewart.geometry.Ab = Ab; + stewart.geometry.Ba = Ba; + stewart.geometry.Bb = Bb; + stewart.geometry.As = As; + stewart.geometry.Bs = Bs; + stewart.geometry.l = l; + + stewart.struts_F.l = l/2; + stewart.struts_M.l = l/2; + + stewart.platform_F.FRa = FRa; + stewart.platform_M.MRb = MRb; +#+end_src + +** =initializeCylindricalPlatforms=: Initialize the geometry of the Fixed and Mobile Platforms +:PROPERTIES: +:header-args:matlab+: :tangle matlab/src/initializeCylindricalPlatforms.m +:header-args:matlab+: :comments none :mkdirp yes :eval no +:END: + +*** Function description +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + function [stewart] = initializeCylindricalPlatforms(stewart, args) + % initializeCylindricalPlatforms - Initialize the geometry of the Fixed and Mobile Platforms + % + % Syntax: [stewart] = initializeCylindricalPlatforms(args) + % + % Inputs: + % - args - Structure with the following fields: + % - Fpm [1x1] - Fixed Platform Mass [kg] + % - Fph [1x1] - Fixed Platform Height [m] + % - Fpr [1x1] - Fixed Platform Radius [m] + % - Mpm [1x1] - Mobile Platform Mass [kg] + % - Mph [1x1] - Mobile Platform Height [m] + % - Mpr [1x1] - Mobile Platform Radius [m] + % + % Outputs: + % - stewart - updated Stewart structure with the added fields: + % - platform_F [struct] - structure with the following fields: + % - type = 1 + % - M [1x1] - Fixed Platform Mass [kg] + % - I [3x3] - Fixed Platform Inertia matrix [kg*m^2] + % - H [1x1] - Fixed Platform Height [m] + % - R [1x1] - Fixed Platform Radius [m] + % - platform_M [struct] - structure with the following fields: + % - M [1x1] - Mobile Platform Mass [kg] + % - I [3x3] - Mobile Platform Inertia matrix [kg*m^2] + % - H [1x1] - Mobile Platform Height [m] + % - R [1x1] - Mobile Platform Radius [m] +#+end_src + +*** Optional Parameters +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + arguments + stewart + args.Fpm (1,1) double {mustBeNumeric, mustBePositive} = 1 + args.Fph (1,1) double {mustBeNumeric, mustBePositive} = 10e-3 + args.Fpr (1,1) double {mustBeNumeric, mustBePositive} = 125e-3 + args.Mpm (1,1) double {mustBeNumeric, mustBePositive} = 1 + args.Mph (1,1) double {mustBeNumeric, mustBePositive} = 10e-3 + args.Mpr (1,1) double {mustBeNumeric, mustBePositive} = 100e-3 + end +#+end_src + +*** Compute the Inertia matrices of platforms +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + I_F = diag([1/12*args.Fpm * (3*args.Fpr^2 + args.Fph^2), ... + 1/12*args.Fpm * (3*args.Fpr^2 + args.Fph^2), ... + 1/2 *args.Fpm * args.Fpr^2]); +#+end_src + +#+begin_src matlab + I_M = diag([1/12*args.Mpm * (3*args.Mpr^2 + args.Mph^2), ... + 1/12*args.Mpm * (3*args.Mpr^2 + args.Mph^2), ... + 1/2 *args.Mpm * args.Mpr^2]); +#+end_src + +*** Populate the =stewart= structure +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + stewart.platform_F.type = 1; + + stewart.platform_F.I = I_F; + stewart.platform_F.M = args.Fpm; + stewart.platform_F.R = args.Fpr; + stewart.platform_F.H = args.Fph; +#+end_src + +#+begin_src matlab + stewart.platform_M.type = 1; + + stewart.platform_M.I = I_M; + stewart.platform_M.M = args.Mpm; + stewart.platform_M.R = args.Mpr; + stewart.platform_M.H = args.Mph; +#+end_src + +** =initializeCylindricalStruts=: Define the inertia of cylindrical struts +:PROPERTIES: +:header-args:matlab+: :tangle matlab/src/initializeCylindricalStruts.m +:header-args:matlab+: :comments none :mkdirp yes :eval no +:END: + +*** Function description +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + function [stewart] = initializeCylindricalStruts(stewart, args) + % initializeCylindricalStruts - Define the mass and moment of inertia of cylindrical struts + % + % Syntax: [stewart] = initializeCylindricalStruts(args) + % + % Inputs: + % - args - Structure with the following fields: + % - Fsm [1x1] - Mass of the Fixed part of the struts [kg] + % - Fsh [1x1] - Height of cylinder for the Fixed part of the struts [m] + % - Fsr [1x1] - Radius of cylinder for the Fixed part of the struts [m] + % - Msm [1x1] - Mass of the Mobile part of the struts [kg] + % - Msh [1x1] - Height of cylinder for the Mobile part of the struts [m] + % - Msr [1x1] - Radius of cylinder for the Mobile part of the struts [m] + % + % Outputs: + % - stewart - updated Stewart structure with the added fields: + % - struts_F [struct] - structure with the following fields: + % - M [6x1] - Mass of the Fixed part of the struts [kg] + % - I [3x3x6] - Moment of Inertia for the Fixed part of the struts [kg*m^2] + % - H [6x1] - Height of cylinder for the Fixed part of the struts [m] + % - R [6x1] - Radius of cylinder for the Fixed part of the struts [m] + % - struts_M [struct] - structure with the following fields: + % - M [6x1] - Mass of the Mobile part of the struts [kg] + % - I [3x3x6] - Moment of Inertia for the Mobile part of the struts [kg*m^2] + % - H [6x1] - Height of cylinder for the Mobile part of the struts [m] + % - R [6x1] - Radius of cylinder for the Mobile part of the struts [m] +#+end_src + +*** Optional Parameters +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + arguments + stewart + args.Fsm (1,1) double {mustBeNumeric, mustBePositive} = 0.1 + args.Fsh (1,1) double {mustBeNumeric, mustBePositive} = 50e-3 + args.Fsr (1,1) double {mustBeNumeric, mustBePositive} = 5e-3 + args.Msm (1,1) double {mustBeNumeric, mustBePositive} = 0.1 + args.Msh (1,1) double {mustBeNumeric, mustBePositive} = 50e-3 + args.Msr (1,1) double {mustBeNumeric, mustBePositive} = 5e-3 + end +#+end_src + +*** Compute the properties of the cylindrical struts +:PROPERTIES: +:UNNUMBERED: t +:END: + +#+begin_src matlab + Fsm = ones(6,1).*args.Fsm; + Fsh = ones(6,1).*args.Fsh; + Fsr = ones(6,1).*args.Fsr; + + Msm = ones(6,1).*args.Msm; + Msh = ones(6,1).*args.Msh; + Msr = ones(6,1).*args.Msr; +#+end_src + +#+begin_src matlab + I_F = zeros(3, 3, 6); % Inertia of the "fixed" part of the strut + I_M = zeros(3, 3, 6); % Inertia of the "mobile" part of the strut + + for i = 1:6 + I_F(:,:,i) = diag([1/12 * Fsm(i) * (3*Fsr(i)^2 + Fsh(i)^2), ... + 1/12 * Fsm(i) * (3*Fsr(i)^2 + Fsh(i)^2), ... + 1/2 * Fsm(i) * Fsr(i)^2]); + + I_M(:,:,i) = diag([1/12 * Msm(i) * (3*Msr(i)^2 + Msh(i)^2), ... + 1/12 * Msm(i) * (3*Msr(i)^2 + Msh(i)^2), ... + 1/2 * Msm(i) * Msr(i)^2]); + end +#+end_src + +*** Populate the =stewart= structure +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + stewart.struts_M.type = 1; + + stewart.struts_M.I = I_M; + stewart.struts_M.M = Msm; + stewart.struts_M.R = Msr; + stewart.struts_M.H = Msh; +#+end_src + +#+begin_src matlab + stewart.struts_F.type = 1; + + stewart.struts_F.I = I_F; + stewart.struts_F.M = Fsm; + stewart.struts_F.R = Fsr; + stewart.struts_F.H = Fsh; +#+end_src + +** =initializeStrutDynamics=: Add Stiffness and Damping properties of each strut +:PROPERTIES: +:header-args:matlab+: :tangle matlab/src/initializeStrutDynamics.m +:header-args:matlab+: :comments none :mkdirp yes :eval no +:END: + +*** Documentation +:PROPERTIES: +:UNNUMBERED: t +:END: + +#+name: fig:piezoelectric_stack +#+attr_html: :width 500px +#+caption: Example of a piezoelectric stach actuator (PI) +[[file:figs/piezoelectric_stack.jpg]] + +A simplistic model of such amplified actuator is shown in Figure [[fig:actuator_model_simple]] where: +- $K$ represent the vertical stiffness of the actuator +- $C$ represent the vertical damping of the actuator +- $F$ represents the force applied by the actuator +- $F_{m}$ represents the total measured force +- $v_{m}$ represents the absolute velocity of the top part of the actuator +- $d_{m}$ represents the total relative displacement of the actuator + +#+begin_src latex :file actuator_model_simple.pdf :tangle no + \begin{tikzpicture} + \draw (-1, 0) -- (1, 0); + + % Spring, Damper, and Actuator + \draw[spring] (-1, 0) -- (-1, 1.5) node[midway, left=0.1]{$K$}; + \draw[damper] ( 0, 0) -- ( 0, 1.5) node[midway, left=0.2]{$C$}; + \draw[actuator] ( 1, 0) -- ( 1, 1.5) node[midway, left=0.1](F){$F$}; + + \node[forcesensor={2}{0.2}] (fsens) at (0, 1.5){}; + + \node[left] at (fsens.west) {$F_{m}$}; + + \draw[dashed] (1, 0) -- ++(0.4, 0); + \draw[dashed] (1, 1.7) -- ++(0.4, 0); + + \draw[->] (0, 1.7)node[]{$\bullet$} -- ++(0, 0.5) node[right]{$v_{m}$}; + + \draw[<->] (1.4, 0) -- ++(0, 1.7) node[midway, right]{$d_{m}$}; + \end{tikzpicture} +#+end_src + +#+name: fig:actuator_model_simple +#+caption: Simple model of an Actuator +#+RESULTS: +[[file:figs/actuator_model_simple.png]] + +*** Function description +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + function [stewart] = initializeStrutDynamics(stewart, args) + % initializeStrutDynamics - Add Stiffness and Damping properties of each strut + % + % Syntax: [stewart] = initializeStrutDynamics(args) + % + % Inputs: + % - args - Structure with the following fields: + % - K [6x1] - Stiffness of each strut [N/m] + % - C [6x1] - Damping of each strut [N/(m/s)] + % + % Outputs: + % - stewart - updated Stewart structure with the added fields: + % - actuators.type = 1 + % - actuators.K [6x1] - Stiffness of each strut [N/m] + % - actuators.C [6x1] - Damping of each strut [N/(m/s)] +#+end_src + +*** Optional Parameters +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + arguments + stewart + args.type char {mustBeMember(args.type,{'classical', 'amplified'})} = 'classical' + args.K (6,1) double {mustBeNumeric, mustBeNonnegative} = 20e6*ones(6,1) + args.C (6,1) double {mustBeNumeric, mustBeNonnegative} = 2e1*ones(6,1) + args.k1 (6,1) double {mustBeNumeric} = 1e6*ones(6,1) + args.ke (6,1) double {mustBeNumeric} = 5e6*ones(6,1) + args.ka (6,1) double {mustBeNumeric} = 60e6*ones(6,1) + args.c1 (6,1) double {mustBeNumeric} = 10*ones(6,1) + args.F_gain (6,1) double {mustBeNumeric} = 1*ones(6,1) + args.me (6,1) double {mustBeNumeric} = 0.01*ones(6,1) + args.ma (6,1) double {mustBeNumeric} = 0.01*ones(6,1) + end +#+end_src + +*** Add Stiffness and Damping properties of each strut +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + if strcmp(args.type, 'classical') + stewart.actuators.type = 1; + elseif strcmp(args.type, 'amplified') + stewart.actuators.type = 2; + end + + stewart.actuators.K = args.K; + stewart.actuators.C = args.C; + + stewart.actuators.k1 = args.k1; + stewart.actuators.c1 = args.c1; + + stewart.actuators.ka = args.ka; + stewart.actuators.ke = args.ke; + + stewart.actuators.F_gain = args.F_gain; + + stewart.actuators.ma = args.ma; + stewart.actuators.me = args.me; +#+end_src + +** =initializeJointDynamics=: Add Stiffness and Damping properties for spherical joints +:PROPERTIES: +:header-args:matlab+: :tangle matlab/src/initializeJointDynamics.m +:header-args:matlab+: :comments none :mkdirp yes :eval no +:END: + +*** Function description +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + function [stewart] = initializeJointDynamics(stewart, args) + % initializeJointDynamics - Add Stiffness and Damping properties for the spherical joints + % + % Syntax: [stewart] = initializeJointDynamics(args) + % + % Inputs: + % - args - Structure with the following fields: + % - type_F - 'universal', 'spherical', 'universal_p', 'spherical_p' + % - type_M - 'universal', 'spherical', 'universal_p', 'spherical_p' + % - Kf_M [6x1] - Bending (Rx, Ry) Stiffness for each top joints [(N.m)/rad] + % - Kt_M [6x1] - Torsion (Rz) Stiffness for each top joints [(N.m)/rad] + % - Cf_M [6x1] - Bending (Rx, Ry) Damping of each top joint [(N.m)/(rad/s)] + % - Ct_M [6x1] - Torsion (Rz) Damping of each top joint [(N.m)/(rad/s)] + % - Kf_F [6x1] - Bending (Rx, Ry) Stiffness for each bottom joints [(N.m)/rad] + % - Kt_F [6x1] - Torsion (Rz) Stiffness for each bottom joints [(N.m)/rad] + % - Cf_F [6x1] - Bending (Rx, Ry) Damping of each bottom joint [(N.m)/(rad/s)] + % - Cf_F [6x1] - Torsion (Rz) Damping of each bottom joint [(N.m)/(rad/s)] + % + % Outputs: + % - stewart - updated Stewart structure with the added fields: + % - stewart.joints_F and stewart.joints_M: + % - type - 1 (universal), 2 (spherical), 3 (universal perfect), 4 (spherical perfect) + % - Kx, Ky, Kz [6x1] - Translation (Tx, Ty, Tz) Stiffness [N/m] + % - Kf [6x1] - Flexion (Rx, Ry) Stiffness [(N.m)/rad] + % - Kt [6x1] - Torsion (Rz) Stiffness [(N.m)/rad] + % - Cx, Cy, Cz [6x1] - Translation (Rx, Ry) Damping [N/(m/s)] + % - Cf [6x1] - Flexion (Rx, Ry) Damping [(N.m)/(rad/s)] + % - Cb [6x1] - Torsion (Rz) Damping [(N.m)/(rad/s)] +#+end_src + +*** Optional Parameters +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + arguments + stewart + args.type_F char {mustBeMember(args.type_F,{'universal', 'spherical', 'universal_p', 'spherical_p', 'universal_3dof', 'spherical_3dof', 'flexible'})} = 'universal' + args.type_M char {mustBeMember(args.type_M,{'universal', 'spherical', 'universal_p', 'spherical_p', 'universal_3dof', 'spherical_3dof', 'flexible'})} = 'spherical' + args.Kf_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 33*ones(6,1) + args.Cf_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-4*ones(6,1) + args.Kt_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 236*ones(6,1) + args.Ct_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-3*ones(6,1) + args.Kf_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 33*ones(6,1) + args.Cf_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-4*ones(6,1) + args.Kt_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 236*ones(6,1) + args.Ct_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e-3*ones(6,1) + args.Ka_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1.2e8*ones(6,1) + args.Ca_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e1*ones(6,1) + args.Kr_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1.1e7*ones(6,1) + args.Cr_F (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e1*ones(6,1) + args.Ka_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1.2e8*ones(6,1) + args.Ca_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e1*ones(6,1) + args.Kr_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1.1e7*ones(6,1) + args.Cr_M (6,1) double {mustBeNumeric, mustBeNonnegative} = 1e1*ones(6,1) + args.K_M double {mustBeNumeric} = zeros(6,6) + args.M_M double {mustBeNumeric} = zeros(6,6) + args.n_xyz_M double {mustBeNumeric} = zeros(2,3) + args.xi_M double {mustBeNumeric} = 0.1 + args.step_file_M char {} = '' + args.K_F double {mustBeNumeric} = zeros(6,6) + args.M_F double {mustBeNumeric} = zeros(6,6) + args.n_xyz_F double {mustBeNumeric} = zeros(2,3) + args.xi_F double {mustBeNumeric} = 0.1 + args.step_file_F char {} = '' + end +#+end_src + +*** Add Actuator Type +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + switch args.type_F + case 'universal' + stewart.joints_F.type = 1; + case 'spherical' + stewart.joints_F.type = 2; + case 'universal_p' + stewart.joints_F.type = 3; + case 'spherical_p' + stewart.joints_F.type = 4; + case 'flexible' + stewart.joints_F.type = 5; + case 'universal_3dof' + stewart.joints_F.type = 6; + case 'spherical_3dof' + stewart.joints_F.type = 7; + end + + switch args.type_M + case 'universal' + stewart.joints_M.type = 1; + case 'spherical' + stewart.joints_M.type = 2; + case 'universal_p' + stewart.joints_M.type = 3; + case 'spherical_p' + stewart.joints_M.type = 4; + case 'flexible' + stewart.joints_M.type = 5; + case 'universal_3dof' + stewart.joints_M.type = 6; + case 'spherical_3dof' + stewart.joints_M.type = 7; + end +#+end_src + +*** Add Stiffness and Damping in Translation of each strut +:PROPERTIES: +:UNNUMBERED: t +:END: +Axial and Radial (shear) Stiffness +#+begin_src matlab + stewart.joints_M.Ka = args.Ka_M; + stewart.joints_M.Kr = args.Kr_M; + + stewart.joints_F.Ka = args.Ka_F; + stewart.joints_F.Kr = args.Kr_F; +#+end_src + +Translation Damping +#+begin_src matlab + stewart.joints_M.Ca = args.Ca_M; + stewart.joints_M.Cr = args.Cr_M; + + stewart.joints_F.Ca = args.Ca_F; + stewart.joints_F.Cr = args.Cr_F; +#+end_src + +*** Add Stiffness and Damping in Rotation of each strut +:PROPERTIES: +:UNNUMBERED: t +:END: +Rotational Stiffness +#+begin_src matlab + stewart.joints_M.Kf = args.Kf_M; + stewart.joints_M.Kt = args.Kt_M; + + stewart.joints_F.Kf = args.Kf_F; + stewart.joints_F.Kt = args.Kt_F; +#+end_src + +Rotational Damping +#+begin_src matlab + stewart.joints_M.Cf = args.Cf_M; + stewart.joints_M.Ct = args.Ct_M; + + stewart.joints_F.Cf = args.Cf_F; + stewart.joints_F.Ct = args.Ct_F; +#+end_src + +*** Stiffness and Mass matrices for flexible joint +:PROPERTIES: +:UNNUMBERED: t +:END: + +#+begin_src matlab + stewart.joints_F.M = args.M_F; + stewart.joints_F.K = args.K_F; + stewart.joints_F.n_xyz = args.n_xyz_F; + stewart.joints_F.xi = args.xi_F; + stewart.joints_F.xi = args.xi_F; + stewart.joints_F.step_file = args.step_file_F; + + stewart.joints_M.M = args.M_M; + stewart.joints_M.K = args.K_M; + stewart.joints_M.n_xyz = args.n_xyz_M; + stewart.joints_M.xi = args.xi_M; + stewart.joints_M.step_file = args.step_file_M; +#+end_src + +** =initializeStewartPose=: Determine the initial stroke in each leg to have the wanted pose +:PROPERTIES: +:header-args:matlab+: :tangle matlab/src/initializeStewartPose.m +:header-args:matlab+: :comments none :mkdirp yes :eval no +:END: + +*** Function description +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + function [stewart] = initializeStewartPose(stewart, args) + % initializeStewartPose - Determine the initial stroke in each leg to have the wanted pose + % It uses the inverse kinematic + % + % Syntax: [stewart] = initializeStewartPose(stewart, args) + % + % Inputs: + % - stewart - A structure with the following fields + % - Aa [3x6] - The positions ai expressed in {A} + % - Bb [3x6] - The positions bi expressed in {B} + % - args - Can have the following fields: + % - AP [3x1] - The wanted position of {B} with respect to {A} + % - ARB [3x3] - The rotation matrix that gives the wanted orientation of {B} with respect to {A} + % + % Outputs: + % - stewart - updated Stewart structure with the added fields: + % - actuators.Leq [6x1] - The 6 needed displacement of the struts from the initial position in [m] to have the wanted pose of {B} w.r.t. {A} +#+end_src + +*** Optional Parameters +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + arguments + stewart + args.AP (3,1) double {mustBeNumeric} = zeros(3,1) + args.ARB (3,3) double {mustBeNumeric} = eye(3) + end +#+end_src + +*** Use the Inverse Kinematic function +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + [Li, dLi] = inverseKinematics(stewart, 'AP', args.AP, 'ARB', args.ARB); +#+end_src + +*** Populate the =stewart= structure +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + stewart.actuators.Leq = dLi; +#+end_src + +** =computeJacobian=: Compute the Jacobian Matrix +:PROPERTIES: +:header-args:matlab+: :tangle matlab/src/computeJacobian.m +:header-args:matlab+: :comments none :mkdirp yes :eval no +:END: + +*** Function description +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + function [stewart] = computeJacobian(stewart) + % computeJacobian - + % + % Syntax: [stewart] = computeJacobian(stewart) + % + % Inputs: + % - stewart - With at least the following fields: + % - geometry.As [3x6] - The 6 unit vectors for each strut expressed in {A} + % - geometry.Ab [3x6] - The 6 position of the joints bi expressed in {A} + % - actuators.K [6x1] - Total stiffness of the actuators + % + % Outputs: + % - stewart - With the 3 added field: + % - kinematics.J [6x6] - The Jacobian Matrix + % - kinematics.K [6x6] - The Stiffness Matrix + % - kinematics.C [6x6] - The Compliance Matrix +#+end_src + +*** Check the =stewart= structure elements +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + assert(isfield(stewart.geometry, 'As'), 'stewart.geometry should have attribute As') + As = stewart.geometry.As; + + assert(isfield(stewart.geometry, 'Ab'), 'stewart.geometry should have attribute Ab') + Ab = stewart.geometry.Ab; + + assert(isfield(stewart.actuators, 'K'), 'stewart.actuators should have attribute K') + Ki = stewart.actuators.K; +#+end_src + + +*** Compute Jacobian Matrix +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + J = [As' , cross(Ab, As)']; +#+end_src + +*** Compute Stiffness Matrix +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + K = J'*diag(Ki)*J; +#+end_src + +*** Compute Compliance Matrix +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + C = inv(K); +#+end_src + +*** Populate the =stewart= structure +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + stewart.kinematics.J = J; + stewart.kinematics.K = K; + stewart.kinematics.C = C; +#+end_src + +** =initializeInertialSensor=: Initialize the inertial sensor in each strut +:PROPERTIES: +:header-args:matlab+: :tangle matlab/src/initializeInertialSensor.m +:header-args:matlab+: :comments none :mkdirp yes :eval no +:END: + +*** Geophone - Working Principle +:PROPERTIES: +:UNNUMBERED: t +:END: +From the schematic of the Z-axis geophone shown in Figure [[fig:z_axis_geophone]], we can write the transfer function from the support velocity $\dot{w}$ to the relative velocity of the inertial mass $\dot{d}$: +\[ \frac{\dot{d}}{\dot{w}} = \frac{-\frac{s^2}{{\omega_0}^2}}{\frac{s^2}{{\omega_0}^2} + 2 \xi \frac{s}{\omega_0} + 1} \] +with: +- $\omega_0 = \sqrt{\frac{k}{m}}$ +- $\xi = \frac{1}{2} \sqrt{\frac{m}{k}}$ + +#+name: fig:z_axis_geophone +#+caption: Schematic of a Z-Axis geophone +[[file:figs/inertial_sensor.png]] + +We see that at frequencies above $\omega_0$: +\[ \frac{\dot{d}}{\dot{w}} \approx -1 \] + +And thus, the measurement of the relative velocity of the mass with respect to its support gives the absolute velocity of the support. + +We generally want to have the smallest resonant frequency $\omega_0$ to measure low frequency absolute velocity, however there is a trade-off between $\omega_0$ and the mass of the inertial mass. + +*** Accelerometer - Working Principle +:PROPERTIES: +:UNNUMBERED: t +:END: +From the schematic of the Z-axis accelerometer shown in Figure [[fig:z_axis_accelerometer]], we can write the transfer function from the support acceleration $\ddot{w}$ to the relative position of the inertial mass $d$: +\[ \frac{d}{\ddot{w}} = \frac{-\frac{1}{{\omega_0}^2}}{\frac{s^2}{{\omega_0}^2} + 2 \xi \frac{s}{\omega_0} + 1} \] +with: +- $\omega_0 = \sqrt{\frac{k}{m}}$ +- $\xi = \frac{1}{2} \sqrt{\frac{m}{k}}$ + +#+name: fig:z_axis_accelerometer +#+caption: Schematic of a Z-Axis geophone +[[file:figs/inertial_sensor.png]] + +We see that at frequencies below $\omega_0$: +\[ \frac{d}{\ddot{w}} \approx -\frac{1}{{\omega_0}^2} \] + +And thus, the measurement of the relative displacement of the mass with respect to its support gives the absolute acceleration of the support. + +Note that there is trade-off between: +- the highest measurable acceleration $\omega_0$ +- the sensitivity of the accelerometer which is equal to $-\frac{1}{{\omega_0}^2}$ + +*** Function description +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + function [stewart] = initializeInertialSensor(stewart, args) + % initializeInertialSensor - Initialize the inertial sensor in each strut + % + % Syntax: [stewart] = initializeInertialSensor(args) + % + % Inputs: + % - args - Structure with the following fields: + % - type - 'geophone', 'accelerometer', 'none' + % - mass [1x1] - Weight of the inertial mass [kg] + % - freq [1x1] - Cutoff frequency [Hz] + % + % Outputs: + % - stewart - updated Stewart structure with the added fields: + % - stewart.sensors.inertial + % - type - 1 (geophone), 2 (accelerometer), 3 (none) + % - K [1x1] - Stiffness [N/m] + % - C [1x1] - Damping [N/(m/s)] + % - M [1x1] - Inertial Mass [kg] + % - G [1x1] - Gain +#+end_src + +*** Optional Parameters +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + arguments + stewart + args.type char {mustBeMember(args.type,{'geophone', 'accelerometer', 'none'})} = 'none' + args.mass (1,1) double {mustBeNumeric, mustBeNonnegative} = 1e-2 + args.freq (1,1) double {mustBeNumeric, mustBeNonnegative} = 1e3 + end +#+end_src + +*** Compute the properties of the sensor +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + sensor = struct(); + + switch args.type + case 'geophone' + sensor.type = 1; + + sensor.M = args.mass; + sensor.K = sensor.M * (2*pi*args.freq)^2; + sensor.C = 2*sqrt(sensor.M * sensor.K); + case 'accelerometer' + sensor.type = 2; + + sensor.M = args.mass; + sensor.K = sensor.M * (2*pi*args.freq)^2; + sensor.C = 2*sqrt(sensor.M * sensor.K); + sensor.G = -sensor.K/sensor.M; + case 'none' + sensor.type = 3; + end +#+end_src + +*** Populate the =stewart= structure +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + stewart.sensors.inertial = sensor; +#+end_src + + + +** =inverseKinematics=: Compute Inverse Kinematics +:PROPERTIES: +:header-args:matlab+: :tangle matlab/src/inverseKinematics.m +:header-args:matlab+: :comments none :mkdirp yes :eval no +:END: + +*** Theory +:PROPERTIES: +:UNNUMBERED: t +:END: +For inverse kinematic analysis, it is assumed that the position ${}^A\bm{P}$ and orientation of the moving platform ${}^A\bm{R}_B$ are given and the problem is to obtain the joint variables, namely, $\bm{L} = [l_1, l_2, \dots, l_6]^T$. + +From the geometry of the manipulator, the loop closure for each limb, $i = 1, 2, \dots, 6$ can be written as +\begin{align*} + l_i {}^A\hat{\bm{s}}_i &= {}^A\bm{A} + {}^A\bm{b}_i - {}^A\bm{a}_i \\ + &= {}^A\bm{A} + {}^A\bm{R}_b {}^B\bm{b}_i - {}^A\bm{a}_i +\end{align*} + +To obtain the length of each actuator and eliminate $\hat{\bm{s}}_i$, it is sufficient to dot multiply each side by itself: +\begin{equation} + l_i^2 \left[ {}^A\hat{\bm{s}}_i^T {}^A\hat{\bm{s}}_i \right] = \left[ {}^A\bm{P} + {}^A\bm{R}_B {}^B\bm{b}_i - {}^A\bm{a}_i \right]^T \left[ {}^A\bm{P} + {}^A\bm{R}_B {}^B\bm{b}_i - {}^A\bm{a}_i \right] +\end{equation} + +Hence, for $i = 1, 2, \dots, 6$, each limb length can be uniquely determined by: +\begin{equation} + l_i = \sqrt{{}^A\bm{P}^T {}^A\bm{P} + {}^B\bm{b}_i^T {}^B\bm{b}_i + {}^A\bm{a}_i^T {}^A\bm{a}_i - 2 {}^A\bm{P}^T {}^A\bm{a}_i + 2 {}^A\bm{P}^T \left[{}^A\bm{R}_B {}^B\bm{b}_i\right] - 2 \left[{}^A\bm{R}_B {}^B\bm{b}_i\right]^T {}^A\bm{a}_i} +\end{equation} + +If the position and orientation of the moving platform lie in the feasible workspace of the manipulator, one unique solution to the limb length is determined by the above equation. +Otherwise, when the limbs' lengths derived yield complex numbers, then the position or orientation of the moving platform is not reachable. + +*** Function description +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + function [Li, dLi] = inverseKinematics(stewart, args) + % inverseKinematics - Compute the needed length of each strut to have the wanted position and orientation of {B} with respect to {A} + % + % Syntax: [stewart] = inverseKinematics(stewart) + % + % Inputs: + % - stewart - A structure with the following fields + % - geometry.Aa [3x6] - The positions ai expressed in {A} + % - geometry.Bb [3x6] - The positions bi expressed in {B} + % - geometry.l [6x1] - Length of each strut + % - args - Can have the following fields: + % - AP [3x1] - The wanted position of {B} with respect to {A} + % - ARB [3x3] - The rotation matrix that gives the wanted orientation of {B} with respect to {A} + % + % Outputs: + % - Li [6x1] - The 6 needed length of the struts in [m] to have the wanted pose of {B} w.r.t. {A} + % - dLi [6x1] - The 6 needed displacement of the struts from the initial position in [m] to have the wanted pose of {B} w.r.t. {A} +#+end_src + +*** Optional Parameters +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + arguments + stewart + args.AP (3,1) double {mustBeNumeric} = zeros(3,1) + args.ARB (3,3) double {mustBeNumeric} = eye(3) + end +#+end_src + +*** Check the =stewart= structure elements +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + assert(isfield(stewart.geometry, 'Aa'), 'stewart.geometry should have attribute Aa') + Aa = stewart.geometry.Aa; + + assert(isfield(stewart.geometry, 'Bb'), 'stewart.geometry should have attribute Bb') + Bb = stewart.geometry.Bb; + + assert(isfield(stewart.geometry, 'l'), 'stewart.geometry should have attribute l') + l = stewart.geometry.l; +#+end_src + + +*** Compute +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + Li = sqrt(args.AP'*args.AP + diag(Bb'*Bb) + diag(Aa'*Aa) - (2*args.AP'*Aa)' + (2*args.AP'*(args.ARB*Bb))' - diag(2*(args.ARB*Bb)'*Aa)); +#+end_src + +#+begin_src matlab + dLi = Li-l; +#+end_src + +** =describeMicroStationSetup= +:PROPERTIES: +:header-args:matlab+: :tangle matlab/src/describeMicroStationSetup.m +:header-args:matlab+: :comments none :mkdirp yes :eval no +:END: + +*** Function description +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + function [] = describeMicroStationSetup() + % describeMicroStationSetup - + % + % Syntax: [] = describeMicroStationSetup() + % + % Inputs: + % - - + % + % Outputs: + % - - +#+end_src + +*** Simscape Configuration +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + load('./mat/conf_simscape.mat', 'conf_simscape'); +#+end_src + +#+begin_src matlab + fprintf('Simscape Configuration:\n'); + + if conf_simscape.type == 1 + fprintf('- Gravity is included\n'); + else + fprintf('- Gravity is not included\n'); + end + + fprintf('\n'); +#+end_src + +*** Disturbances +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + load('./mat/nass_disturbances.mat', 'args'); +#+end_src + +#+begin_src matlab + fprintf('Disturbances:\n'); + if ~args.enable + fprintf('- No disturbance is included\n'); + else + if args.Dwx && args.Dwy && args.Dwz + fprintf('- Ground motion\n'); + end + if args.Fty_x && args.Fty_z + fprintf('- Vibrations of the Translation Stage\n'); + end + if args.Frz_z + fprintf('- Vibrations of the Spindle\n'); + end + end + fprintf('\n'); +#+end_src + +*** References +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + load('./mat/nass_references.mat', 'args'); +#+end_src + +#+begin_src matlab + fprintf('Reference Tracking:\n'); + fprintf('- Translation Stage:\n'); + switch args.Dy_type + case 'constant' + fprintf(' - Constant Position\n'); + fprintf(' - Dy = %.0f [mm]\n', args.Dy_amplitude*1e3); + case 'triangular' + fprintf(' - Triangular Path\n'); + fprintf(' - Amplitude = %.0f [mm]\n', args.Dy_amplitude*1e3); + fprintf(' - Period = %.0f [s]\n', args.Dy_period); + case 'sinusoidal' + fprintf(' - Sinusoidal Path\n'); + fprintf(' - Amplitude = %.0f [mm]\n', args.Dy_amplitude*1e3); + fprintf(' - Period = %.0f [s]\n', args.Dy_period); + end + + fprintf('- Tilt Stage:\n'); + switch args.Ry_type + case 'constant' + fprintf(' - Constant Position\n'); + fprintf(' - Ry = %.0f [mm]\n', args.Ry_amplitude*1e3); + case 'triangular' + fprintf(' - Triangular Path\n'); + fprintf(' - Amplitude = %.0f [mm]\n', args.Ry_amplitude*1e3); + fprintf(' - Period = %.0f [s]\n', args.Ry_period); + case 'sinusoidal' + fprintf(' - Sinusoidal Path\n'); + fprintf(' - Amplitude = %.0f [mm]\n', args.Ry_amplitude*1e3); + fprintf(' - Period = %.0f [s]\n', args.Ry_period); + end + + fprintf('- Spindle:\n'); + switch args.Rz_type + case 'constant' + fprintf(' - Constant Position\n'); + fprintf(' - Rz = %.0f [deg]\n', 180/pi*args.Rz_amplitude); + case { 'rotating', 'rotating-not-filtered' } + fprintf(' - Rotating\n'); + fprintf(' - Speed = %.0f [rpm]\n', 60/args.Rz_period); + end + + + fprintf('- Micro Hexapod:\n'); + switch args.Dh_type + case 'constant' + fprintf(' - Constant Position\n'); + fprintf(' - Dh = %.0f, %.0f, %.0f [mm]\n', args.Dh_pos(1), args.Dh_pos(2), args.Dh_pos(3)); + fprintf(' - Rh = %.0f, %.0f, %.0f [deg]\n', args.Dh_pos(4), args.Dh_pos(5), args.Dh_pos(6)); + end + + fprintf('\n'); +#+end_src + +*** Controller +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + load('./mat/controller.mat', 'controller'); +#+end_src + +#+begin_src matlab + fprintf('Controller:\n'); + fprintf('- %s\n', controller.name); + fprintf('\n'); +#+end_src + +*** Micro-Station +:PROPERTIES: +:UNNUMBERED: t +:END: +#+begin_src matlab + load('./mat/stages.mat', 'ground', 'granite', 'ty', 'ry', 'rz', 'micro_hexapod', 'axisc'); +#+end_src + +#+begin_src matlab + fprintf('Micro Station:\n'); + + if granite.type == 1 && ... + ty.type == 1 && ... + ry.type == 1 && ... + rz.type == 1 && ... + micro_hexapod.type == 1; + fprintf('- All stages are rigid\n'); + elseif granite.type == 2 && ... + ty.type == 2 && ... + ry.type == 2 && ... + rz.type == 2 && ... + micro_hexapod.type == 2; + fprintf('- All stages are flexible\n'); + else + if granite.type == 1 || granite.type == 4 + fprintf('- Granite is rigid\n'); + else + fprintf('- Granite is flexible\n'); + end + if ty.type == 1 || ty.type == 4 + fprintf('- Translation Stage is rigid\n'); + else + fprintf('- Translation Stage is flexible\n'); + end + if ry.type == 1 || ry.type == 4 + fprintf('- Tilt Stage is rigid\n'); + else + fprintf('- Tilt Stage is flexible\n'); + end + if rz.type == 1 || rz.type == 4 + fprintf('- Spindle is rigid\n'); + else + fprintf('- Spindle is flexible\n'); + end + if micro_hexapod.type == 1 || micro_hexapod.type == 4 + fprintf('- Micro Hexapod is rigid\n'); + else + fprintf('- Micro Hexapod is flexible\n'); + end + + end + + fprintf('\n'); +#+end_src + +** =computeReferencePose= +:PROPERTIES: +:header-args:matlab+: :tangle matlab/src/computeReferencePose.m :header-args:matlab+: :comments none :mkdirp yes :eval no :END: #+begin_src matlab - function [geophone] = initializeZAxisGeophone(args) - arguments - args.mass (1,1) double {mustBeNumeric, mustBePositive} = 1e-3 % [kg] - args.freq (1,1) double {mustBeNumeric, mustBePositive} = 1 % [Hz] - end + function [WTr] = computeReferencePose(Dy, Ry, Rz, Dh, Dn) + % computeReferencePose - Compute the homogeneous transformation matrix corresponding to the wanted pose of the sample + % + % Syntax: [WTr] = computeReferencePose(Dy, Ry, Rz, Dh, Dn) + % + % Inputs: + % - Dy - Reference of the Translation Stage [m] + % - Ry - Reference of the Tilt Stage [rad] + % - Rz - Reference of the Spindle [rad] + % - Dh - Reference of the Micro Hexapod (Pitch, Roll, Yaw angles) [m, m, m, rad, rad, rad] + % - Dn - Reference of the Nano Hexapod [m, m, m, rad, rad, rad] + % + % Outputs: + % - WTr - - %% - geophone.m = args.mass; + %% Translation Stage + Rty = [1 0 0 0; + 0 1 0 Dy; + 0 0 1 0; + 0 0 0 1]; - %% The Stiffness is set to have the damping resonance frequency - geophone.k = geophone.m * (2*pi*args.freq)^2; + %% Tilt Stage - Pure rotating aligned with Ob + Rry = [ cos(Ry) 0 sin(Ry) 0; + 0 1 0 0; + -sin(Ry) 0 cos(Ry) 0; + 0 0 0 1]; - %% We set the damping value to have critical damping - geophone.c = 2*sqrt(geophone.m * geophone.k); -#+end_src - -#+begin_src matlab -if exist('./mat', 'dir') - if exist('./mat/geophone_z_axis.mat', 'file') - save('mat/geophone_z_axis.mat', 'geophone', '-append'); - else - save('mat/geophone_z_axis.mat', 'geophone'); - end -elseif exist('./matlab', 'dir') - if exist('./matlab/mat/geophone_z_axis.mat', 'file') - save('matlab/mat/geophone_z_axis.mat', 'geophone', '-append'); - else - save('matlab/mat/geophone_z_axis.mat', 'geophone'); - end -end -#+end_src + %% Spindle - Rotation along the Z axis + Rrz = [cos(Rz) -sin(Rz) 0 0 ; + sin(Rz) cos(Rz) 0 0 ; + 0 0 1 0 ; + 0 0 0 1 ]; -** Z-Axis Accelerometer -:PROPERTIES: -:header-args:matlab+: :tangle matlab/src/initializeZAxisAccelerometer.m -:header-args:matlab+: :comments none :mkdirp yes :eval no -:END: + %% Micro-Hexapod + Rhx = [1 0 0; + 0 cos(Dh(4)) -sin(Dh(4)); + 0 sin(Dh(4)) cos(Dh(4))]; -#+begin_src matlab - function [accelerometer] = initializeZAxisAccelerometer(args) - arguments - args.mass (1,1) double {mustBeNumeric, mustBePositive} = 1e-3 % [kg] - args.freq (1,1) double {mustBeNumeric, mustBePositive} = 5e3 % [Hz] - end + Rhy = [ cos(Dh(5)) 0 sin(Dh(5)); + 0 1 0; + -sin(Dh(5)) 0 cos(Dh(5))]; - %% - accelerometer.m = args.mass; + Rhz = [cos(Dh(6)) -sin(Dh(6)) 0; + sin(Dh(6)) cos(Dh(6)) 0; + 0 0 1]; - %% The Stiffness is set to have the damping resonance frequency - accelerometer.k = accelerometer.m * (2*pi*args.freq)^2; + Rh = [1 0 0 Dh(1) ; + 0 1 0 Dh(2) ; + 0 0 1 Dh(3) ; + 0 0 0 1 ]; - %% We set the damping value to have critical damping - accelerometer.c = 2*sqrt(accelerometer.m * accelerometer.k); + Rh(1:3, 1:3) = Rhz*Rhy*Rhx; - %% Gain correction of the accelerometer to have a unity gain until the resonance - accelerometer.gain = -accelerometer.k/accelerometer.m; + %% Nano-Hexapod + Rnx = [1 0 0; + 0 cos(Dn(4)) -sin(Dn(4)); + 0 sin(Dn(4)) cos(Dn(4))]; -#+end_src + Rny = [ cos(Dn(5)) 0 sin(Dn(5)); + 0 1 0; + -sin(Dn(5)) 0 cos(Dn(5))]; -#+begin_src matlab -if exist('./mat', 'dir') - if exist('./mat/accelerometer_z_axis.mat', 'file') - save('mat/accelerometer_z_axis.mat', 'accelerometer', '-append'); - else - save('mat/accelerometer_z_axis.mat', 'accelerometer'); - end -elseif exist('./matlab', 'dir') - if exist('./matlab/mat/accelerometer_z_axis.mat', 'file') - save('matlab/mat/accelerometer_z_axis.mat', 'accelerometer', '-append'); - else - save('matlab/mat/accelerometer_z_axis.mat', 'accelerometer'); - end -end + Rnz = [cos(Dn(6)) -sin(Dn(6)) 0; + sin(Dn(6)) cos(Dn(6)) 0; + 0 0 1]; + + Rn = [1 0 0 Dn(1) ; + 0 1 0 Dn(2) ; + 0 0 1 Dn(3) ; + 0 0 0 1 ]; + + Rn(1:3, 1:3) = Rnz*Rny*Rnx; + + %% Total Homogeneous transformation + WTr = Rty*Rry*Rrz*Rh*Rn; + end #+end_src * Helping Functions :noexport: